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 11.0 (Big Sur) 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().

Interfaces

By default, find_async() and friends will look for ODrives on USB and, when on Windows or macOS, on compatible USB-CAN adapters at 1Mbps.

When using SocketCAN on Linux, the SocketCAN interface must be explicitly specified.

You can set a specific list of interfaces by:

  • Changing default_interfaces once at the start of the script:

    from odrive.device_manager import get_device_manager
    get_device_manager().default_interfaces = {"can:can0"} # ignores USB and uses only can0 via SocketCAN
    
    odrv0 = odrive.find_sync() # Sync
    odrv0 = await odrive.find_async() # Async
    
  • or: passing an interface list directly to find_async() / find_sync():

    # Same functionality as the above
    odrv0 = odrive.find_sync(interfaces=["can:can0"]) # Sync
    odrv0 = await odrive.find_async(interfaces=["can:can0"]) # Async
    

Allowed interface strings:

  • "usb": Discover devices on USB

  • "usbcan[:baudrate]": Discover devices on compatible USB-CAN adapters. If baudrate is not specified, default_can_baudrate is used. Discovery of USB-CAN adapters themselves is started/stopped automatically as needed, regardless of whether "usb" is also in the list.

    Linux: USB-CAN adapters are usually claimed by the kernel and must be used through SocketCAN instead (unless they have been unbound, see Unbinding from SocketCAN on Linux).

  • "can:can0", "can:can1", …: Discover devices on specified SocketCAN interface(s) (Linux only).

Connection Livecycle

When an ODrive is retrieved via find_async(), find_sync() or wait_for(), a connection to the ODrive is opened.

Once connected, the ODrive can no longer be used by other programs. Attempts to connect to an ODrive that is already claimed by another program will result in an exception being raised or a warning being logged, depending on the arguments.

The ODrive can be disconnected by calling release_connection().

Within the same Python program, there can be multiple users of the same ODrive connection. In this case, the ODrive is connected on first discovery and disconnected on the last call to release_connection().

USB-CAN adapters are implicitly connected and disconnected as needed (see Interfaces). This means that on Windows and macOS, it is not possible to have multiple programs connect to different ODrives via the same USB-CAN adapter at the same time. On Linux this is possible via SocketCAN.

For more control over the connection lifecycle, see also use_connection(), release_connection(), use_device() and release_device().

Best Practices

  • For initial development, it is recommended to set up the ODrive via the Web GUI and use Python scripting 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.

  • CAN is considered more reliable than USB for runtime operation.

  • 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 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: Sequence[str] | str | None = None, *, count: int | None = None, return_type: Type[T] = AsyncObject, device_type: DeviceType | None = None, interfaces: List[str] | 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: Sequence[str] | str | None = None, *, count: int | None = None, return_type: Type[T] = SyncObject, timeout: float = None, device_type: DeviceType | None = None, interfaces: List[str] | None = 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, by default this starts a background thread to run the backend. However if the current thread already has an event loop (e.g. in an ipython shell or Jupyter Notebook), the device manager is initialized on the current thread and event loop instead.

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.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.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.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.restore_config(device: RuntimeDevice | AsyncObject | SyncObject, config: Dict[str, Any] | Tuple[str, Any], throw_on_error: bool = False, verify: bool = False)

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)]

  • throw_on_error – If True, raises an exception if any of the properties could not be found or set. If False, returns a list of errors. In both cases, the function does not exit on the first error, but continues to apply the rest of the config.

  • verify – If True, verifies that the values were set correctly. Some values may be successfully written at the protocol level, but ignored by the ODrive for example if they exceed a hardcoded limit.

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.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.high_rate_capture(odrv: RuntimeDevice | AsyncObject | SyncObject, properties: Iterable[str | int], unsafe: bool = False, trigger_point: float | None = DEFAULT_TRIGGER_POINT, trigger_timeout: float | None = None, return_as: Type[T] = list, t_fmt: TimestampFmt | None = None) T

Captures a short window of data from the ODrive at its native control loop rate.

The length of the window depends on how many variables are being captured.

For more information, see High Rate Capture.

Example:

from odrive.utils import high_rate_capture
data = await high_rate_capture(odrv, ['axis0.controller.pos_setpoint', 'axis0.pos_estimate'])
Parameters:
Returns:

The captured data, in the format specified by return_as.

odrive.utils.high_rate_capture_start(odrv: RuntimeDevice | AsyncObject | SyncObject, properties: Iterable[str | int], unsafe: bool = False)

Starts recording data on the ODrive at its native control loop rate.

Returns a HighRateCapturer that can be used to trigger and download the data using trigger(), wait() and download(), or trigger_and_download_sync() / trigger_and_download_async().

For a high level overview, see High Rate Capture.

Parameters:
Returns:

A HighRateCapturer object that can be used to trigger and download the data.

class odrive.utils.HighRateCapturer(odrv: RuntimeDevice, type_info: List[Tuple[Any, int, Callable[[bytes], Any]]], unsafe: bool)

Facility to capture variables from the ODrive at its native control loop rate.

For a high level overview and instructions how to use in odrivetool, see High Rate Capture.

Usage example from a Python script:

from odrive.utils import HighRateCapturer
capturer = await HighRateCapturer.from_properties(odrv, ['axis0.controller.pos_setpoint', 'axis0.pos_estimate'])
await capturer.start()
await capturer.trigger()
await capturer.wait()
data = await capturer.download()

For a shortcut, see high_rate_capture().

async static from_properties(odrv: RuntimeDevice, properties: Iterable[str | int], unsafe: bool = False) HighRateCapturer

Creates a HighRateCapturer object from a list of property names.

Parameters:
  • odrv – The ODrive to capture data from.

  • properties – The paths of the properties to capture, e.g. ['axis0.controller.pos_setpoint', 'axis0.pos_estimate'].

  • unsafe – Should be left as False unless instructed otherwise by ODrive support. If set to True, ODrive firmware can reset unexpectedly, potentially causing damage to the hardware.

async start()

Starts recording into a circular buffer on the ODrive. Once the buffer is full, the oldest samples are overwritten.

Only one HighRateCapturer instance can be active for each ODrive at a time. Starting multiple recordings at the same time causes corrupt data once download() is called.

async trigger(trigger_point: float = DEFAULT_TRIGGER_POINT)

Triggers the capture.

After the triggering, use wait() to wait for the recording to complete.

Has no effect if the capture was already triggered (by a previous call to this function or by the ODrive entering AxisState.IDLE).

Parameters:

trigger_point

Number in the range [0.0, 1.0] that defines the timing of the trigger relative to the capture window.

  • 0.0 means the resulting capture starts at trigger()

  • 1.0 means the resulting capture stops at trigger()

Defaults to 0.5.

async wait(timeout: float | None = None)

Waits for the recording to complete.

Recording completes shortly after the trigger. The trigger can is set off either manually by calling trigger() or automatically when the ODrive enters AxisState.IDLE (e.g. because of an error).

Parameters:

timeout – Optional maximum time [s] to wait for the recording to complete. If it is expected that the trigger already fired or will fire in a specific time, it is recommended to provide this parameter. Otherwise, can be omitted to wait indefinitely.

async download(return_as: Type[T] = list, t_fmt: TimestampFmt | None = None) T

Downloads and decodes the recorded data. Recording must have completed before calling this function (see wait()).

Parameters:
  • return_as

    The requested return type. Can be one of:

    • list: the result is returned as a list of lists where each inner list is the timeseries for one expression.

    • dict: the result is returned as a dict of the form:

      {
          'timestamps': [...], # according t_fmt
          'expr1': [...],
          'expr2': [...],
          ...
      }
      
    • numpy.ndarray: the result is returned as a 2D numpy array of shape (n_expressions, n_samples), similar to the list format.

    • numpy.recarray: the result is returned as a structured numpy array with the fields ‘timestamps’, ‘expr1’, ‘expr2’, etc, similar to the dict format.

  • t_fmt – The timestamp format. If None (default), no timestamps are included. If not None, timestamps are included as the first series in the result.

Returns:

The captured data, in the format specified by return_as and t_fmt.

async trigger_and_download_async(trigger_point: float | None = DEFAULT_TRIGGER_POINT, trigger_timeout: float | None = None, return_as: Type[T] = list, t_fmt: TimestampFmt | None = None) T

Combines trigger(), wait() and download() into a single function call.

This function is asynchronous and intended for use in async scripts. For use in odrivetool or synchronous scripts, use trigger_and_download_sync().

Parameters:
Returns:

The captured data, in the format specified by return_as.

trigger_and_download_sync(trigger_point: float | None = DEFAULT_TRIGGER_POINT, trigger_timeout: float | None = None, return_as: Type[T] = list, t_fmt: TimestampFmt | None = None) T

Combines trigger(), wait() and download() into a single function call.

This function is synchronous and intended for use in odrivetool or synchronous scripts. For asynchronous usage, use trigger_and_download_async().

Parameters:
Returns:

The captured data, in the format specified by return_as.

class odrive.utils.TimestampFmt(value, names=_not_given, *values, module=None, qualname=None, type=None, start=1, boundary=None)

Timestamp format to use in HighRateCapturer.download().

CONTROL_CYCLE = 1

Timestamps are integers that increment by 1 for each control cycle. Currently the ODrive’s control loop frequency is fixed at 8kHz.

NANOSECONDS = 2

Timestamps are nanoseconds relative to the trigger point.

NANOSECONDS_PYTHON = 3

Timestamps are with respect to the Python monotonic clock time.monotonic_ns().

The correlation is based on a best effort of correlating the ODrive’s clock with. On a Raspberry Pi 4, the accuracy was observed to be in the range of 1ms - 5ms, but can be worse in some cases (e.g. high CPU load or garbage collect event). The correlation happens at the time of download(), so if the data is downloaded significantly later than the trigger, the correlation may be less accurate due to clock drift.

odrive.device_manager

class odrive.device_manager.DeviceManager(loop: AbstractEventLoop, lib: LibODrive, no_json_cache: bool = False)

Facilitates discovery and connection to ODrive devices.

The DeviceManger should be used as a singleton and can be retrieved via get_device_manager(). The global instance can be used independently by multiple parts of the user application and manages the lifecycle of resources for multiple users. This includes:

  • opening/closing interfaces

  • starting/stopping discovery on interfaces

  • connecting/disconnecting devices

default_interfaces: Set[str]

The default interfaces on which to discover devices when wait_for(), find_sync(), find_async() or subscribe() is called without specifying interfaces explicitly.

The default value is {"usb", "usbcan"} on Windows and macOS, and {"usb"} on Linux.

See Interfaces for details.

default_can_baudrate: int

The default baudrate to use for USB-CAN adapters.

The default value is 1Mbps (1000000).

This can be overridden by specifying an interface string with a baudrate suffix, e.g. "usbcan:500000". See Interfaces for details.

subscribe(filter_spec: FilterSpec, delegate: DeviceManagerDelegate, passive: bool = False, debug_name: str | None = None) Subscription

Starts device discovery.

The requested interfaces are started automatically if needed, unless passive is True.

Returns an opaque handle that can be passed to unsubscribe().

Parameters:
  • filter_spec – Which devices to look for and on which interfaces to look. The delegate is only notified about devices that match the filter.

  • delegate – The delegate that will be notified about devices that match the filter.

  • passive – If True, this subscription does not automatically start/ stop interfaces according to filter_spec.interfaces but still receives events for devices on those interfaces. If False (default), interfaces are started and stopped automatically according to filter_spec.interfaces.

  • debug_name – An optional name for this subscription, used for logging.

unsubscribe(subscription: Subscription)

Stop a discovery process that was previously started with subscribe().

The devices that were found during discovery are closed and forgotten, unless they are retained with retain().

The underlying interfaces are closed if no longer needed.

async wait_for(*, interfaces: List[str] | None = None, serial_number: Sequence[str] | str | None = None, count: int | None = None, return_type: Type[T] = RuntimeDevice, device_type: Sequence[DeviceType] | DeviceType | None = None) T

Waits until one or multiple ODrives are found and connected.

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

Specific ODrives can be selected by specifying their serial number. In this case, connection errors on matching ODrives are propagated to the caller as exceptions.

Alternatively, count can be specified to wait for a certain number of ODrives with any serial number. In this case, connection errors are not propagated and the function continues to look.

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.

Discovery happens on all interfaces specified by default_interfaces or the interfaces parameter if provided.

When a device returned by this function is no longer needed, the user application can optionally call release_connection() to allow another application to claim it. See also Connection Livecycle.

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(), subscribe(), unsubscribe().

Parameters:
  • interfaces

    The interfaces on which to enable discovery. If None, the device manager’s default_interfaces is used. See Interfaces for details.

    The corresponding interfaces are initialized and discovery started as needed. When the function finishes, discovery is stopped and the interfaces are deinitialized as appropriate. If devices were found, they keep the corresponding interface open until released.

  • 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 devices to wait for. Must be None if serial_number is specified.

  • return_type – The type of the returned object. For normal use, this will be either RuntimeDevice, SyncObject or AsyncObject. To request an unconnected device, use Device. In this case, the device muse be released with release_device() instead of release_connection(). Other return types are reserved for internal use.

  • device_type – The type of devices to wait for. Should be omitted for normal use as it is implied by return_type.

async use_connection(dev: Device, baudrate: int | None = None, release_device: bool = False, catch_exception: bool = False) Device | RuntimeDevice | CanAdapter

Increments the use count of the connection of the device. Connects to the device if it was not connected yet.

This call should be matched with a call to release_connection(), unless the device is lost from the backend side.

Parameters:
  • dev – The raw Device to connect to.

  • baudrate – If the device is a USB-CAN adapter, this specifies the baudrate to use for the connection. If None, the default baudrate of the device manager is used.

Returns:

The connected device. This is a RuntimeDevice, CanAdapter or Device depending on the device type.

release_connection(dev: Device | RuntimeDevice | CanAdapter)

Decrements the use count of the connection of the device. Disconnects from the device if the use count reaches zero.

This can be used to release devices obtained through wait_for() or to mirror a call to use_connection().

This can also close the underlying interface if it is no longer in use.

If the device is lost (e.g. due to a physical disconnect), calling this function has no effect and can be omitted.

use_device(dev: Device)

Increments the use count of a device. Similar to use_connection(), but does not request a connection. Keeps the underlying interface alive until the corresponding call to release_device() or the device is lost.

release_device(dev: Device)

Decrements the use count of a device. Closes the underlying interface if it is no longer in use.

This can be used to release raw Device objects obtained through wait_for(return_type=Device) or to mirror a call to use_device().

If the device is lost (e.g. due to a physical disconnect), calling this function has no effect and can be omitted.

class odrive.device_manager.Subscription

Opaque handle for DeviceManager.subscribe() and DeviceManager.unsubscribe().

class odrive.device_manager.FilterSpec

Filter specification for DeviceManager.subscribe().

The filter check passes if a device matches all of the specified criteria.

interfaces: List[str | Interface] | None = None

List of interfaces on which to consider devices.

For allowed values see Interfaces.

If None, the behavior depends on the context:

  • For autostarting interfaces, the default interfaces are used

  • For passive checks (match()) all interfaces are accepted.

serial_numbers: List[str] | None = None

List of serial numbers to consider. If None, all serial numbers are considered.

device_types: List[DeviceType] | None = None

List of device types to consider. If None, all device types are considered.

match(dev: Device) bool

Checks if the device matches the filter specification.

class odrive.device_manager.DeviceManagerDelegate

Delegate for use with DeviceManager.subscribe(). The subscriber can implement the callbacks that it is interested in.

on_found_device(dev: Device) bool

Called when any device that matches the filter is found.

Can be called multiple times for the same physical device if it’s found on multiple interfaces.

To connect to the device, the application can call use_connection(). To keep the device around beyond unsubscribe(), but without connecting to it, the application can call use_device().

on_lost_device(dev: Device)

Called when any device that matches the filter is lost. If the device was previously connected, on_disconnected_device() is called beforehand.

on_connected_device(dev: Device | RuntimeDevice | CanAdapter)

Called when any device that matches the filter is connected.

on_disconnected_device(dev: Device | RuntimeDevice | CanAdapter)

Called when any device that matches the filter is disconnected.

exception odrive.device_manager.NotConnectableException

Raised when the application tries to connect to a device that is not connectable. This can happen if the device was discovered on a CAN interface but its firmware does not support connecting over CAN.

odrive.device_manager.get_device_manager(force_background_thread: bool = False) 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().

Parameters:

on_other_thread – If True, forces the device manager to be started on a background thread, even if the current thread has an event loop.

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.

Changelog

This section only shows changes to odrivetool and the Python package. For the firmware changelog, see here.

[0.6.11] - 2026-05-05

  • Added:

  • Removed:

    • Removed deprecated --path argument from odrivetool. This argument did not have any effect in recent versions.

  • Fixed:

    • Occasional error when starting liveplotter: liveplotter failed: index -1 is out of bounds for axis 0 with size 0

    • Restore of config.gpioX_analog_mapping.endpoint and config.gpioX_pwm_mapping.endpoint when using odrivetool restore-config or odrive.utils.restore_config(). This fixes a regression in 0.6.10 where these configs, if used, were restored incorrectly, effectively disabling the PWM/analog mapping.

    • Improved reliability of reconnecting after reboot with buggy USB hubs

    • Fixed very slow USB connect times on some Windows machines (regression in 0.6.10)

    • find_any() in Jupyter Notebooks (used to raise RuntimeError: asyncio.run() cannot be called from a running event loop)

    • Fix global variables when odrivetool is used in --no-ipython mode

  • Changed:

    • Migrate backend from to libodrive 0.8.x to libodrive 0.9.x

    • Removed dependency on appdirs package

    • odrivetool new-dfu firmware.elf now exits with an error message when firmware.elf is for another hardware version, unless --force is passed.

    • SpiEncoderMode.RLS renamed to SpiEncoderMode.RLS_ORBIS

    • SpiEncoderMode.AMS renamed to SpiEncoderMode.AMS_AS50XX

    • SpiEncoderMode.CUI renamed to SpiEncoderMode.CUI_AMT23

    • SpiEncoderMode.MA732 renamed to SpiEncoderMode.MPS_MAGALPHA

    • SpiEncoderMode.AEAT renamed to SpiEncoderMode.BROADCOM_AEAT

    • SpiEncoderMode.TLE renamed to SpiEncoderMode.INFINEON_TLE

    • SpiEncoderMode.NOVOHALL renamed to SpiEncoderMode.NOVOHALL_RSC2800

    • Rs485EncoderMode.AMT21_POLLING renamed to Rs485EncoderMode.CUI_AMT21_POLLING

    • Rs485EncoderMode.AMT21_EVENT_DRIVEN renamed to Rs485EncoderMode.CUI_AMT21_EVENT_DRIVEN

[0.6.10] - 2025-04-15

This version contains a major update to the backend and may fix issues not listed here.

  • Added:

    • ability to connect to selected ODrives only and use unconnected ODrives in other programs

    • --name argument to define custom names for the interactive odrivetool shell

    • cleaner ways to discover devices in scripts (Discovery Use Cases)

    • optional seamless async usage with example script (or mixed sync/async usage)

  • Removed:

    • support for Python <3.7

    • support for manylinux_2_28_armv7l (System Requirements)

    • removed utils:

      • previously documented: BulkCapture and MachineConfig / AxisConfig / related

      • previously undocumented: step_and_plot(), oscilloscope_dump(), get_user_name(), benchmark(), devices() and possibly more

  • Fixed: spurious warning when ODrive is rebooted

  • Changed:

    • cleaned up global namespace in interactive odrivetool

    • changed signature of start_liveplotter()

    • improved performance

[0.6.9] - 2024-05-17

  • Added: odrivetool new-dfu and odrivetool install-bootloader: support for new DFU system

  • Changed: Flattened JSON format of odrivetool backup-config/restore-config

  • Changed: removed legacy command odrivetool drv-status. Use dump_errors(odrv0) instead.

[0.6.8] - 2024-01-11

  • Added: Initial ODrive Micro support

  • Fixed: Fixed libfibre-linux-aarch64.so: wrong ELF class: ELFCLASS64 when running Python in 32-bit mode on 64-bit Linux

  • Fixed: Avoid creating empty files in firmware cache when download fails

  • Changed: Added odrivetool legacy-dfu as alias for odrivetool dfu

[0.6.7] - 2023-07-13

  • Fixed: dump_errors() decoding and related minor compatibility issues in Python 3.11 (caused by changes in enum module).

  • Fixed: Tell user to use DFU switch in cases where DFU is known to fail otherwise.

[0.6.5] - 2023-03-13

  • Added: --no-erase-all flag for DFU

  • Added: Presumably fixed slow resource leak on Windows that could slow down odrivetool after several hours.

  • Added: Show firmware version when a device connects

  • Fixed: Silence warning “protocol failed with 3 - propagating error to application”. This warning was harmless and therefore distracting.

  • Fixed: Occasional error Transfer on EP XX still in progress. This is gonna be messy., sometimes followed by a segmentation fault, when disconnecting an ODrive.

[0.6.3] - 2022-08-22

  • Fixed: System level errors on legacy hardware will now be parsed correctly

[0.6.1] - 2022-06-17

  • Added: --version option for odrivetool dfu

  • Fixed:

    • fix enum decoding compatibility with firmware 0.5.4

    • Added back missing old-style enum names (such as ENCODER_MODE_HALL, used in some versions of the docs and corresponding to EncoderMode.HALL)

    • Compatibility with Python 3.6

    • Added missing enum value ODriveError.CALIBRATION_ERROR (fixes UNKNOWN ERROR: 0x40000000)

    • Fix corruption of Python interpreter. When __pycache__ was clear (e.g. on first load of the odrive module), on ODrive discovery the backend would overwrite Python’s b'\0' buffer with something non-zero, resulting in subsequent unexpected behavior such as print(b'\0') => ':'.

[0.6.0] - 2021-09-30

  • Added: experimental machine-centric configuration system. See example_config, status(example_config), apply(example_config) and calibrate(example_config).

  • Changed: enum naming convention from AXIS_STATE_CLOSED_LOOP_CONTROL to AxisState.CLOSED_LOOP_CONTROL