Python Package

The odrive Python package provides an easy and intuitive way to control one or multiple ODrives from a Python script.

The package also contains the interactive command line tool odrivetool. odrivetool is documented separately here, whereas this page is for users who want to write scripts.

System Requirements

  • Python 3.7 or higher

  • Operating System:

    • Linux based on glibc 2.28 or higher (Ubuntu ≥ 20.04 / Debian ≥ 10 / …) (x86_64, ARM64)

    • Windows 10 or higher (x86_64)

    • macOS 12.0 (Monterey) or higher (Apple Silicon, Intel)

    If you are constrained to a system that is not supported, please contact us.

  • Full compatibility with all current generation ODrives (ODrive Pro, S1, Micro) on all firmware versions

  • Basic compatibility with ODrive v3.x, firmware v0.3.0 or higher

Installation

Quick install, if you’ve already done this kind of thing:

Command Line
python3 -m pip install --upgrade odrive

For detailed instructions and troubleshooting, see: odrivetool Installation.

Basic Example

This example assumes that you have already configured the ODrive in the GUI so that it’s ready for position control and you now want to control it from Python.

Full Example Script Here.

  1. Discover the ODrive (see also Discovery Use Cases):

    import odrive
    odrv0 = odrive.find_sync()
    
  2. Enter closed loop control:

    from odrive.enums import AxisState
    from odrive.utils import request_state
    
    request_state(odrv0.axis0, AxisState.CLOSED_LOOP_CONTROL)
    
  3. Run a sine wave:

    import math
    import time
    
    p0 = odrv0.axis0.controller.input_pos
    t0 = time.monotonic()
    while odrv0.axis0.current_state == AxisState.CLOSED_LOOP_CONTROL:
        setpoint = p0 + 4.0 * math.sin((time.monotonic() - t0) * 2) # [rev]
        print(f"goto {setpoint}")
        odrv0.axis0.controller.input_pos = setpoint
        time.sleep(0.01)
    
  4. If the loop exits for any reason, show errors:

The object odrv0 in this example can be used exactly like in the interactive odrivetool shell.

See ODrive API Reference for a list of all available properties and functions on the ODrive.

Async Usage

Interacting with ODrives is mostly I/O-oriented, therefore asynchronous programming is a natural fit. It allows for thread-like concurrency but in a single thread (learn more for example here). The odrive package can be used seamlessly with Python’s async/await syntax and asyncio library.

To turn your ODrive script into an async script, start by replacing odrive.find_sync() with await odrive.find_async(). This will return an ODrive object that is suitable for use in async/await code. find_async() behaves almost identically to find_sync(), except that all I/O operations become awaitable and the syntax for reading/writing properties changes.

Full Example Script Here.

Summary of the differences:

  1. Discovery

    odrv0 = odrive.find_sync() # Sync
    odrv0 = await odrive.find_async() # Async
    
  2. Reading properties

    pos = odrv0.axis0.pos_estimate # Sync
    pos = await odrv0.axis0.pos_estimate.read() # Async
    
  3. Writing properties

    odrv0.axis0.controller.input_pos = 5.0 # Sync
    await odrv0.axis0.controller.input_pos.write(5.0) # Async
    
  4. Using util functions

    from odrive.utils import request_state
    
    request_state(odrv0.axis0, AxisState.CLOSED_LOOP_CONTROL) # Sync
    await request_state(odrv0.axis0, AxisState.CLOSED_LOOP_CONTROL) # Async
    

Warning

Asynchronous ODrive objects are not thread-safe. They must only be used on the thread that was used for discovery and manages the backend. Multithreaded synchronous and single-threaded asynchronous styles can be mixed with odrive.utils.to_sync() and odrive.utils.to_async().

Discovery Use Cases

The examples below are for Async Usage. For synchronous usage, replace find_async() with find_sync().

Best Practices

Note

CAN is considered more reliable than USB for runtime operation. Full CAN support in the Python package is coming soon. Until then, if you want to use CAN, see separate CAN Bus Guide.

  • For initial development, it is recommended to set up the ODrive via the Web GUI and use the Python script only for runtime operation. Once it works as desired, you can export the config commands from the GUI (Configuration tab) and use Python to (re-)commission the ODrives in your application programmatically.

  • Keep ODrive setup (config & calibration) separate from runtime operation in the code. For fast iteration and easy debugging, you should be able to run either one without the other.

  • While in CLOSED_LOOP_CONTROL, continuously monitor <axis>.current_state to check if the ODrive stopped for any reason. If it stopped, inspect the error <axis>.disarm_reason. Depending on the error and on your application, restart the axis either automatically or upon user action.

  • Expect USB disconnects: On the ODrive side, enable the watchdog timer. On the Python side, ongoing operations (read, write, function calls) would fail with DeviceLostException on disconnect. Catch DeviceLostException, reconnect and treat it as any other axis error by restarting the axis (automatically or upon user interaction, depending on your application).

Reference

odrive

exception odrive.DeviceLostException(device: Device)

Exception that is thrown when any operation fails because the underlying device was disconnected.

odrive.find_any(*args, **kwargs)

Alias for find_sync().

async odrive.find_async(serial_number: ~typing.Sequence[str] | str | None = None, count: int | None = None, return_type: ~typing.Type[~odrive.device_manager.T] = <class 'odrive.async_tree.AsyncObject'>, device_type: ~odrive.libodrive.DeviceType | None = None) T

Waits until one or multiple ODrives are found and connected.

This is a wrapper around odrive.device_manager.DeviceManager.wait_for().

If the device manager was not initialized yet, it is initialized and bound to the current thread and event loop.

If a timeout is needed, consider wrapping this in asyncio.wait_for(find_any(...), timeout).

For a blocking, thread-safe wrapper, see find_sync().

odrive.find_sync(serial_number: ~typing.Sequence[str] | str | None = None, count: int | None = None, return_type: ~typing.Type[~odrive.device_manager.T] = <class 'odrive.sync_tree.SyncObject'>, timeout: float = None) T

Waits until one or multiple ODrives are found and connected.

This is a blocking, thread-safe wrapper around odrive.device_manager.DeviceManager.wait_for().

If the device manager was not initialized yet, this starts a background thread to run the backend.

For use with async/await, see find_async().

odrive.utils

Convenience functions for working with ODrives.

All members of odrive.utils are exposed directly in the odrivetool console but can also be used in user scripts.

odrive.utils.backup_config(device: RuntimeDevice | AsyncObject | SyncObject) dict

Returns a dict of the form {path: value} containing all properties on the ODrive that have “config” in their path.

Parameters:

device – The device to read from

odrive.utils.dump_errors(odrv: RuntimeDevice | AsyncObject | SyncObject, clear: bool = False)

Prints a summary of the error status of the device on stdout.

If you need the errors as a string instead, see format_errors().

async odrive.utils.format_errors(odrv: RuntimeDevice, clear: bool = False)

Returns a summary of the error status of the device formatted as RichText.

odrive.utils.request_state(axis: AsyncObject | SyncObject, state: AxisState)

Requests an axis to enter the specified state.

No effect if the axis is already in that state.

odrive.utils.restore_config(device: RuntimeDevice | AsyncObject | SyncObject, config: Dict[str, Any] | Tuple[str, Any])

Restores the configuration of the ODrive from a dictionary.

Parameters:
  • device – The ODrive to write the config to.

  • config – A dictionary of the form {path: value} or a list of tuples given in the form [(path: value)]

odrive.utils.run_state(axis: AsyncObject | SyncObject, state: AxisState)

Runs the requested state and waits until it finishes.

Example:

run_state(odrv0.axis0, AxisState.MOTOR_CALIBRATION)

Upon entering, all pending errors are cleared (clear_errors()). After entering the requested axis state, the function continuously polls the state and feeds the watchdog at 5Hz. If the state finishes successfully, the function returns normally. If the state finishes with an error, the function raises a odrive.exceptions.DeviceStateException. If the function is cancelled, the ODrive axis is commanded to IDLE.

odrive.utils.start_liveplotter(properties: List[AsyncProperty], layout: List[List[str]] | None = None, window_size: float = 5.0)

Starts the liveplotter. See also Liveplotter.

This function returns immediately, it does not block until the plot is closed. The liveplotter can be stopped by closing the figure or calling stop_liveplotter().

Raises an exception if a liveplotter is already open.

Parameters:
  • properties – A list of ODrive properties that shall be read.

  • layout – An optional nested list of keys that defines the subplots and the ordering of data within each subplot. Each string is a name of a plotted property, e.g. “axis0.pos_estimate”. If multiple ODrives are plotted, prepend the ODrive name. Each list of strings correspond to one subplot. If omitted, all properties are shown on a single subplot.

  • window_size – The size of the x-axis in number of samples.

odrive.utils.stop_liveplotter()

Stops the currently running liveplotter.

odrive.utils.to_async(odrv: RuntimeDevice | AsyncObject | SyncObject)

Converts an ODrive object that was obtained for synchronous usage (find_sync()) to an object that is suitable for asynchronous usage (see Async Usage).

The returned object must only be used on the same thread as the device manager (get_device_manager()).

odrive.utils.to_sync(odrv: RuntimeDevice | AsyncObject | SyncObject)

Converts an ODrive object that was obtained for asynchronous usage (find_async()) to an ODrive object that is suitable for synchronous usage (see Async Usage).

The returned object is thread-safe.

odrive.device_manager

class odrive.device_manager.DeviceManager(loop: AbstractEventLoop, lib: LibODrive)
subscribe(subscription: Subscription)

Adds a subscription to this device manager that will be notified when a matching device appears / disappears.

The subscription is also notified for all matching devices already present.

async wait_for(serial_number: ~typing.Sequence[str] | str | None = None, count: int | None = None, return_type: ~typing.Type[~odrive.device_manager.T] = <class 'odrive.runtime_device.RuntimeDevice'>, device_type: ~odrive.libodrive.DeviceType = None) T

Waits until one or multiple ODrives are found and connected.

If no arguments are given, the function waits for a single ODrive.

Specific ODrives can be selected by specifying their serial number. If the serial numbers are not known, count can be specified to wait for a certain number of ODrives.

The return type is either a single ODrive object (if no arguments are given or serial_number is given as a string) or a tuple of ODrives otherwise.

The ODrives that this function connects to are claimed for exclusive use by the current Python process and cannot be used by any other programs. Other ODrives are not claimed and can still be used by other programs.

Can be called multiple times, including simultaneously, from multiple async tasks on the same thread. Calls from multiple threads are not allowed. The returned ODrive object must not be used from any other thread than the one it was retrieved on (exception: if return_type is SyncObject).

See also: Discovery Use Cases, get_device_manager(), odrive.find_sync(), odrive.find_async().

Parameters:
  • serial_number – Single serial number or sequence (e.g. tuple or list) of multiple serial numbers. None to accept any serial number. If a sequence is specified, the returned tuple is in the same order.

  • count – Number of ODrives to wait for. Must be None if serial_number is specified.

class odrive.device_manager.Subscription(on_found: Callable[[Device], bool], on_lost: Callable[[Device], None], on_connected: Callable[[RuntimeDevice], None], on_disconnected: Callable[[RuntimeDevice], None], debug_name: str)

Subscription to be used with DeviceManager.subscribe().

Parameters:
  • on_found – Called when a device is found. The serial number is already available before the device is connected, so the application can use this callback to decide if the device shall be connected. The handler shall return True to request connection and False to ignore the device. If connection is requested, on_connected is called later. If multiple subscriptions are active, a connection is opened if any subscription accepts the device. Otherwise, if no subscription requests a connection, the device can be used by other applications.

  • on_lost – Called when a device is lost.

  • on_connected – Called when a connection with the device is established.

  • on_disconnected – Called when a device that was previously announced via on_connected is disconnected.

odrive.device_manager.close_device_manager()

Closes the global DeviceManager object (if it is open). All devices associated with it must be considered invalid after calling this.

This is called automatically upon exit of the program.

odrive.device_manager.get_device_manager() DeviceManager

Returns the global DeviceManager object. The first call to this function instantiates the device manager, initializes the backend and starts USB discovery.

The first call also defines which thread and asyncio event loop the device manager is bound to:

  • If the current thread has an event loop, the device manager is bound to the current thread and event loop.

  • If the current thread has no event loop, a background thread with an event loop is started.

Subsequent calls return the same device manager, until close_device_manager() is called.

The device manager and devices returned by it must only be used on the thread that it is bound to. An exception are the thread safe wrapper objects returned by odrive.find_sync() and odrive.utils.to_sync().