ODrive Documentation

High performance motor control

View the Project on GitHub odriverobotics/ODrive

Help improve these docs: submit edits using the link in the top right.

If you need help, please search or ask the ODrive Community.

Parameters & Commands

We will use the <odrv> as a placeholder for any ODrive object. Every ODrive controller is an ODrive object. In odrivetool this is usually odrv0. Furthermore we use <axis> as a placeholder for any axis, which is an attribute of an ODrive object (for example odrv0.axis0). An axis represents where the motors are connected. (axis0 for M0 or axis1 for M1)

Table of contents

Per-Axis commands

For the most part, both axes on the ODrive can be controlled independently.

State Machine

The current state of an axis is indicated by <axis>.current_state. The user can request a new state by assigning a new value to <axis>.requested_state. The default state after startup is AXIS_STATE_IDLE. A description of all states can be found here.

Startup Procedure

By default the ODrive takes no action at startup and goes to idle immediately. In order to change what startup procedures are used, set the startup procedures you want to True. The ODrive will sequence all enabled startup actions selected in the order shown below.

See here for a description of each state.

Control Mode

The default control mode is position control. If you want a different mode, you can change <axis>.controller.config.control_mode. Possible values are listed here.

Input Mode

As of version v0.5.0, ODrive now intercepts the incoming commands and can apply filters to them. The old protocol values pos_setpoint, vel_setpoint, and current_setpoint are still used internally by the closed-loop cascade control, but the user cannot write to them directly. This allows us to condense the number of ways the ODrive accepts motion commands. The new commands are:

Control Commands

Modes can be selected by changing <axis>.controller.config.input_mode. The default input mode is INPUT_MODE_PASSTHROUGH. Possible values are listed here.

System monitoring commands

Encoder position and velocity

Motor current and torque estimation

Using the motor current and the known KV of your motor you can estimate the motors torque using the following relationship: Torque [N.m] = 8.27 * Current [A] / KV.

General system commands

Saving the configuration

All variables that are part of a [...].config object can be saved to non-volatile memory on the ODrive so they persist after you remove power. The relevant commands are:

Diagnostics

Setting up sensorless

The ODrive can run without encoder/hall feedback, but there is a minimum speed, usually around a few hundred RPM. In other words, sensorless mode does not support stopping or changing direction!

Sensorless mode starts by ramping up the motor speed in open loop control and then switches to closed loop control automatically. The sensorless speed ramping parameters are in axis.config.sensorless_ramp The vel and accel (in [radians/s] and [radians/s^2]) control the speed that the ramp tries to reach and how quickly it gets there. When the ramp reaches sensorless_ramp.vel, controller.input_vel is automatically set to the same velocity, in [turns/s], and the state switches to closed loop control.

If your motor comes to a stop after the ramp, try incrementally raising the vel parameter. The goal is to be above the minimum speed necessary for sensorless position and speed feedback to converge - this is not well-parameterized per motor. The parameters suggested below work for the D5065 motor, with 270KV and 7 pole pairs. If your motor grinds and skips during the ramp, lower the accel parameter until it is tolerable.

Below are some suggested starting parameters that you can use for the ODrive D5065 motor. Note that you must set the pm_flux_linkage correctly for sensorless mode to work. Motor calibration and setup must also be completed before sensorless mode will work.

odrv0.axis0.controller.config.vel_gain = 0.01
odrv0.axis0.controller.config.vel_integrator_gain = 0.05
odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.axis0.controller.config.vel_limit = <a value greater than axis.config.sensorless_ramp.vel / (2pi * <pole_pairs>)>
odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (<pole pairs> * <motor kv>)
odrv0.axis0.config.enable_sensorless_mode = True

To start the motor:

<axis>.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL