Configuring ODrive for Steering and Throttle Using PWM Inputs (v3.6, FW 0.5.4, Hoverboard Motors with Hall Encoders)

Hi everyone,

I’m using an ODrive v3.6 with firmware version 0.5.4, and I have successfully calibrated two hoverboard motors with hall encoders. I’m trying to control these motors using PWM signals:

GPIO4 for throttle (forward/reverse).
GPIO3 for steering (left/right).

I’ve written a Python script (below) to map the PWM signals on GPIO4 and GPIO3 to control motor velocities (axis0.controller.input_vel and axis1.controller.input_vel). The goal is to combine the throttle and steering inputs so the left and right motors adjust speeds accordingly (e.g., for turning).

However, it doesn’t seem to work as expected:

  1. The motors don’t respond correctly to the PWM signals.
  2. I’m unsure if my approach to normalizing the PWM signals and combining them into left/right velocities is correct.

Setup Details:

ODrive v3.6, firmware 0.5.4.
Hoverboard motors with hall encoders.
Motors calibrated successfully.
GPIO4 and GPIO3 configured as PWM inputs with a range of -2 to 2.

Here’s what I’ve tried so far:

  • Calibrated the motors with hall encoders (using AXIS_STATE_MOTOR_CALIBRATION and AXIS_STATE_ENCODER_OFFSET_CALIBRATION and 'AXIS_STATE_HALL_POLARITY_CALIBRATION).
  • Configured GPIO3 and GPIO4 as PWM inputs.
  • Tested the script to read PWM signals using get_adc_voltage.

Questions:

  1. Is it possible to directly map two independent PWM channels (GPIO4 for throttle, GPIO3 for steering) to control the velocities of two axes as I’m trying to do?
  2. Am I correctly using the ODrive configuration (e.g., gpio3_pwm_mapping, gpio4_pwm_mapping)?
  3. Are there additional steps I need to take in the firmware or Python API to achieve this setup?

Here’s the Python script I’ve been testing:


python

import odrive
from odrive.enums import GPIO_MODE_PWM, AXIS_STATE_CLOSED_LOOP_CONTROL
import time

Connect to the ODrive

print(“Connecting to ODrive…”)
odrv0 = odrive.find_any()
print(“ODrive connected!”)

Configure GPIO4 for throttle (forward/reverse)

print(“Configuring GPIO4 for throttle (forward/reverse)…”)
odrv0.config.gpio4_mode = GPIO_MODE_PWM
odrv0.config.gpio4_pwm_mapping.min = -2 # Minimum PWM range
odrv0.config.gpio4_pwm_mapping.max = 2 # Maximum PWM range

Configure GPIO3 for steering (left/right)

print(“Configuring GPIO3 for steering (left/right)…”)
odrv0.config.gpio3_mode = GPIO_MODE_PWM
odrv0.config.gpio3_pwm_mapping.min = -2 # Minimum PWM range
odrv0.config.gpio3_pwm_mapping.max = 2 # Maximum PWM range

Save and reboot the ODrive configuration

print(“Saving configuration…”)
try:
odrv0.save_configuration()
except Exception as e:
print(f"Save error: {e}“)
print(“Rebooting ODrive…”)
try:
odrv0.reboot()
except Exception as e:
print(f"Reboot error: {e}”)

Wait for the ODrive to reboot

time.sleep(5)
print(“Reconnecting to ODrive…”)
odrv0 = odrive.find_any()

Activate CLOSED_LOOP_CONTROL for both axes

print(“Activating CLOSED_LOOP_CONTROL…”)
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL

print(“Configuration complete. Test PWM channels on GPIO3 and GPIO4.”)

Main loop with debugging

try:
while True:
# Read voltages from GPIO4 (throttle) and GPIO3 (steering)
throttle = odrv0.get_adc_voltage(4) # Voltage from GPIO4
steering = odrv0.get_adc_voltage(3) # Voltage from GPIO3

    # Debug: print the read voltages
    print(f"Read voltage: Throttle = {throttle:.2f}, Steering = {steering:.2f}")

    # Normalize voltages (-2 to 2 mapped to -1.0 to 1.0)
    throttle = throttle / 2  # Divide by 2 to normalize
    steering = steering / 2  # Divide by 2 to normalize

    # Calculate motor velocities
    motor_left = throttle + steering
    motor_right = throttle - steering

    # Limit velocities to the range [-1, 1]
    motor_left = max(-1, min(1, motor_left))
    motor_right = max(-1, min(1, motor_right))

    # Debug: print calculated velocities
    print(f"Motor commands: Left = {motor_left:.2f}, Right = {motor_right:.2f}")

    # Send velocity commands to motors
    odrv0.axis0.controller.input_vel = motor_left
    odrv0.axis1.controller.input_vel = motor_right

    # Pause to avoid CPU overload
    time.sleep(0.01)

except KeyboardInterrupt:
print(“Script stopped by user.”)
# Stop the motors
odrv0.axis0.controller.input_vel = 0
odrv0.axis1.controller.input_vel = 0

Hmm, I don’t know if this is the best way to do things. A few notes:

  • get_adc_voltage isn’t the right way to read PWM inputs, as that’s not an analog voltage input.
  • I’m actually not sure there is a way to just read the PWM input on the ODrive over USB. One hacky workaround would be to map the PWM inputs to unused properties on the ODrive, then read those. For instance:
    odrv0.config.gpio4_pwm_mapping.endpoint = odrv0.axis0.config.sensorless_ramp._accel_property
    odrv0.config.gpio3_pwm_mapping.endpoint = odrv0.axis0.config.sensorless_ramp._vel_property

From here, you could read odrv0.axis0.config.sensorless_ramp.accel to get the GPIO4 PWM value, and odrv0.axis0.config.sensorless_ramp.vel to get the GPIO3 PWM value. As I said, awful and hacky, but it should work.

Other than that, math looks generally okay, with the note that this isn’t respecting any sort of units or consistency. Check out the math here for an example: ODriveResources/botwheel-explorer/bot_ctrl.py at master · odriverobotics/ODriveResources · GitHub