Diff DriveΒΆ
This plugin provides common features for a differential drive robots. All velocities and odometries are w.r.t. the robot origin
- Subscribes to a topic publishing geometry_msgs/Twist messages, and move the robot at the desired forward and rotation velocities
- Publishes to two topics with nav_msgs/Odometry messages, one for robot odometry which has noise, the other the ground truth odometry
plugins:
# required, specify DiffDrive type to load the plugin
- type: DiffDrive
# required, name of the plugin
name: turtlebot_drive
# required, body of a model to set velocities and obtain odometry
body: base
# optional, defaults to odom, the name of the odom frame
odom_frame_id: odom
# optional, defaults to inf, rate to publish odometry at, in Hz
pub_rate: .inf
# optional, defaults to "cmd_vel", the topic to subscribe for velocity
# commands
twist_sub: cmd_vel
# optional, defaults to "odometry/filtered", the topic to advertise for
# publish noisy odometry
odom_pub: odometry/filtered
# optional, defaults to "odometry/ground_truth", the topic to advertise for publish
# no noise ground truth odometry
ground_truth_pub: odometry/ground_truth
# optional, defaults to "twist", the topic to publish noisy local frame velocity
# that simulates encoder readings
twist_pub: twist
# optional, defaults to true, enables the advertising and publishing of both
# ground truth and noisy odometry
enable_odom_pub: true
# optional, defaults to true, enables the publishing of the TF between
# 'base_link' (or link specified in "body") and 'odom' links.
# Disable if your code has its own TF publisher for these two links.
enable_odom_tf_pub: true
# optional, defaults to true, enables the advertising and publishing of noisy local
# frame velocity
enable_twist_pub: true
# optional, defaults to [0, 0, 0], corresponds to noise on [x, y, yaw],
# the variances of gaussian noise to apply to the pose components of the
# odometry message
odom_pose_noise: [0, 0, 0]
# optional, defaults to [0, 0, 0], corresponds to noise on
# [x velocity, y velocity, yaw rate], the variances of gaussian noise to
# apply to the twist components of the odometry message
odom_twist_noise: [0, 0, 0]
# optional, defaults to the diagonal [x, y, yaw] components replaced by
# odom_pose_noise with all other values equals zero, must have length of 36,
# represents a 6x6 covariance matrix for x, y, z, roll, pitch, yaw.
# This does not involve in any of the noise calculation, it is simply
# the output values of odometry pose covariance
odom_pose_covariance: [0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0]
# optional, defaults to the diagonal [x velocity, y velocity, yaw rate]
# components replaced by odom_twist_noise with all other values equals zero,
# must have length of 36, represents a 6x6 covariance matrix for rates x,
# y, z, roll, pitch, yaw. This does not involve in any of the noise
# calculation, it is simply the output values of odometry twist covariance
odom_twist_covariance: [0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0]
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on angular velocity, acceleration (in rads/sec; rads/sec/sec)
angular_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in rads/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in rads/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in rads/s; 0.0 means "no limit"
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on linear velocity, acceleration (in m/s; m/s/s)
linear_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in m/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in m/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in m/s; 0.0 means "no limit"
ground_truth_frame_id: map # The name of the ground truth origin TF frame