-
Notifications
You must be signed in to change notification settings - Fork 9
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
[kxr_controller] support mecanum drive
- Loading branch information
Showing
3 changed files
with
55 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
<launch> | ||
|
||
<rosparam command="load" file="$(find kxr_models)/config/kxrmw4a6h2m_mecanum_drive_controller.yaml" /> | ||
|
||
<node name="mecanum_drive_controller_spawner" | ||
pkg="controller_manager" type="spawner" | ||
respawn="true" respawn_delay="5" output="screen" | ||
args="ridgeback_control" > | ||
</node> | ||
|
||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
43 changes: 43 additions & 0 deletions
43
ros/kxr_models/config/kxrmw4a6h2m_mecanum_drive_controller.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |