Close

Using RViz to Validate Motor Movement Against LIDAR Data

A project log for Phoebe TurtleBot

DIY variant of ROS TurtleBot for <$250 capable of simultaneous location and mapping (SLAM)

rogerRoger 10/01/2018 at 19:510 Comments

The Roboclaw ROS node is responsible for calculating odometry information based on encoder values read from each wheel. In order to translate them into standard ROS units, it needs two parameters:

Both of these values needed updating after upgrading Phoebe to the second chassis. I got impatient with the slow speed of the first draft, so the motor gearboxes were changed out with ones that deliver less torque and precision but much faster top speed. This change of gearing would need a new ticks_per_meter value. And the second chassis is slightly wider than the first, which obviously changes the base_width value. Both of these could be calculated on paper, but that is only a starting point. Real world is always a little different from the theoretical and needs a little adjustment.

The easiest place to start is ticks_per_meter. Phoebe is placed on a flat surface, next to a ruler, and commanded to drive straight forward for a short distance. During this activity, the odometry data is monitored with rostopic echo /odom to see how far Phoebe thinks it has actually gone. If the ruler said Phoebe didn’t go as far as it thought it did, increase ticks_per_meter. If Phoebe overshot, reduce that value.

Once wheel travel was verified with a ruler, LIDAR is added to the picture. RViz is commanded to plot odometry data and LIDAR data together, and Phoebe is placed facing a door serving as a large flat surface for reference. The red arrow represents where Phoebe thinks it is, facing the horizontal line representing its LIDAR’s view of the door.

Phoebe Door Test 1 Start

Then Phoebe was commanded to move backwards 0.5m. If odometry data agrees with LIDAR data, the movement away from door and the door’s distance from robot would match, canceling each other out so the line representing the door would not move on the RViz plot. It looks like the ruler calibration worked out well, as we’re only a tiny bit off.

Phoebe Door Test 2 Back 0.5m.png

Once distance was verified, we move on to rotation. Command Phoebe to make a 90 degree turn clockwise and see if LIDAR plot agrees. Again, ideally the turn calculated from odometry would agree with the LIDAR plot, leaving the door in roughly the same place on the RViz plot. Ideally.

Phoebe Door Test 3 90 Deg Right Bad

In this case, however, the door shows a minor clockwise rotation. This change of position in LIDAR data indicates Phoebe didn’t turn as far as it thought it did. To adjust parameters so Phoebe’s calculations better align with actual motion, we can increase the base_widthparameter. And if the door had rotated the other way (Phoebe turned further than it thought it did) the parameter should be decreased.

(Cross-posted to NewScrewdriver.com)

Discussions