Warning

This documention is in the process of being updated for ODrive Pro

Getting Started

Wire up the ODrive

Requirements

  • A brushless motor.

  • An encoder, unless using sensorless mode.

  • A 12V-58V power supply or battery. Some advice on choosing a power supply can be found here.

Pinout

Warning

Make sure to avoid a ground loop! See the ground loop page for details.

  1. Solder the motor phases onto the solder pads that are labelled A/B/C.

  2. Solder the power supply cables onto the solder pads that are labelled +++/—.

  3. If using an encoder, connect it to the corresponding I/O connector.

_images/pro_pinout.png

To learn more about pin functionality and specifications please refer to the pinout page here.

Safety & Power Up

Warning

Always think safety before powering up the ODrive if a motor is attached. Consider what might happen if the motor spins as soon as power is applied.

If possible, connect the power source first and then turn it on to avoid inrush current. If this can’t be avoided then a small spark is normal when plugging in the power connector, this is caused by the capacitors charging up. To avoid this issue we recommend using these anti spark connectors.

Connecting to the ODrive

There are two methods for connecting your ODrive to a computer, a command line utility called odrivetool or our new web GUI. If you are using the GUI, select Connect new device in the top right corner and skip ahead to Configure Power Supply, otherwise continue for installation instructions for odrivetool.

Note

You cannot use odrivetool and the GUI at the same time, if either say Could not claim interface make sure the other is closed and try again.

Install odrivetool

  1. Install Python 3. We recommend the Anaconda distribution because it packs a lot of useful scientific tools, however you can also install the standalone python.

    • Anaconda: Download the installer from here. Execute the downloaded file and follow the instructions.

    • Standalone Python: Download the installer for 3.8.6 from here. Execute the downloaded file and follow the instructions. As of Oct 2020, Matplotlib (required by odrivetool) had not been updated to work with 3.9, so please use 3.8.6.

    • If you have Python 2 installed alongside Python 3, replace pip by C:UsersYOUR_USERNAMEAppDataLocalProgramsPythonPython36-32Scriptspip. If you have trouble with this step then refer to this walkthrough.

  2. Launch the command prompt.

    • Anaconda: In the start menu, type Anaconda Prompt Enter

    • Standalone Python: In the start menu, type cmd Enter

  3. Install the ODrive tools by typing pip install --pre --upgrade odrive Enter

Start odrivetool

To launch the main interactive ODrive tool, type odrivetool Enter. Connect your ODrive and wait for the tool to find it. If it doesn’t connect after a few seconds refer to the troubleshooting page. Now you can, for instance type odrv0.vbus_voltage Enter to inpect the boards main supply voltage. It should look something like this:

ODrive control utility v0.5.1
Please connect your ODrive.
Type help() for help.

Connected to ODrive 306A396A3235 as odrv0
In [1]: odrv0.vbus_voltage
Out[1]: 11.97055721282959

The tool you’re looking at is a fully capable Python command prompt, so you can type any valid python code.

You can read more about odrivetool here.

..warning:: If any of the following steps fail, print the errors by running dump_errors(odrv0) in odrivetool. You can clear errors by running odrv0.clear_errors().

Configure Power Supply

Use this configuration if you’re powering the ODrive from a power supply that plugs into the grid.

Please note that ODrive Pro does not include a brake resistor feature (see note at the top of this page), so with this configuraion it is not possible to do electric deceleration because most AC/DC supplies do not support reverse current.

Please adapt the ??? placeholders for dc_bus_overvoltage_trip_level and dc_max_positive_current according to your power supply. dc_bus_overvoltage_trip_level should be slightly higher than your power supply’s nominal voltage. For instance if your power supply outputs 24V we recommend to set this value to 25.

odrv0.config.dc_bus_overvoltage_trip_level = ???
odrv0.config.dc_max_positive_current = ??? # current rating of your power supply in Amps
odrv0.config.dc_max_negative_current = -1

Motor Configuration

We only list configurations for the most commonly used motors here. If you’re using a different motor, you can use these scenarios as reference and read up on the documentation of the settings to adapt them for your motor.

odrv0.axis0.config.motor.motor_type = MotorType.HIGH_CURRENT
odrv0.axis0.config.motor.pole_pairs = 7
odrv0.axis0.config.motor.torque_constant = 8.27 / 270
odrv0.axis0.requested_state = AxisState.MOTOR_CALIBRATION
# [wait for end of motor beep]
odrv0.save_configuration()

Warning

If you change the motor, make sure to re-run the motor calibration.

If using motor thermistor Please see the Thermistors page for setup.

Setting the Limits

Current limit

odrv0.axis0.config.motor.current_soft_max = 10 # [A]

The default current limit, for safety reasons, is set to 10A. This is quite weak, but good for making sure the drive is stable. Once you have tuned the ODrive, you can increase this to 60A to increase performance. Note that above 60A, you must change the current amplifier gains. You do this by requesting a different current range. i.e. for 90A on M0: odrv0.axis0.config.motor.requested_current_range = 90 [A], then save the configuration and reboot as the gains are written out to the DRV (MOSFET driver) only during startup.

Note

The motor current and the current drawn from the power supply is not the same in general. You should not look at the power supply current to see what is going on with the motor current.

Velocity limit

odrv0.axis0.controller.config.vel_limit = 2 # [turn/s]

The motor will be limited to this speed. Again the default value is quite slow.

Encoder Configuration

Note

The rotor must be allowed to rotate without any biased load during encoder calibration. That means mass and weak friction loads are fine, but gravity or spring loads are not okay.

The following commands assume you have the encoder connected to the Motor I/O connector.

Connecting the A,B phases is mandatory, the Z (index pulse) is optional.

odrv0.inc_encoder0.config.cpr = 8192
odrv0.inc_encoder0.config.enabled = True
odrv0.axis0.config.load_encoder = EncoderId.INC_ENCODER0
odrv0.axis0.config.commutation_encoder = EncoderId.INC_ENCODER0
odrv0.save_configuration()
# [wait for ODrive to reboot]
odrv0.axis0.requested_state = AxisState.ENCODER_OFFSET_CALIBRATION
# [wait for motor to stop]

After each subsequent reboot you need to re-run odrv0.axis0.requested_state = AxisState.ENCODER_OFFSET_CALIBRATION before you can activate position/velocity control.

Viewing Encoder Feedback

Position and velocity feedback from the load_encoder can be found in the Mapper pos_vel_mapper by entering

odrv0.axis0.pos_vel_mapper.pos_rel
# or
odrv0.axis0.pos_vel_mapper.vel

Similarly, feedback from the commutation_encoder can be found in the Mapper commutation_mapper.

What is a Mapper?

A Mapper converts from one rotational/linear space to another rotational/linear space. For example, from an encoder’s circular output onto the user’s axis linear space, or the motor’s electrical phase circular space.

Position Control

Warning

Make sure you have a good mechanical connection between the encoder and the motor, slip can cause disastrous oscillations or runaway.

Let’s get motor 0 up and running. The procedure for motor 1 is exactly the same, so feel free to substitute axis1 wherever it says axis0.

  1. Type odrv0.axis0.requested_state = AxisState.CLOSED_LOOP_CONTROL Enter. From now on the ODrive will try to hold the motor’s position. If you try to turn it by hand, it will fight you gently. That is unless you bump up odrv0.axis0.config.motor.current_soft_max, in which case it will fight you more fiercely. If the motor begins to vibrate either immediately or after being disturbed you will need to lower the controller gains.

  2. Send the motor a new position setpoint. odrv0.axis0.controller.input_pos = 1 Enter. The units are in turns.

  3. At this point you will probably want to properly tune the motor controller in order to maximize system performance.

Other Control Modes

The default control mode is unfiltered position control in the absolute encoder reference frame. You may wish to use a controlled trajectory instead. Or you may wish to control position in a circular frame to allow continuous rotation forever without growing the numeric value of the setpoint too large.

You may also wish to control velocity (directly or with a ramping filter). You can also directly control the current of the motor, which is proportional to torque.

Filtered Position Control

Asking the ODrive controller to go as hard as it can to raw setpoints may result in jerky movement. Even if you are using a planned trajectory generated from an external source, if that is sent at a modest frequency, the ODrive may chase each stair in the incoming staircase in a jerky way. In this case, a good starting point for tuning the filter bandwidth is to set it to one half of your setpoint command rate.

You can use the second order position filter in these cases.

odrv0.axis0.controller.config.input_filter_bandwidth = 2.0 # Set the filter bandwidth [1/s]
odrv0.axis0.controller.config.input_mode = InputMode.POS_FILTER # Activate the setpoint filter
odrv0.axis0.controller.input_pos = 1 # control the velocity [turns]
secondOrderResponse

Step response of a 1000 to 0 position input with a filter bandwidth of 1.0 [/sec].

Trajectory Control

See the :usage section for details. This mode lets you smoothly accelerate, coast, and decelerate the axis from one position to another. With raw position control, the controller simply tries to go to the setpoint as quickly as possible. Using a trajectory lets you tune the feedback gains more aggressively to reject disturbance, while keeping smooth motion.

TrapTrajPosVel

Position (blue) and velocity (orange) vs. time using trajectory control.

Parameters

odrv0.axis0.trap_traj.config.vel_limit = <Float>
odrv0.axis0.trap_traj.config.accel_limit = <Float>
odrv0.axis0.trap_traj.config.decel_limit = <Float>
odrv0.axis0.controller.config.inertia = <Float>
  • vel_limit is the maximum planned trajectory speed. This sets your coasting speed.

  • accel_limit is the maximum acceleration in turns / sec^2

  • decel_limit is the maximum deceleration in turns / sec^2

  • controller.config.inertia is a value which correlates acceleration (in turns / sec^2) and motor torque. It is 0 by default. It is optional, but can improve response of your system if correctly tuned. Keep in mind this will need to change with the load / mass of your system.

Note

All values should be strictly positive (>= 0).

Keep in mind that you must still set your safety limits as before. It is recommended you set these a little higher ( > 10%) than the planner values, to give the controller enough control authority.

odrv0.axis0.config.motor.current_soft_max = <Float>
odrv0.axis0.controller.config.vel_limit = <Float>

Usage

Make sure you are in position control mode. To activate the trajectory module, set the input mode to trajectory:

odrv0.axis0.controller.config.input_mode = InputMode.TRAP_TRAJ

Simply send a position command to execute the move:

odrv0.axis0.controller.input_pos = <Float>

Use the move_incremental function to move to a relative position.

odrv0.axis0.controller.move_incremental(pos_increment, from_goal_point)

To set the goal relative to the current actual position, use from_goal_point = False To set the goal relative to the previous destination, use from_goal_point = True

You can also execute a move with the appropriate ascii command.

Circular Position Control

To enable Circular position control, set

odrv0.axis0.controller.config.circular_setpoints = True

This mode is useful for continuous incremental position movement. For example a robot rolling indefinitely, or an extruder motor or conveyor belt moving with controlled increments indefinitely. In the regular position mode, the input_pos would grow to a very large value and would lose precision due to floating point rounding.

In this mode, the controller will try to track the position within only one turn of the motor. Specifically, input_pos is expected in the range [0, 1). If the input_pos is incremented to outside this range (say via step/dir input), it is automatically wrapped around into the correct value. Note that in this mode encoder.pos_circular is used for feedback instead of encoder.pos_estimate.

If you try to increment the axis with a large step in one go that exceeds 1 turn, the motor will go to the same angle around the wrong way. This is also the case if there is a large disturbance. If you have an application where you would like to handle larger steps, you can use a larger circular range. Set

odrv0.axis0.controller.config.circular_setpoints_range = <N>

Choose N to give you an appropriate circular space for your application.

Velocity Control

Set the control mode

odrv0.axis0.controller.config.control_mode = ControlMode.VELOCITY_CONTROL

You can now control the velocity [turn/s] with

odrv0.axis0.controller.input_vel = 1

Ramped Velocity Control

Set the control mode

odrv0.axis0.controller.config.control_mode = ControlMode.VELOCITY_CONTROL

Set the velocity ramp rate (acceleration in turn/s^2):

odrv0.axis0.controller.config.vel_ramp_rate = 0.5

Activate the ramped velocity mode:

odrv0.axis0.controller.config.input_mode = InputMode.VEL_RAMP

You can now control the velocity (turn/s) with

odrv0.axis0.controller.input_vel = 1

Torque Control

Set the control mode

odrv0.axis0.controller.config.control_mode = ControlMode.TORQUE_CONTROL

Set the torque constant, e.g.:

# Approximately 8.23 / Kv where Kv is in the units [rpm / V]
odrv0.axis0.config.motor.torque_constant = 8.23 / 150

You can now control the torque (Nm) with e.g.

odrv0.axis0.controller.input_torque = 0.1

Note

For safety reasons, the torque mode velocity limiter is enabled by default. This works by reducing the torque of the motor according to vel_limit and vel_gain, as shown below. Please note that with the default settings, torque will limited even at 0 rpm.

torque_mode_vel_limit

The torque mode velocity limiter can be completely disabled by setting:

odrv0.axis0.controller.enable_torque_mode_vel_limit = False

What’s Next?

You can now:

  • Properly tune the motor controller to unlock the full potential of the ODrive.

  • See what other commands and parameters are available, in order to better control the ODrive.

  • Control the ODrive from your own program or hook it up to an existing system through one of it’s interfaces.

  • See how you can improve the behavior during the startup procedure, like bypassing encoder calibration.

If you have any issues or any questions please get in touch. The ODrive Community warmly welcomes you.