Ros API

VelocitySmoother Nodelet

The velocity smoother nodelet is intended to run together with the kobuki_node to apply robot's velocity and acceleration limits to the incoming commands before resending them to the robot.

Subscribed Topics

~raw_cmd_vel (geometry_msgs/Twist)
  • Input velocity commands.
~odometry (nav_msgs/Odometry)
  • We compare the output velocity commands to "real" velocity to ensure we don't create very big jumps in the velocity profile.

Published Topics

~smooth_cmd_vel (geometry_msgs/Twist)
  • Smoothed output velocity commands respecting velocity and acceleration limits.

Parameters

~accel_lim_v (double)
  • Linear acceleration limit. Mandatory.
~accel_lim_w (double)
  • Angular acceleration limit. Mandatory.
~speed_lim_v (double)
  • Linear velocity limit. Mandatory.
~speed_lim_w (double)
  • Angular velocity limit. Mandatory.
~decel_factor (double, default: 1.0)
  • Deceleration/acceleration ratio. Useful to make deceleration more aggressive, for example to safely brake on robots with high inertia.
~frequency (double, default: 20.0)
  • Output messages rate. The velocity smoother keeps it regardless incoming messages rate, interpolating whenever necessary.

Hints

  • All the parameters except frequency are dynamically reconfigurable.
  • Linear and angular velocities are smoothed proportionally to the more restricted, so we guaranty a constant rotation radius.
  • If the input topic gets inactive, and the last command is not a zero-velocity one, (maybe the controller crashed, or just forgot good manners...), we introduce a fake zero-velocity command after a sort timeout.
  • Take a look to the Kobuki's Control System Tutorial to learn how yocs_velocity_smoother works together with other components to build up a safe and flexible control system.

Report a Bug

Use github to report bugs or request features.

Wiki: yocs_velocity_smoother/groovy (last edited 2013-01-16 12:00:28 by Jorge Santos)