From c00cb189ca3660eac5775c46f33e137f0841659d Mon Sep 17 00:00:00 2001 From: davidcalderon03 Date: Mon, 20 Nov 2023 21:54:42 -0500 Subject: [PATCH] Added gazebo controllers yaml --- .../config/gazebo_controllers.yaml | 68 +++++++++++++++++++ urc_hw_description/urdf/ros2_control.xacro | 6 +- 2 files changed, 71 insertions(+), 3 deletions(-) create mode 100644 urc_hw_description/config/gazebo_controllers.yaml diff --git a/urc_hw_description/config/gazebo_controllers.yaml b/urc_hw_description/config/gazebo_controllers.yaml new file mode 100644 index 00000000..df381468 --- /dev/null +++ b/urc_hw_description/config/gazebo_controllers.yaml @@ -0,0 +1,68 @@ +controller_manager: + ros__parameters: + update_rate: 30 + use_sim_time: true + + diff_cont: + type: diff_drive_controller/DiffDriveController + + joint_broad: + type: joint_state_broadcaster/JointStateBroadcaster + +diff_cont: + ros__parameters: + + publish_rate: 50.0 + + base_frame_id: base_link + + left_wheel_names: ['left_front_wheel_joint', 'left_center_wheel_joint', 'left_rear_wheel_joint'] + right_wheel_names: ['right_front_wheel_joint', 'right_center_wheel_joint', 'right_rear_wheel_joint'] + wheel_separation: 0.05 + wheel_radius: 0.03 + + use_stamped_vel: false + + # open_loop: false + + wheels_per_side: 3 + # wheel_separation_multiplier: x + # left_wheel_radius_multiplier: x + # right_wheel_radius_multiplier: x + + # odom_frame_id: x + # pose_covariance_diagonal: x + # twist_covariance_diagonal: x + # open_loop: x + # enable_odom_tf: x + + # cmd_vel_timeout: x + # publish_limited_velocity: x + # velocity_rolling_window_size: x + + + # linear.x.has_velocity_limits: false + # linear.x.has_acceleration_limits: false + # linear.x.has_jerk_limits: false + # linear.x.max_velocity: NAN + # linear.x.min_velocity: NAN + # linear.x.max_acceleration: NAN + # linear.x.min_acceleration: NAN + # linear.x.max_jerk: NAN + # linear.x.min_jerk: NAN + + # angular.z.has_velocity_limits: false + # angular.z.has_acceleration_limits: false + # angular.z.has_jerk_limits: false + # angular.z.max_velocity: NAN + # angular.z.min_velocity: NAN + # angular.z.max_acceleration: NAN + # angular.z.min_acceleration: NAN + # angular.z.max_jerk: NAN + # angular.z.min_jerk: NAN + + + + +# joint_broad: +# ros__parameters: \ No newline at end of file diff --git a/urc_hw_description/urdf/ros2_control.xacro b/urc_hw_description/urdf/ros2_control.xacro index 8d458506..0220b858 100644 --- a/urc_hw_description/urdf/ros2_control.xacro +++ b/urc_hw_description/urdf/ros2_control.xacro @@ -1,6 +1,6 @@ - + @@ -232,8 +232,8 @@ - $(find urc_gazebo)/config/my_controllers.yaml - + $(find urc_hw_description)/config/gazebo_controllers.yaml +