Calibrate Phidgets Odometry

From wikidb
Jump to: navigation, search

Overview

Calibration needs work. So far the distance traveled in roughly a straight line is used to calibrate the encoder clicks per mm for the left and right wheels. This has not been done accurately. Rotation has not been calibrated. The odometer launch script specifies a wheelbase but the odometry utility appears to want only half that distance. See below.

References

Background

This process leverages teleop built using rostopic plus motor controller modification. See the following prereqs:

Execute

Joystick Connected Directly to Bot Approach

Terminal 1

 roscore

Terminal 2

 roslaunch floor_hugger js_teleop.launch

Terminal 3

  roslaunch floor_hugger odometry.launch

Terminal 4 - Record left and right wheel counts

 rostopic echo phidgets/encoder/351547
  
 rostopic echo phidgets/encoder/351673

Rosbridge and Video Streaming Approach

This launch script was created odometry_calabrate.launch.

From another computer start up the following windows.

Terminal 1

 roscore

Terminal 2

 roslaunch floor_hugger odometry_calabrate.launch

In a Chrome or Firefox browser to control the Floor Hugger with a joystick

 http://10.0.0.111/~eepp/js_twist.html

The joystick is not always recognised. Check it out by looking at dev/input/js0. May need to unplug and replug the joystick of modify the js0 permissions.

In another browser to see where the going.

 http://10.0.0.111:8080/

Sometimes its necessary to change the video driver permissions.

 sudo chmod 666 /dev/video0

The joystick should move the robot and display where it is heading.

Set the Floor Hugger at a defined spot. Before moving it run the following to capture the odometer count. The count is reset to 0 each time the odometry_calabrate.launch script is started.

 rostopic echo phidgets/encoder/351547

 rostopic echo phidgets/encoder/351673

Example Results - Pololu Motor

Measured

  • Pololu 2827 motor/encoder
  • Polulu 1439 Wheel 90x10 mm => 282.74 mm
  • Distance travelled = 14 feet 11 inches => 179 inches => 4546.6 mm
  • Odometry
    • Left wheel encoder count (351547) = -133,802
      • 133,802 counts / 4546.6 mm => 29.43 counts / mm
    • Right wheel encoder count (351673) = 133,746
      • 133,746 / 4546.6 => 29.42 counts / mm
  • average = 29.42 counts / mm

From Specs

Counts per mm

  • 37Dx73L Pololu Motor Specs
    • 80 RPM
    • 131.25:1 Gear ratio
  • Counts / motor revolution => 64
  • 64 * 131.25 => 8400 counts / wheel revolution
  • 1439 90 x 10 mm wheel
  • 90 mm wheel => 282.74 mm / wheel revolution
  • 8400 / 282.74 => 29.71 counts / mm
  • We're within a percent - good starting place.

Max Velocity

  • Max velocity should be 283 mm/rev * 80 rev/min / 60 sec/min / 1000 mm/m => 0.38 m/sec
    • Wheeled Platforms "... 1 m/sec is pretty fast for indoor robots."
    • This sounds reasonable

New Pololu Script

TBD - Remeasure and test - 302 mm wheelbase??

The divide by two wheelbase tests showed a lack of my understanding of quaternions. (See depreciated SGMADA rotation note below.) The robot should rotate twice before return to the same orientation value.

        <!-- separation between the two wheels in millimetres (310 mm)-->
        <param name="wheelbase" value="310" />
        <!-- number of encoder counts per millimetre for the left wheel -->
        <param name="countspermmleft" value="29.7" />
        <!-- number of encoder counts per millimetre for the right wheel -->
        <param name="countspermmright" value="29.7" />
 

Error Checks - Pololu Motor

See the following link for rotation tuning tests.

Rotation

Using the above execution procedure odometry values were recorded for rotation. Rotation angles were rough (a guess accurate to 1/16 of a rotation). The goal was only a sanity check. The results weren't. The results show the position z and w rotation values below. From above do the following in 4 separate terminals

 roscore
 roslaunch floor_hugger js_teleop.launch
 roslaunch floor_hugger odometry.launch
 rostopic echo odom

Depreciated SGMADA Motor

Depreciated SGMADA Linear test

  • VEX wheel
  • Distance travelled = 12 feet 4 inches => 3759 mm.
  • Left wheel encoder count (351547) = 22824
    • 22824 / 3759 = 6.07 counts per mm => 6
  • Right wheel encoder count (351673) = 22792
    • 22792 / 3759 = 6.06 counts per mm => 6

Depreciated SGMADA Script

The measured wheelbase is 283 mm. It was halved to 141 mm to correct error noted below.

        
        <!-- separation between the two wheels in millimeters (11 5/32 inches or 283)-->
        <!-- half the wheelbase works  -->
        <param name="wheelbase" value="141" />
        <!-- number of encoder counts per millimetre for the left wheel -->
        <param name="countspermmleft" value="6" />
        <!-- number of encoder counts per millimetre for the right wheel -->
        <param name="countspermmright" value="6" />

Depreciated SGMADA Motor Rotation Test

Note: With the measure wheelbase of 283 the robot rotates twice before the yaw numbers return roughly to their original values.

Rotation z w
0 0.0 1.0
1/8 0.45 0.89
1/4 0.78 0.63
1/2 0.99 -0.06
3/4 0.60 -0.80
1 -0.14 -0.99
1 1/4 -0.80 -0.60
1 1/2 -0.98 -0.19
1 3/4 -0.54 0.83
2 0.24 0.98

These are the new numbers after the wheelbase was halved. Clearly these values are better. They almost return to their original value after one rotation. A more rigorous calibration is in order.

TBD: Why

Rotation z w
0 0.0 1.0
1/8 0.68 0.76
1/4 1.00 0.02
1/2 0.04 -1.00
3/4 -1.00 0.02
1 0.13 0.99