mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-02-11 09:20:40 +00:00
feat: add ros2_control to Core URDF
This commit is contained in:
35
src/core_rover_description/config/ros2_controllers.yaml
Normal file
35
src/core_rover_description/config/ros2_controllers.yaml
Normal file
@@ -0,0 +1,35 @@
|
|||||||
|
controller_manager:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 10
|
||||||
|
use_sim_time: true
|
||||||
|
|
||||||
|
diff_controller:
|
||||||
|
type: "diff_drive_controller/DiffDriveController"
|
||||||
|
|
||||||
|
joint_broadcaster:
|
||||||
|
type: "joint_state_broadcaster/JointStateBroadcaster"
|
||||||
|
|
||||||
|
diff_controller:
|
||||||
|
ros__parameters:
|
||||||
|
left_wheel_names: ["bl_wheel_joint", "fl_wheel_joint"]
|
||||||
|
right_wheel_names: ["br_wheel_joint", "fr_wheel_joint"]
|
||||||
|
|
||||||
|
wheel_separation: 0.836
|
||||||
|
wheels_per_side: 2
|
||||||
|
wheel_radius: 0.171
|
||||||
|
|
||||||
|
base_frame_id: "base_link"
|
||||||
|
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
|
||||||
|
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
|
||||||
|
|
||||||
|
position_feedback: true
|
||||||
|
open_loop: false
|
||||||
|
enable_odom_tf: true
|
||||||
|
|
||||||
|
cmd_vel_timeout: 0.5
|
||||||
|
publish_limited_velocity: false
|
||||||
|
|
||||||
|
use_stamped_vel: false
|
||||||
|
publish_rate: 10.0
|
||||||
|
|
||||||
|
# TODO: add reasonable velocity and acceleration limits
|
||||||
@@ -21,7 +21,7 @@ def generate_launch_description():
|
|||||||
default_rviz_config_path = os.path.join(pkg_share, 'config/rviz_basic_settings.rviz')
|
default_rviz_config_path = os.path.join(pkg_share, 'config/rviz_basic_settings.rviz')
|
||||||
|
|
||||||
# Set the path to the URDF file
|
# Set the path to the URDF file
|
||||||
default_urdf_model_path = os.path.join(pkg_share, 'urdf/core_rover_description.urdf')
|
default_urdf_model_path = os.path.join(pkg_share, 'urdf/core_rover_description.xacro')
|
||||||
|
|
||||||
########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ##############
|
########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ##############
|
||||||
# Launch configuration variables specific to simulation
|
# Launch configuration variables specific to simulation
|
||||||
|
|||||||
@@ -115,7 +115,7 @@ def generate_launch_description():
|
|||||||
"""
|
"""
|
||||||
# Define filenames
|
# Define filenames
|
||||||
urdf_package = 'core_rover_description'
|
urdf_package = 'core_rover_description'
|
||||||
urdf_filename = 'core_rover_description.urdf'
|
urdf_filename = 'core_rover_description.xacro'
|
||||||
rviz_config_filename = 'rviz_basic_settings.rviz'
|
rviz_config_filename = 'rviz_basic_settings.rviz'
|
||||||
|
|
||||||
# Set paths to important files
|
# Set paths to important files
|
||||||
@@ -233,6 +233,6 @@ def generate_launch_description():
|
|||||||
ld.add_action(start_joint_state_publisher_cmd)
|
ld.add_action(start_joint_state_publisher_cmd)
|
||||||
ld.add_action(start_joint_state_publisher_gui_cmd)
|
ld.add_action(start_joint_state_publisher_gui_cmd)
|
||||||
ld.add_action(start_robot_state_publisher_cmd)
|
ld.add_action(start_robot_state_publisher_cmd)
|
||||||
ld.add_action(start_rviz_cmd)
|
# ld.add_action(start_rviz_cmd)
|
||||||
|
|
||||||
return ld
|
return ld
|
||||||
|
|||||||
@@ -152,7 +152,7 @@
|
|||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint
|
<joint
|
||||||
name="br_wheel_axis"
|
name="br_wheel_joint"
|
||||||
type="continuous">
|
type="continuous">
|
||||||
<origin
|
<origin
|
||||||
xyz="-0.41838 -0.17155 0.12984"
|
xyz="-0.41838 -0.17155 0.12984"
|
||||||
@@ -162,7 +162,7 @@
|
|||||||
<child
|
<child
|
||||||
link="br_wheel" />
|
link="br_wheel" />
|
||||||
<axis
|
<axis
|
||||||
xyz="1 0 0" />
|
xyz="-1 0 0" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
@@ -217,7 +217,7 @@
|
|||||||
<child
|
<child
|
||||||
link="fr_wheel" />
|
link="fr_wheel" />
|
||||||
<axis
|
<axis
|
||||||
xyz="1 0 0" />
|
xyz="-1 0 0" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
@@ -262,7 +262,7 @@
|
|||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint
|
<joint
|
||||||
name="averaging_bar_axis"
|
name="averaging_bar_joint"
|
||||||
type="revolute">
|
type="revolute">
|
||||||
<origin
|
<origin
|
||||||
xyz="0 -0.23362 -0.0508"
|
xyz="0 -0.23362 -0.0508"
|
||||||
@@ -0,0 +1,8 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="core_rover">
|
||||||
|
|
||||||
|
<xacro:include filename="core_rover.urdf"/>
|
||||||
|
|
||||||
|
<xacro:include filename="ros2_control.xacro"/>
|
||||||
|
|
||||||
|
</robot>
|
||||||
36
src/core_rover_description/urdf/ros2_control.xacro
Normal file
36
src/core_rover_description/urdf/ros2_control.xacro
Normal file
@@ -0,0 +1,36 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<ros2_control name="GazeboSystem" type="system">
|
||||||
|
<hardware>
|
||||||
|
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||||
|
</hardware>
|
||||||
|
<joint name="bl_wheel_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="br_wheel_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="fl_wheel_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="fr_wheel_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
</joint>
|
||||||
|
</ros2_control>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
||||||
|
<parameters>$(find core_rover_description)/config/ros2_controllers.yaml</parameters>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
||||||
Reference in New Issue
Block a user