PWM Input

Endpoint Mapping

You can control the ODrive directly from a hobby RC receiver.

Any of the numerical parameters that are writable from odrivetool or the Web GUI can be controlled by a PWM input. The datasheet (Pro, S1) tells you which pins are PWM input capable for your device.

Given a PWM-capable GPIO pin Gxx (here, N will be used to notate the GPIO pin number), the pin can be configured in PWM mode with <odrv>.config.gpio(N)_mode = GpioMode.PWM.

All GPIO mode changes require a <odrv>.save_configuration() before taking effect.

Every time the PWM value is read, the pulse width will be remapped from 1000us - 2000us (1ms-2ms) to a range defined by <odrv>.config.gpio(N)_pwm_mapping.min to <odrv>.config.gpio(N)_pwm_mapping.max.

The mapped value will then be written to the endpoint defined by <odrv>.config.gpio(N)_pwm_mapping.endpoint. This can be any writable value on the ODrive, not just pos/vel/torque setpoints.

Typically, the name of this endpoint will be the property name with a leading underscore, and followed by _property.

For instance, if you want to map to <odrv>.axis0.controller.input_torque, the property name will be <odrv>.axis0.controller._input_torque_property.

As another example, the name of <odrv>.axis0.config.motor.current_soft_max would be <odrv>.axis0.config.motor._current_soft_max_property.

This mapping can be disabled by setting <odrv>.config.gpio(N)_pwm_mapping to None.

Position Control Example

As an example, we’ll configure the axis to move within a range of -2 to 2 turns. This assumes your ODrive is connected to ODrivetool as odrv0. In the GUI, this can be set up graphically in the configurator, so this guide is only relevant for when using ODrivetool.

  1. Make sure you’re able to control the axis0 angle by writing to odrv0.axis0.controller.input_pos, and that the position controller is properly tuned. If you need help with this follow the getting started guide.

  2. If you want to control your ODrive with the PWM input without using anything else to activate the ODrive, you can configure the ODrive such that it automatically enters closed loop at startup. See here for more information.

  3. Select a PWM-capable pin (see the Pro, S1 pinout pages for details).

  4. In odrivetool, configure the PWM input mapping, where N is the GPIO pin number selected (e.g. if pin G08 on ODrive S1 is used for PWM input, gpio(N) would be replaced with gpio8)

    odrv0.config.gpio(N)_mode = GpioMode.PWM
    odrv0.config.gpio(N)_pwm_mapping.min = -2
    odrv0.config.gpio(N)_pwm_mapping.max = 2
    odrv0.config.gpio(N)_pwm_mapping.endpoint = odrv0.axis0.controller._input_pos_property
    

    Note

    you can disable the input by setting odrv0.config.gpio(N)_pwm_mapping.endpoint = None

  5. Save the configuration and reboot

  6. With the ODrive powered off, connect the RC receiver ground to the corresponding GND on the ODrive, and one of the RC receiver signals to your selected PWM-capable GPIO.

    Note

    If using ODrive Pro or S1 and your PWM pin is in an ISOLATED IO grouping, you will need to externally power ISO_VDD/ISO_GND. See the corresponding datasheet page (Pro, S1) for more information.

    You may power the receiver from the ODrive’s 5V supply if it doesn’t draw too much power, being extremely careful to avoid ground loops.

  7. Power up the RC transmitter, and put the ODrive in closed loop control. You should now be able to control the motor’s position from one of the RC sticks.

Warning

Be sure to set up the failsafe feature on your RC Receiver so that if connection is lost between the remote and the receiver, the receiver outputs a safe value for your configured setpoint (e.g. 0 for torque/velocity, or whatever is safest for your position).

Note

If the receiver turns off (loss of power, etc.) or if the signal from the receiver to the ODrive is lost (wire comes unplugged, etc.), the ODrive will time out after 100ms and consider the input to be NAN, which in turn disarms the motor when connected to any of input_pos/input_vel/input_torque.

  1. Now, once the ODrive is powered and running in closed loop control (whether manually commanded in the GUI/ODrivetool or set to enter closed loop control on startup), the position setpoint will be set by the R/C PWM input.