Overview
Odometry estimates robot pose (position + orientation) by integrating wheel encoder measurements over time. For Mecanum wheels, we use forward kinematics to compute robot velocity from individual wheel speeds.Odometry provides local pose estimate (where robot thinks it is). It drifts over time due to wheel slippage. Later we’ll fuse with IMU and correct with SLAM.
Odometry Concepts
Pose Representation
Pose = Position + Orientation in 2D:Odometry Integration
Process:- Read wheel velocities from encoders (rad/s)
- Compute robot velocity using forward kinematics (Vx, Vy, ω)
- Integrate velocity to update pose:
x += Vx * dt,y += Vy * dt,θ += ω * dt - Publish updated pose as
/odomtopic
Coordinate Frames
Two frames involved:odom- World-fixed reference frame (origin where robot started)base_link- Robot body frame (moves with robot)
odom → base_link represents robot pose
ROS2 Odometry Message
Odometry published asnav_msgs/msg/Odometry:
Odometry in ros2_control
Good news: mecanum_drive_controller computes and publishes odometry automatically! In controller config:What Controller Does
Every control cycle (50Hz):- Reads wheel velocities from hardware interface (state interfaces)
- Computes robot velocity:
(Vx, Vy, ω) = forward_kinematics(w_FL, w_FR, w_RL, w_RR) - Integrates velocity to update pose:
x += Vx*dt,y += Vy*dt,θ += ω*dt - Publishes
/odomtopic (nav_msgs/Odometry) - Broadcasts TF transform:
odom → base_link
Verifying Odometry
Check Odometry Topic
Check TF Transform
Visualize in RViz
Launch RViz:- Fixed Frame:
odom - Add: Odometry display
- Topic:
/mecanum_drive_controller/odom - Covariance: Show position (optional)
- Topic:
- Add: TF display
- Add: RobotModel
- Drive robot forward using teleop
- Red arrow in RViz should extend forward (shows odometry path)
- Robot model moves in RViz
Odometry Calibration
Why Calibrate?
Odometry accuracy depends on:- Wheel radius - Affects distance traveled per rotation
- Wheel separation - Affects rotation radius
- Encoder CPR - Resolution of position measurement
Calibration Procedure
1
Measure Wheel Radius
Method 1: Direct measurementUse calipers to measure wheel diameter.Method 2: Rollout test
- Mark wheel position
- Roll wheel exactly 1 revolution
- Measure distance traveled:
d - Calculate:
radius = d / (2 * π)
2
Measure Wheel Separation
Wheel Separation X (front-rear):
- Measure from front wheel axle to rear wheel axle
- Measure from left wheel axle to right wheel axle
3
Test Forward Motion
- Place robot on measured distance (e.g., 1 meter)
- Reset odometry: Restart robot control node
- Drive robot forward using teleop
- Stop at 1-meter mark
- Check odometry:
- Odometry reads 0.9m but robot moved 1.0m → Increase wheel_radius
- Odometry reads 1.1m but robot moved 1.0m → Decrease wheel_radius
4
Test Rotation
- Place robot on flat surface
- Mark orientation (tape arrow on floor)
- Reset odometry
- Rotate robot exactly 360° (one full turn)
- Check odometry angle:
- Adjust
wheel_separation_xandwheel_separation_y
5
Update URDF and Config
File: File: Rebuild:
urdf/mecanum_robot.urdf.xacroconfig/mecanum_controller.yamlEncoder CPR Verification
Check encoder counts per revolution (CPR):- Manually rotate wheel exactly 1 revolution
- Check encoder count change
- Should match CPR (±2%)
Odometry Uncertainty (Covariance)
Covariance matrix represents pose uncertainty. In controller config:- 0.001 - Low uncertainty (1mm standard deviation)
- 0.03 - Higher uncertainty for yaw (0.03 rad ≈ 1.7°)
Tuning: Increase covariance if odometry drifts quickly. Sensor fusion (EKF) will rely less on odometry and more on IMU.
Common Odometry Errors
Odometry drifts (general)
Odometry drifts (general)
Symptom: Over time, odometry pose diverges from true poseCauses:
- Wheel slippage (especially Mecanum wheels!)
- Incorrect wheel radius/separation
- Encoder noise
- Calibrate wheel parameters
- Fuse with IMU (robot_localization)
- Use SLAM for global correction
Robot drives straight but odometry curves
Robot drives straight but odometry curves
Cause: Wheel radii differ (one wheel larger/smaller)Solutions:
- Check physical wheels (all same size?)
- Individual wheel calibration (advanced):
Rotation angle wrong
Rotation angle wrong
Symptom: Rotate 360°, odometry shows 340° or 380°Cause: Incorrect wheel separation valuesSolution:
- Measure wheel separation accurately
- Use calibration procedure (Step 4 above)
Odometry jumps or glitches
Odometry jumps or glitches
Cause: Encoder noise, missed counts, or communication errorsSolutions:
- Check encoder wiring (noise?)
- Add capacitors to encoder lines (0.1µF)
- Increase serial baud rate (reduce latency)
- Filter encoder data on ESP32
Odometry published but TF not updating
Odometry published but TF not updating
Symptom:
/odom topic has data but RViz doesn’t show robot movingCause: TF transform not broadcasted by controllerSolutions:- Check controller config:
publish_odom: true - Verify
odom_frame_idandbase_frame_idcorrect - Check TF tree:
ros2 run tf2_tools view_frames
Testing Procedure
Test 1: Straight Line
Procedure:- Place robot, note starting position
- Reset odometry (restart node)
- Drive forward 2 meters
- Measure actual distance with tape measure
- Compare with odometry
Test 2: Square Path
Procedure:- Reset odometry
- Drive square: 1m forward, rotate 90°, repeat 4x
- Check final pose (should return to start)
Test 3: Strafe (Mecanum-specific)
Procedure:- Reset odometry
- Strafe left 1 meter
- Check odometry Y position
Improving Odometry
Higher Update Rate
Increase control loop frequency:Reduces numerical integration error.
Wheel Calibration
Measure and calibrate all wheel parameters accurately. Even 1mm error compounds over distance.
Sensor Fusion
Combine odometry with IMU using Extended Kalman Filter (next section).
SLAM Correction
Use SLAM to periodically correct odometry drift with map landmarks.
Next Steps
IMU Fusion
Fuse IMU data with odometry using robot_localization
EKF Configuration
Configure Extended Kalman Filter for sensor fusion
Localization Testing
Validate complete localization system
SLAM Mapping
Create maps while correcting odometry drift