controller_manager: ros__parameters: update_rate: 30 # Hz was 100 vefore joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster diffbot_base_controller: type: diff_drive_controller/DiffDriveController diffbot_base_controller: ros__parameters: # left_wheel_names: ["left_wheel_joint"] # right_wheel_names: ["right_wheel_joint"] right_wheel_names: ["left_wheel_joint"] # needed to switch names because motors are connected to the wrong slots left_wheel_names: ["right_wheel_joint"] wheel_separation: 0.28 #wheels_per_side: 1 # actually 2, but both are controlled by 1 signal wheel_radius: 0.065 wheel_separation_multiplier: 1.0 left_wheel_radius_multiplier: -1.0 right_wheel_radius_multiplier: 1.0 publish_rate: 50.0 # was 100 before odom_frame_id: odom 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] # pose_covariance_diagonal: # [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] # twist_covariance_diagonal: # [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml # Updated covariance matrix to small values on the diagonal axis for package ros_localization. This is recommended for diffdrive rorbots. pose_covariance_diagonal : [0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001] twist_covariance_diagonal: [0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001] open_loop: false enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) cmd_vel_timeout: 10.0 # was 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml # preserve turning radius when limiting speed/acceleration/jerk preserve_turning_radius: false # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml # Velocity and acceleration limits # Whenever a min_* is unspecified, default to -max_* # linear.x.has_velocity_limits: false # linear.x.has_acceleration_limits: false # linear.x.has_jerk_limits: false # linear.x.max_velocity: 2.0 # linear.x.min_velocity: -2.0 # linear.x.max_acceleration: 5.0 # linear.x.max_jerk: 0.0 # linear.x.min_jerk: 0.0 # angular.z.has_velocity_limits: false # angular.z.has_acceleration_limits: false # angular.z.has_jerk_limits: false # angular.z.max_velocity: 5.0 # angular.z.min_velocity: -5.0 # angular.z.max_acceleration: 10.0 # angular.z.min_acceleration: -10.0 # angular.z.max_jerk: 0.0 # angular.z.min_jerk: 0.0 linear.x.has_velocity_limits: true linear.x.has_acceleration_limits: false linear.x.has_jerk_limits: false linear.x.max_velocity: 2.0 linear.x.min_velocity: -2.0 linear.x.min_acceleration: -5.0 linear.x.max_acceleration: 5.0 linear.x.max_jerk: 0.0 linear.x.min_jerk: 0.0 angular.z.has_velocity_limits: true angular.z.has_acceleration_limits: true angular.z.has_jerk_limits: false angular.z.max_velocity: 6.28 angular.z.min_velocity: -6.28 angular.z.max_acceleration: 25.0 angular.z.min_acceleration: -25.0 angular.z.max_jerk: 0.0 angular.z.min_jerk: 0.0