Getting Started

Hardware Requirements

You will need

  • One or two brushless motors. It is fine, even recommended, to start testing with just a single motor and encoder.

  • One or two encoder(s).

  • A power supply (12V-24V for the 24V board variant, 12V-56V for the 56V board variant). A battery is also fine. Some advice on choosing a power supply can be found here.

  • A power resistor. A good starting point would be the 50W resistor included with your ODrive.

Wiring up the ODrive

Warning

Firmware, software, and documentation is intended for use with ODrive motor controllers purchased from odriverobotics.com. ODrive Robotics does not sell products through any channel other than odriverobotics.com. We do not provide support for ODrives purchased elsewhere.

Warning

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

All non-power I/O is 3.3V output and 5V tolerant on input, on ODrive v3.3 and newer.

Wiring up the motors

Connect the motor phases into the 3-phase screw terminals. It is not recommended to use a clip-on connector such as an alligator clip, as this can cause issues with the phase resistance/inductance measurements.

Wiring up the encoders

Connect the encoder(s) to J4. The A,B phases are required, and the Z (index pulse) is optional. The A,B and Z lines have 3.3k pull up resistors, for use with open-drain encoder outputs. For single ended push-pull signals with weak drive current (<4mA), you may want to desolder the pull-ups.

_images/ODriveBasicWiring.png

Safety & Power UP

Warning

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

  • Unlike some devices, the ODrive does not recieve power over the USB port so the 24/56 volt power input is required even just to communicate with it using USB. It is ok to power up the ODrive before or after connecting the USB cable.

  • To power up the ODrive, connect the power source to the DC terminals. Make sure to pay attention to the polarity. Try to 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. This is caused by the capacitors charging up.

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

Downloading and Installing odriveool

Most instructions in this guide refer to a utility called odrivetool, so you should install that first.

  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 odrivetool by running

    pip install --upgrade odrive
    

Firmware

To simplify the start up procedure we suggest using the latest firmware verion. Please follow the instructions here to make sure your firmware is up to date.

ODrive v3.5 and later

Your board should come preflashed with the latest firmware. If you run into problems, check your firmware version and upgrade if possible.

ODrive v3.4 and earlier

Your board does not come preflashed with any firmware. Follow the instructions here on the ST Link procedure before you continue.

Start odrivetool

  • To launch the main interactive ODrive tool, type odrivetool and Enter.

  • Connect your ODrive and wait for the tool to find it. If it dos not connect after a few seconds refer to the troubleshooting guide.

  • Now you can, for instance type odrv0.vbus_voltage Enter to inspect the boards main supply voltage.

It should look something like this:

ODrive control utility v0.5.4
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.

Motor Configuration

Warning

Read this section carefully, else you risk breaking something.

Configuration of a motor is done within the odrivetool console, type odrivetool and Enter to launch. Make sure you have completed :ref:` Start odrivetool <odrivetool-startup>` before continuing.

This section assumes that the motor being configured is connected to the ODrive as M0 (axis0). To configure M1, simply replace all instances of axis0 with axis1.

If any of the following steps fail, print the errors by running dump_errors(odrv0) and refer to the Error codes section for debugging. Once the error(s) have been identified and corrected, run odrv0.clear_errors() to clear them before moving forward.

Working on a hoverboard?

There is a separate guide specifically for hoverboard motors

Setting the Limits

With odrivetool open you can assign variables directly by name. For instance, to set the current limit of M0 to 10A you would type

odrv0.axis0.motor.config.current_lim = 10

Current limit

The default current limit, for safety reasons, is set to 10A. This is quite weak, but good for making sure the drive is stable. To change the current limit,

odrv0.axis0.motor.config.current_lim = val

Once you have tuned the ODrive, you can increase this to 60A to increase performance.

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

The motor will be limited to this speed in [turn/s]. Again the default value is quite slow.

odrv0.axis0.controller.config.vel_limit = 2

Calibration Current

You can change odrv0.axis0.motor.config.calibration_current [A] to the largest value you feel comfortable leaving running through the motor continuously when the motor is stationary. If you are using a small motor (i.e. 15A current rated) you may need to reduce calibration_current to a value smaller than the default.

Setting Other Hardware Parameters

Enable Brake Resistor

Set this to True if using a brake resistor. You need to save the configuration and reboot the ODrive for this to take effect.

odrv0.config.enable_brake_resistor

Brake Resistor Value

This is the resistance [Ohms] of the brake resistor. You can leave this at the default setting if you are not using a brake resistor.

odrv0.config.brake_resistance

Note

There may be some extra resistance in your wiring and in the screw terminals, so if you are getting issues while braking you may want to increase this parameter by around 0.05 ohm.

Negative Current

This is the amount of current [Amps] allowed to flow back into the power supply. The convention is that it is negative. By default, it is set to a conservative value of 10mA. If you are using a brake resistor and getting DC_BUS_OVER_REGEN_CURRENT errors, raise it slightly. If you are not using a brake resistor and you intend to send braking current back to the power supply, set this to a safe level for your power source.

odrv0.config.dc_max_negative_current

Pole Pairs

This is the number of magnet poles in the rotor, divided by two. To find this, you can simply count the number of permanent magnets in the rotor, if you can see them.

odrv0.axis0.motor.config.pole_pairs

Note

This is not the same as the number of coils in the stator.

A good way to find the number of pole pairs is with a current limited power supply. Connect any two of the three phases to a power supply outputting around 2A, spin the motor by hand, and count the number of detents. This will be the number of pole pairs. If you can’t distinguish the detents from the normal cogging present when the motor is disconnected, increase the current. Another way is sliding a loose magnet in your hand around the rotor, and counting how many times it stops. This will be the number of pole pairs. If you use a ferrous piece of metal instead of a magnet, you will get the number of magnet poles.

Torque Constant

This is the ratio of torque produced by the motor per Amp of current delivered to the motor. This should be set to 8.27 / (motor KV).

odrv0.axis0.motor.config.torque_constant

If you decide that you would rather command torque in units of Amps, you could simply set the torque constant to 1.

Motor Type

This is the type of motor being used. Currently two types of motors are supported: High-current motors (MOTOR_TYPE_HIGH_CURRENT, [0]) and gimbal motors (MOTOR_TYPE_GIMBAL, [2]).

odrv0.axis0.motor.config.motor_type

Note

When using gimbal motors, current_lim and calibration_current actually mean voltage limit and calibration voltage respectively, since we don’t use current feedback. This means that if you set it to 10, it means 10V, despite the name of the parameter.

Motor Thermistor

If using motor thermistor please see the thermistors page for setup.

Encoder Configuration

With Encoder

Set the encoder count per revolution [CPR] value

odrv0.axis0.encoder.config.cpr

This is 4x the Pulse Per Revolution (PPR) value. Usually this is indicated in the datasheet of your encoder. If you purchased an encoder from our shop, you can find the parameters here.

Without Encoder

Save Configuration

You can save all .config parameters to persistent memory so the ODrive remembers them between power cycles. This will reboot the board.

odrv0.save_configuration()

Position control of M0

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. Start the calibratrion sequence by entering

odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

and press Enter.

After about 2 seconds you should hear a beep. Then the motor will turn slowly in one direction for a few seconds, then back in the other direction.

The startup procedure is demonstrated here.

Note

The rotor must be allowed to rotate without any biased load during startup. That means mass and weak friction loads are fine, but gravity or spring loads are not okay. Also note that in the video, the motors spin after initialization, but in the current software the default behaviour is not like that.

  1. Start closed loop control by typing

    odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    

    and press 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.motor.config.current_lim, 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 with

    odrv0.axis0.controller.input_pos = 1
    

    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. The ODrive can be used with a variety of control modes, to learn more, check out the control modes documentation page.

Watchdog Timer

Each axis has a configurable watchdog timer that can stop the motors if the control connection to the ODrive is interrupted.

Each axis has a configurable watchdog timeout: axis.config.watchdog_timeout, measured in seconds. Set

axis.config.enable_watchdog = True

to turn on this feature.

The watchdog is fed using the axis.watchdog_feed() method of each axis. Some ascii commands and most CANSimple commands feed the watchdog automatically.

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. * The CAN communication is the most reliable way of talking to ODrive in a real application. Check out the CAN Guide and CAN Protocol

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

Upgrading from 0.4.12

A new version (0.5.4) of ODrive firmware has released, complete with a new odrivetool. Follow the installation instructions, making sure to add the --upgrade flag to pip commands, and check out the Changelog for changes!

The odrivetool will stage and restore your configuration. This probably isn’t wise for the 0.4.12 -> 0.5.1 upgrade, so we suggest using odrv0.erase_configuration() immediately after connecting the first time.