You're reading the documentation for an older, but still supported, version of ROS 2. For information on the latest version, please have a look at Jazzy.
mecanum_drive_controller
Library with shared functionalities for mobile robot controllers with mecanum drive (four mecanum wheels). The library implements generic odometry and update methods and defines the main interfaces.
Execution logic of the controller
The controller uses velocity input, i.e., stamped Twist messages where linear x
, y
, and angular z
components are used.
Values in other components are ignored.
In the chain mode, the controller provides three reference interfaces, one for linear velocity and one for steering angle position.
Other relevant features are:
odometry publishing as Odometry and TF message;
input command timeout based on a parameter.
Note about odometry calculation: In the DiffDRiveController, the velocity is filtered out, but we prefer to return it raw and let the user perform post-processing at will. We prefer this way of doing so as filtering introduces delay (which makes it difficult to interpret and compare behavior curves).
Description of controller’s interfaces
References (from a preceding controller)
When controller is in chained mode, it exposes the following references which can be commanded by the preceding controller:
<controller_name>/linear/x/velocity
, in m/s<controller_name>/linear/y/velocity
, in m/s<controller_name>/angular/z/velocity
, in rad/s
Commands
<*_wheel_command_joint_name>/velocity
, in rad/s
States
<joint_name>/velocity
, in rad/s
Note
joint_name
can be of *_wheel_state_joint_name
parameter (if used), *_wheel_command_joint_name
otherwise.
Subscribers
Used when the controller is not in chained mode (in_chained_mode == false
).
<controller_name>/reference
[geometry_msgs/msg/TwistStamped
] Velocity command for the controller, ifuse_stamped_vel == true
.<controller_name>/reference_unstamped
[geometry_msgs/msg/Twist
] Velocity command for the controller, ifuse_stamped_vel == false
.
Publishers
<controller_name>/odometry
[nav_msgs/msg/Odometry
]<controller_name>/tf_odometry
[tf2_msgs/msg/TFMessage
]<controller_name>/controller_state
[control_msgs/msg/MecanumDriveControllerState
]
Parameters
This controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.
- reference_timeout (double)
Timeout for controller references after which they will be reset. This is especially useful for controllers that can cause unwanted and dangerous behavior if reference is not reset, e.g., velocity controllers. If value is 0 the reference is reset after each run.
Default: 0.0
- front_left_wheel_command_joint_name (string)
Name of the joints for commanding front left wheel.
Read only: True
Default: “”
Constraints:
parameter is not empty
- front_right_wheel_command_joint_name (string)
Name of the joints for commanding front right wheel.
Read only: True
Default: “”
Constraints:
parameter is not empty
- rear_right_wheel_command_joint_name (string)
Name of the joints for commanding rear right wheel.
Read only: True
Default: “”
Constraints:
parameter is not empty
- rear_left_wheel_command_joint_name (string)
Name of the joints for commanding rear left wheel.
Read only: True
Default: “”
Constraints:
parameter is not empty
- front_left_wheel_state_joint_name (string)
(optional) Specifies a joint name for reading states of front left wheel. This parameter is only relevant when state joints are different then command joint, i.e., when a following controller is used.
Read only: True
Default: “”
- front_right_wheel_state_joint_name (string)
(optional) Specifies a joint name for reading states of front right wheel. This parameter is only relevant when state joints are different then command joint, i.e., when a following controller is used.
Read only: True
Default: “”
- rear_right_wheel_state_joint_name (string)
(optional) Specifies a joint name for reading states of rear right wheel. This parameter is only relevant when state joints are different then command joint, i.e., when a following controller is used.
Read only: True
Default: “”
- rear_left_wheel_state_joint_name (string)
(optional) Specifies a joint name for reading states of rear left wheel. This parameter is only relevant when state joints are different then command joint, i.e., when a following controller is used.
Read only: True
Default: “”
- kinematics.base_frame_offset.x (double)
Base frame offset along X axis of base_frame (base_link frame).
Read only: True
Default: 0.0
- kinematics.base_frame_offset.y (double)
Base frame offset along Y axis of base_frame (base_link frame).
Read only: True
Default: 0.0
- kinematics.base_frame_offset.theta (double)
Base frame offset along Theta axis of base_frame (base_link frame).
Read only: True
Default: 0.0
- kinematics.wheels_radius (double)
Wheel’s radius.
Default: 0.0
Constraints:
greater than 0.0
- kinematics.sum_of_robot_center_projection_on_X_Y_axis (double)
Wheels geometric param used in mecanum wheels’ IK. lx and ly represent the distance from the robot’s center to the wheels projected on the x and y axis with origin at robots center respectively, sum_of_robot_center_projection_on_X_Y_axis = lx+ly
Default: 0.0
- use_stamped_vel (bool)
Use stamp from input velocity message to calculate how old the command actually is.
Default: true
- base_frame_id (string)
Base frame_id set to value of base_frame_id.
Default: “base_link”
- odom_frame_id (string)
Odometry frame_id set to value of odom_frame_id.
Default: “odom”
- enable_odom_tf (bool)
Publishing to tf is enabled or disabled?
Default: true
- twist_covariance_diagonal (double_array)
Diagonal values of twist covariance matrix.
Default: {0.1, 0.1, 0.1, 0.1, 0.1, 0.1}
- pose_covariance_diagonal (double_array)
Diagonal values of pose covariance matrix.
Default: {0.1, 0.1, 0.1, 0.1, 0.1, 0.1}
An example parameter file for this controller can be found in the test directory:
test_mecanum_drive_controller:
ros__parameters:
reference_timeout: 0.9
front_left_wheel_command_joint_name: "front_left_wheel_joint"
front_right_wheel_command_joint_name: "front_right_wheel_joint"
rear_right_wheel_command_joint_name: "back_right_wheel_joint"
rear_left_wheel_command_joint_name: "back_left_wheel_joint"
kinematics:
base_frame_offset: { x: 0.0, y: 0.0, theta: 0.0 }
wheels_radius: 0.5
sum_of_robot_center_projection_on_X_Y_axis: 1.0
base_frame_id: "base_link"
odom_frame_id: "odom"
enable_odom_tf: true
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
test_mecanum_drive_controller_with_rotation:
ros__parameters:
reference_timeout: 5.0
front_left_wheel_command_joint_name: "front_left_wheel_joint"
front_right_wheel_command_joint_name: "front_right_wheel_joint"
rear_right_wheel_command_joint_name: "rear_right_wheel_joint"
rear_left_wheel_command_joint_name: "rear_left_wheel_joint"
kinematics:
base_frame_offset: { x: 1.0, y: 2.0, theta: 3.0 }
wheels_radius: 0.05
sum_of_robot_center_projection_on_X_Y_axis: 0.2925
base_frame_id: "base_link"
odom_frame_id: "odom"
enable_odom_tf: true
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]