Wheel Encoders

Rover 3.2 (not yet released) includes support for up to two AB wheel encoders like those in this Pololu motor which can be used to improve position estimation especially when no GPS is used.

Connection and Setup

../_images/wheel-encoder-pixhawk.png
  • connect motor encoder’s A and B outputs to the flight controller (i.e. Pixhawk’s) AUX OUT 3,4,5 and 6 signal pins as shown above
  • set BRD_PWM_COUNT to 2 to allow AUX OUT 3 and 4 to be used as inputs
  • set WENC_TYPE and WENC2_TYPE to 1 to enable reading from two wheel encoders
  • set WENC_CPR and WENC2_CPR to the counts-per-revolution of the encoder. This is the number of “pings” the encoder will produce for each full revolution of the wheel
  • set WENC_RADIUS and WENC2_RADIUS to the radius (in meters) of each wheel (i.e. 5cm radius would be 0.05)
  • set WENC_POS_X and WENC_POS_Y to define the first wheel’s distance from the flight controller or COG (i.e. WENC_POS_X = 0.10, WENC_POS_Y = 0.05 means the wheel is 10cm ahead and 5cm left of the flight controller)
  • set WENC2_POS_X and WENC2_POS_Y to define the second wheel’s distance from the flight controller or COG

To enable position estimation using the wheel encoders the EKF3 must be set as the main AHRS:

After making the above changes the flight controller should be rebooted

Ground Testing

The RPM of the two wheels can be seen as “rpm1” and “rpm2” in the ground station.

If using the Mission Planner these values can be seen in the Flight Data screen’s Status tab.

DataFlash logging

The wheel encoder data including total distance travelled by each wheel appears in the WENC dataflash log messages.