diff --git a/ros/kxr_controller/launch/mecanum_drive_controller.launch b/ros/kxr_controller/launch/mecanum_drive_controller.launch new file mode 100644 index 00000000..cb74c49b --- /dev/null +++ b/ros/kxr_controller/launch/mecanum_drive_controller.launch @@ -0,0 +1,11 @@ + + + + + + + + diff --git a/ros/kxr_controller/package.xml b/ros/kxr_controller/package.xml index 6cb078c2..011bcbee 100644 --- a/ros/kxr_controller/package.xml +++ b/ros/kxr_controller/package.xml @@ -36,6 +36,7 @@ cmake_modules kxr_models rviz + ridgeback_control roslaunch rostest diff --git a/ros/kxr_models/config/kxrmw4a6h2m_mecanum_drive_controller.yaml b/ros/kxr_models/config/kxrmw4a6h2m_mecanum_drive_controller.yaml new file mode 100644 index 00000000..f362c67e --- /dev/null +++ b/ros/kxr_models/config/kxrmw4a6h2m_mecanum_drive_controller.yaml @@ -0,0 +1,43 @@ +ridgeback_control: + type: "mecanum_drive_controller/MecanumDriveController" + front_left_wheel_joint: "front_left_wheel_joint" + back_left_wheel_joint: "rear_left_wheel_joint" + front_right_wheel_joint: "front_left_wheel_joint" + back_right_wheel_joint: "rear_right_wheel_joint" + publish_rate: 50 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03] + twist_covariance_diagonal: [0.001, 0.001, 0.001, 1000000.0, 1000000.0, 0.03] + cmd_vel_timeout: 0.25 + + # Override URDF look-up for wheel separation since the parent link is not the base_link. + wheel_separation_x: 0.638 + wheel_separation_y: 0.551 + + # Odometry fused with IMU is published by robot_localization, so + # no need to publish a TF based on encoders alone. + enable_odom_tf: true + base_frame_id: bodyset94855827795112 + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.5 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : true + max_velocity : 0.1 # m/s + has_acceleration_limits: true + max_acceleration : 20.0 # m/s^2 + y: + has_velocity_limits : true + max_velocity : 0.1 # m/s + has_acceleration_limits: true + max_acceleration : 20.0 # m/s^2 + angular: + z: + has_velocity_limits : true + max_velocity : 4.0 # rad/s + has_acceleration_limits: true + max_acceleration : 25.0 # rad/s^2