diff --git a/rosbot_controller/config/diff_drive_controller.yaml b/rosbot_controller/config/diff_drive_controller.yaml index 5355f598..a7730a31 100644 --- a/rosbot_controller/config/diff_drive_controller.yaml +++ b/rosbot_controller/config/diff_drive_controller.yaml @@ -26,13 +26,13 @@ left_wheel_names: [fl_wheel_joint, rl_wheel_joint] right_wheel_names: [fr_wheel_joint, rr_wheel_joint] - wheel_separation: 0.186 + wheel_separation: 0.195 wheel_radius: 0.0425 # For skid drive kinematics it will act as ICR coefficient # Kinematic model with ICR coefficient isn't totally accurate and this coefficient can differ # for various ground types, but checking on our office floor 1.3 looked approximately alright - wheel_separation_multiplier: 1.45 + wheel_separation_multiplier: 1.3 left_wheel_radius_multiplier: 1.0 right_wheel_radius_multiplier: 1.0 diff --git a/rosbot_controller/package.xml b/rosbot_controller/package.xml index 6e162921..798d310a 100644 --- a/rosbot_controller/package.xml +++ b/rosbot_controller/package.xml @@ -24,6 +24,7 @@ launch launch_ros mecanum_drive_controller + nav2_common robot_state_publisher ros_components_description rosbot_description