Skip to content

Commit

Permalink
Added gazebo controllers yaml
Browse files Browse the repository at this point in the history
  • Loading branch information
davidcalderon03 committed Nov 21, 2023
1 parent 4751747 commit c00cb18
Show file tree
Hide file tree
Showing 2 changed files with 71 additions and 3 deletions.
68 changes: 68 additions & 0 deletions urc_hw_description/config/gazebo_controllers.yaml
Original file line number Diff line number Diff line change
@@ -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:
6 changes: 3 additions & 3 deletions urc_hw_description/urdf/ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<!-- Gazebo Configuration -->
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Gazebo Configuration -->
<ros2_control name="GazeboSystem" type="system">
<hardware>
<!-- TODO make a launch param to switch between real/fake hardware. You can only use ONE. -->
Expand Down Expand Up @@ -232,8 +232,8 @@

<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>$(find urc_gazebo)/config/my_controllers.yaml</parameters>
<!-- Below is the one needed for the arm -->
<parameters>$(find urc_hw_description)/config/gazebo_controllers.yaml</parameters>
<!-- Below is the one needed for the arm (maybe) -->
<!-- <parameters>file://$(find urc_gazebo)/urdf/config/RoboticArm_params.yaml</parameters> -->
</plugin>
</gazebo>
Expand Down

0 comments on commit c00cb18

Please sign in to comment.