Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions src-ODrive/docs/commands.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ Per-Axis Commands
-------------------------------------------------------------------------------

For the most part, both axes on the ODrive can be controlled independently.
Axis 0 corresponds to connector M0 and is accessed via :code:`odrv0.axis0`;
axis 1 corresponds to M1 and is accessed via :code:`odrv0.axis1`.

State Machine
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Expand Down Expand Up @@ -102,6 +104,8 @@ Diagnostics
* :code:`<odrv>.serial_number`: A number that uniquely identifies your device. When printed in upper case hexadecimal (:code:`hex(<odrv>.serial_number).upper()`), this is identical to the serial number indicated by the USB descriptor.
* :code:`<odrv>.fw_version_major`, :code:`<odrv>.fw_version_minor`, :code:`<odrv>.fw_version_revision`: The firmware version that is currently running.
* :code:`<odrv>.hw_version_major`, :code:`<odrv>.hw_version_minor`, :code:`<odrv>.hw_version_revision`: The hardware version of your ODrive.
* :code:`<odrv>.vbus_voltage`: The current DC bus voltage [V]. Useful for monitoring the power supply during operation.
* :code:`<odrv>.ibus`: The current drawn from the DC bus [A]. Positive values indicate current flowing from the supply into the ODrive.

.. _sensorless-setup:

Expand Down
4 changes: 2 additions & 2 deletions src-ODrive/docs/getting-started.rst
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ Safety & Power UP

.. _install-odrivetool:

Downloading and Installing :code:`odriveool`
Downloading and Installing :code:`odrivetool`
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

Most instructions in this guide refer to a utility called `odrivetool`, so you should install that first.
Expand Down Expand Up @@ -222,7 +222,7 @@ Start :code:`odrivetool`
--------------------------------------------------------------------------------

* To launch the main interactive ODrive tool, type :code:`odrivetool` and :kbd:`Enter`.
* Connect your ODrive and wait for the tool to find it. If it dos not connect after a few seconds refer to the :ref:`troubleshooting guide <troubleshooting>`.
* Connect your ODrive and wait for the tool to find it. If it does not connect after a few seconds refer to the :ref:`troubleshooting guide <troubleshooting>`.
* Now you can, for instance type :code:`odrv0.vbus_voltage` :kbd:`Enter` to inspect the boards main supply voltage.

It should look something like this:
Expand Down
36 changes: 35 additions & 1 deletion src-ODrive/docs/troubleshooting.rst
Original file line number Diff line number Diff line change
Expand Up @@ -163,4 +163,38 @@ Index search never completes

* There are some GPIO pin interrupt collisions on ODrive 3.6 that could cause index search to fail in certain conditions.
If you are using both step/dir and index pins, we recommend disabling :code:`step_dir_always_on`.
For more information, `see this thread <https://github.com/odriverobotics/ODrive/issues/605#issuecomment-971576393>`_.
For more information, `see this thread <https://github.com/odriverobotics/ODrive/issues/605#issuecomment-971576393>`_.

Motor does not respond to commands
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* Verify the axis is in :code:`AXIS_STATE_CLOSED_LOOP_CONTROL` by checking :code:`<axis>.current_state`.
* Run :code:`dump_errors(odrv0)` to check for any active errors that may be preventing motor movement.
* Confirm that calibration completed successfully. Re-run :code:`AXIS_STATE_FULL_CALIBRATION_SEQUENCE` if necessary.
* Check that the motor phase resistance and inductance measurements look reasonable.
A phase resistance of 0 or very high values usually indicates a wiring problem.

ODrive does not appear on USB / cannot connect
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* Make sure the ODrive has a valid 12–56V DC power supply connected; it does not power itself over USB.
* On **Linux**, verify the udev rules are installed (see :ref:`Getting Started <install-odrivetool>`).
Try running :code:`lsusb` to confirm the device is enumerated.
* On **Windows**, use `Zadig <http://zadig.akeo.ie/>`_ to ensure the driver for :code:`ODrive 3.x Native Interface` is set to :code:`WinUSB`.
* Try a different USB cable and a different USB port (preferably a USB 2.0 port directly on the motherboard).
* Ensure no other program (another :code:`odrivetool` instance, a serial monitor, etc.) is already connected to the ODrive.

Calibration fails immediately with MOTOR_ERROR_PHASE_RESISTANCE_OUT_OF_RANGE
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* Check the motor wiring. Loose or missing phase connections will cause this error.
* Verify the connector on the ODrive screw terminal is tight and making good contact.
* Make sure :code:`<axis>.motor.config.motor_type` is set correctly for your motor (high-current vs. gimbal).
* If the resistance is too high, try increasing :code:`<axis>.motor.config.calibration_current` slightly.

Encoder CPR is wrong / position drifts
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* Double-check the encoder CPR value. The :code:`cpr` setting must be **4 × PPR** (pulses per revolution).
* Verify the encoder A and B channels are not swapped. Swapped channels will cause the encoder to count in the wrong direction.
* For SPI encoders, confirm the SPI mode and clock settings match the encoder's datasheet.
55 changes: 55 additions & 0 deletions src-ODrive/tools/odrive/configuration.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,19 @@
from odrive.utils import OperationAbortedException, yes_no_prompt

def obj_to_path(root, obj):
"""
Returns the dot-separated attribute path of obj relative to root.

Recursively searches the attributes of root to find the object and builds
a string path such as "axis0.controller.config".

Args:
root: The root ODrive object to search from.
obj: The target object to find within root.

Returns:
str or None: The dot-separated path string if found, or None if not found.
"""
for k in dir(root):
v = getattr(root, k)
if not k.startswith('_') and isinstance(v, fibre.libfibre.RemoteObject):
Expand All @@ -18,6 +31,21 @@ def obj_to_path(root, obj):
return None

def get_dict(root, obj, is_config_object):
"""
Recursively builds a dictionary representation of an ODrive object's configuration.

Traverses the object tree and collects all config properties into a nested dict
suitable for JSON serialization.

Args:
root: The root ODrive object (used for resolving object references to paths).
obj: The current object to serialize.
is_config_object (bool): If True, scalar properties on this object are included.
Automatically set to True for sub-objects named 'config'.

Returns:
dict: A nested dictionary of configuration values.
"""
result = {}

for k in dir(obj):
Expand All @@ -35,6 +63,21 @@ def get_dict(root, obj, is_config_object):
return result

def set_dict(obj, path, config_dict):
"""
Applies a configuration dictionary to an ODrive object.

Recursively writes values from config_dict to the matching properties on obj.
Collects and returns a list of error messages for any properties that could
not be restored (e.g., renamed or removed in a newer firmware version).

Args:
obj: The ODrive object to apply configuration to.
path (str): Dot-separated path string for error reporting (use "" for the root).
config_dict (dict): Dictionary of configuration values to apply.

Returns:
list[str]: A list of error message strings for any properties that failed to restore.
"""
errors = []
for (k,v) in config_dict.items():
name = path + ("." if path != "" else "") + k
Expand All @@ -53,6 +96,18 @@ def set_dict(obj, path, config_dict):
return errors

def get_temp_config_filename(device):
"""
Returns the path to a temporary configuration file for the given ODrive device.

The filename is derived from the device's serial number, ensuring that each
device has a unique temporary config file in the system's temp directory.

Args:
device: The ODrive device object.

Returns:
str: The full path to the temporary configuration JSON file.
"""
serial_number = odrive.get_serial_number_str_sync(device)
safe_serial_number = ''.join(filter(str.isalnum, serial_number))
return os.path.join(tempfile.gettempdir(), 'odrive-config-{}.json'.format(safe_serial_number))
Expand Down
23 changes: 23 additions & 0 deletions src-ODrive/tools/odrive/shell.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,9 @@
from odrive.utils import *

def print_banner():
"""
Prints the ODrive welcome banner with links to documentation and community resources.
"""
print("Website: https://odriverobotics.com/")
print("Docs: https://docs.odriverobotics.com/")
print("Forums: https://discourse.odriverobotics.com/")
Expand All @@ -19,6 +22,17 @@ def print_banner():
print('You can also type help() or quit().')

def print_help(args, have_devices):
"""
Prints usage help for the interactive odrivetool shell.

Provides guidance on connecting to an ODrive and navigating its property tree
using tab completion.

Args:
args: Parsed command-line arguments (used to display the connection path).
have_devices (bool): If True, instructs the user to connect a device first;
otherwise shows usage examples assuming a device is already connected.
"""
print('')
if have_devices:
print('Connect your ODrive to {} and power it up.'.format(args.path))
Expand All @@ -42,6 +56,15 @@ def print_help(args, have_devices):
discovered_devices = []

def benchmark(odrv):
"""
Measures the asynchronous read throughput for the ODrive's vbus_voltage property.

Queues 1000 asynchronous reads and reports the time taken. Used to evaluate
the USB communication performance.

Args:
odrv: The ODrive object (e.g., odrv0).
"""
import asyncio
import time

Expand Down
Loading