ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

You'll find a more detailed treatment in a reference like Introduction to Autonomous Mobile Robots by Siegwart, et. al. You didn't say what type of drive system you have, so I'm assuming differential drive. At a high level, you need something like this:

  1. A way of converting from the Twist message in /cmd_vel to linear speeds for the left and right wheel frames.
  2. A conversion from linear speeds above to desired encoder speeds for the motors.
  3. A motor controller that drives the motors to the desired encoder speeds.

Generally, one more more ROS nodes cooperate to supply all three. 1) The diff_drive_controller package does it all, and works out-of-the-box for several commercial robots. 2) The diff_drive_controller node in the diff_drive package does #1 and #2, and publishes the desired encoder rates as lwheel_desired_rate and rwheel_desired_rate. 3) The ros_arduino_bridge package does all three things for a limited set of motor interfaces. 4) the differential_drive package has nodes for all three items, albeit without a mechanism for communicating with the hardware.

If you want to do things yourself, a few definitions:

v = velocity of the robot directly ahead, in m/s
v_l = velocity of the center of the left wheel, straight ahead, in m/s
v_r = velocity of the center of the right wheel, straight ahead, in m/s
l = separation of the two wheels, in m
z = angular velocity of the robot, in rad/s

From the Twist message, v = msg.linear.x and z = msg.angular.z. For a differential drive robot:

v = (v_r + v_l) / 2
z = (v_r - v_l) / l

Combining and simplifying we get:

2*v + l*z = 2*v_r
v_r = v + l*z/2
v_l = v_r - l*z = v - l*z/2

If the motor gives ticks_per_rev ticks per revolution, and the wheel diameter is d (in m), then:

wheel_circumference = pi * d
wheel_rotations_per_meter = 1 / (pi * d)
ticks_per_meter = wheel_rotations_per_meter * ticks_per_rev
ticks_per_second_l = v_l * ticks_per_meter
ticks_per_second_r = v_r * ticks_per_meter

A couple more complexities:

  1. The equations above may give you left and right velocities that are not achievable. If the maximum of the two wheel speeds is greater than some maximum limit, then you probably should reduce both wheel speeds by the same factor to keep under that limit.
  2. If a wheel motor speed is below the stall speed for the motor, then it is pointless to send it any current (and may be problematic). So if either wheel speed is below some minimum limit, you should probably set that wheel speed to zero.

You still need a lower-level controller to drive the motors to the desired ticks/sec speeds. The form of that controller will depend on your hardware.