ODrive Reference
- class ODrive
Toplevel interface of your ODrive.
The odrv0, odrv1, … objects that appear in odrivetool implement this toplevel interface.
- get_adc_voltage(gpio) float
Reads the ADC voltage of the specified GPIO. The GPIO should be in
GpioMode.ANALOG_IN
.- Parameters:
gpio (int) –
- erase_configuration()
Resets all config variables to their default values and reboots the controller
- reboot()
Reboots the controller without saving the current configuraiton
- enter_dfu_mode()
Enters the Device Firmware Update mode provided by the MCU manufacturer (DFU-over-USB)
- enter_dfu_mode2() bool
Experimental
Enters the ODrive Device Firmware Update mode (DFU-over-CAN).
The bootloader, when first started, will set itself as the primary startup target and write-protect its own flash sectors.
Therefore, after calling this function, older firmware (0.6.4 and older) can no longer be installed / booted on the device. This can be reversed by calling
disable_bootloader()
.Returns false if the ODrive bootloader is not installed.
- disable_bootloader() bool
Experimental
Disables the bootloader.
This unprotects the flash sectors containing the bootloader and causes the device to start the main firmware (rather than the bootloader) on startup.
The bootloader can be re-activated by calling
enter_dfu_mode2()
.Calling this function is necessary before downgrading to an older firmware version that was not yet compatible with the bootloader.
- get_interrupt_status(irqn) int
Returns information about the specified interrupt number.
- Parameters:
irqn (int) – -12…-1: processor interrupts, 0…239: NVIC interrupts
- get_dma_status(stream_num) int
Returns information about the specified DMA stream.
- Parameters:
stream_num (int) – 0…7: DMA1 streams, 8…15: DMA2 streams
- clear_errors()
Clear all the errors of this device including all contained submodules.
- vbus_voltage: [Volt] - Float32Property
Voltage on the DC bus as measured by the ODrive.
- ibus: [Amp] - Float32Property
Current on the DC bus as calculated by the ODrive.
A positive value means that the ODrive is consuming power from the power supply, a negative value means that the ODrive is sourcing power to the power supply.
This value is equal to the sum of the motor currents and the brake resistor currents. The motor currents are measured, the brake resistor current is calculated based on
config.brake_resistor0.resistance
.
- ibus_report_filter_k: Float32Property
Filter gain for the reported ibus. Set to a value below 1.0 to get a smoother line when plotting ibus. Set to 1.0 to disable. This filter is only applied to the reported value and not for internal calculations.
- serial_number: Uint64Property
- hw_version_major: Uint8Property
- hw_version_minor: Uint8Property
- hw_version_variant: Uint8Property
- hw_version_revision: Uint8Property
- fw_version_major: Uint8Property
- fw_version_minor: Uint8Property
- fw_version_revision: Uint8Property
- commit_hash: Uint32Property
- fw_version_unreleased: Uint8Property
0 for official releases, 1 otherwise
- n_evt_sampling: Uint32Property
Number of input sampling events since startup (modulo 2^32)
- n_evt_control_loop: Uint32Property
Number of control loop iterations since startup (modulo 2^32)
- task_timers_armed: BoolProperty
Set by a profiling application to trigger sampling of a single control iteration. Cleared by the device as soon as the sampling is complete.
- task_times: ODrive.TaskTimes
- system_stats: ODrive.SystemStats
- user_config_loaded: Uint32Property
- misconfigured: BoolProperty
If this property is true, something is bad in the configuration. The ODrive can still be used in this state but the user should investigate which setting is problematic. This variable does not cover all misconfigurations.
- Possible causes:
A GPIO was set to a mode that it doesn’t support
A GPIO was set to a mode for which the corresponding feature was not enabled. Example:
GpioMode.UART_A
was used without enablingconfig.enable_uart_a
.A feature was enabled which is not supported on this hardware. Example:
config.enable_uart_c
set to true on ODrive v3.x.A GPIO was used as an interrupt input for two internal components or two GPIOs that are mutually exclusive in their interrupt capability were both used as interrupt input. Example:
config.step_gpio_pin
of both axes were set to the same GPIO.
- oscilloscope: ODrive.Oscilloscope
- can: ODrive.Can
- test_property: Uint32Property
- identify: BoolProperty
Flashes the status LED when enabled.
This is intended to help identify a particular ODrive in a setup with multiple devices.
- reboot_required: BoolProperty
Can be used by support software to indicate that a reboot is required.
- amt21_encoder_group0: ODrive.Amt21EncoderGroup0
- issues: ODrive.Issues
Experimental
- class ODrive.TaskTimes
- sampling: ODrive.TaskTimer
- encoder_update: ODrive.TaskTimer
- control_loop_misc: ODrive.TaskTimer
- control_loop_checks: ODrive.TaskTimer
- current_sense_wait: ODrive.TaskTimer
- dc_calib_wait: ODrive.TaskTimer
- class ODrive.SystemStats
- uptime: Uint32Property
- min_heap_space: Uint32Property
- max_stack_usage_axis: Uint32Property
- max_stack_usage_usb: Uint32Property
- max_stack_usage_uart: Uint32Property
- max_stack_usage_can: Uint32Property
- max_stack_usage_startup: Uint32Property
- stack_size_axis: Uint32Property
- stack_size_usb: Uint32Property
- stack_size_uart: Uint32Property
- stack_size_startup: Uint32Property
- stack_size_can: Uint32Property
- prio_axis: Int32Property
- prio_usb: Int32Property
- prio_uart: Int32Property
- prio_startup: Int32Property
- prio_can: Int32Property
- class ODrive.Amt21EncoderGroup0
- status: Property[ODrive.ComponentStatus]
- raw: Float32Property
- class ODrive.Config
- enable_uart_a: BoolProperty
Enables/disables UART_A.
You also need to set the corresponding GPIOs to
GpioMode.UART_A
. Refer to the UART Interface page to see which pins support UART_A. Changing this requires a reboot.
- uart_a_baudrate: [baud/s] - Uint32Property
Defines the baudrate used on the UART interface.
Some baudrates will have a small timing error due to hardware limitations.
Here’s an (incomplete) list of baudrates for ODrive v3.x:
Configured
Actual
Error [%]
1.2 KBps
1.2 KBps
0
2.4 KBps
2.4 KBps
0
9.6 KBps
9.6 KBps
0
19.2 KBps
19.195 KBps
0.02
38.4 KBps
38.391 KBps
0.02
57.6 KBps
57.613 KBps
0.02
115.2 KBps
115.068 KBps
0.11
230.4 KBps
230.769 KBps
0.16
460.8 KBps
461.538 KBps
0.16
921.6 KBps
913.043 KBps
0.93
1.792 MBps
1.826 MBps
1.9
1.8432 MBps
1.826 MBps
0.93
For more information refer to Section 30.3.4 and Table 142 (the column with f_PCLK = 42 MHz) in the STM datasheet.
- enable_can_a: BoolProperty
Enables CAN. Changing this setting requires a reboot.
- usb_cdc_protocol: Property[ODrive.StreamProtocolType]
The protocol that’s being run on the device’s virtual COM port on USB. Note that the ODrive has two independent interfaces on USB: One is the virtual COM port (affected by this option) and the other one is a vendor specific interface which always runs Fibre. So changing this option does not affect the working of odrivetool.
- uart0_protocol: Property[ODrive.StreamProtocolType]
- max_regen_current: [Amp] - Float32Property
The bus current allowed to flow back to the power supply before the brake resistor module will start shunting current.
- dc_bus_undervoltage_trip_level: [Volt] - Float32Property
Minimum voltage below which the motor stops operating.
This parameter defaults and is limited to the board’s minimum operating voltage.
- dc_bus_overvoltage_trip_level: [Volt] - Float32Property
Maximum DC bus voltage above which the motor stops operating.
This protects against cases in which the power supply fails to dissipate the brake power if the brake resistor is disabled.
This parameter defaults and is limited to the board’s maximum operating voltage.
On some revisions of ODrive S1, the board’s maximum operating voltage depends on
config.brake_resistor0.enable
. Refer to the specifications of your device for details.
- dc_max_positive_current: [Amp] - Float32Property
Max current the power supply can source.
- dc_max_negative_current: [Amp] - Float32Property
Max current the power supply can sink.
This is the amount of current 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. Note that in that case, it should be higher than your motor current limit + current limit margin.Set to -INFINITY to disable.
- class ODrive.Can
- error: Property[ODrive.Can.Error]
- n_restarts: Uint32Property
- n_rx: Uint32Property
- config: ODrive.Can.Config
- class ODrive.Axis
- watchdog_feed()
Feed the watchdog to prevent watchdog timeouts.
- set_abs_pos(pos) float
Set the absolute position of the axis.
Returns the distance by which the reference was shifted. Add this to the previous position on any off-board controllers to effect an impulse free change of reference.
Do not use while in trajectory control mode.
- Parameters:
pos (float) –
- active_errors: Property[ODrive.Error]
Indicates the current error condition(s) of the axis. Each error flag clears automatically when the error condition goes away. If an attempt is made to activate the axis while an error is present, the axis immediately disarms and disarm_reason is updated accordingly.
- disarm_reason: Property[ODrive.Error]
This value is updated every time the axis disarms and indicates the reason why the axis was disarmed. It can be cleared using clear_errors(). This variable is used for reporting only. It affects the status LED and the ERROR pin output but it does not prevent the axis from getting re-armed upon user request.
- step_dir_active: BoolProperty
- last_drv_fault: Uint32Property
- steps: Int64Property
The current commanded position, in steps, while in step_dir mode
- current_state: Property[ODrive.Axis.AxisState]
The current state of the axis
- requested_state: Property[ODrive.Axis.AxisState]
The user’s commanded axis state
This is used to command the axis to change state or perform certain routines. Values input here will be “consumed” and queued by the state machine handler. Thus, reading this value back will usually show
AxisState.UNDEFINED
(0).
- is_homed: BoolProperty
Whether or not the axis has been successfully homed.
- config: ODrive.Axis.Config
- motor: ODrive.Motor
- controller: ODrive.Controller
- trap_traj: ODrive.TrapezoidalTrajectory
- min_endstop: ODrive.Endstop
- max_endstop: ODrive.Endstop
- mechanical_brake: ODrive.MechanicalBrake
- pos_vel_mapper: ODrive.Mapper
- commutation_mapper: ODrive.Mapper
- interpolator: ODrive.Interpolator
- task_times: ODrive.Axis.TaskTimes
- procedure_result: Property[ODrive.ProcedureResult]
- disarm_time: Float32Property
- is_armed: BoolProperty
- class ODrive.BrakeResistor
- current_meas: Float32Property
- current_meas_status: Uint32Property
- duty: Float32Property
- additional_duty: Float32Property
Experimental
Additional duty cycle to add, on top of the value that is based on motor current and DC voltage.
- current: [Amp] - Float32Property
Calculated current dumped into the brake resistor.
This value is not measured but calculated based the configured brake resistance. It is therefore only reliable if the actual brake resistance matches the configured brake resistance.
In the future this might take into account feedback from current_meas.
- chopper_temp: Float32Property
Estimate of the brake resistor chopper temperature.
- is_armed: BoolProperty
- is_saturated: BoolProperty
Indicates if the brake resistor reached saturation. This flag is latching and needs to be reset by the client before it can indicate another saturation event.
- class ODrive.BrakeResistorConfig
- enable: BoolProperty
Enable/disable the use of a brake resistor.
Setting this to False even though a brake resistor is connected is harmless. Setting this to True even though no brake resistor is connected can break the power supply. Changes to this value require a reboot to take effect.
Setting this to true reduces the maximum value for
config.dc_bus_overvoltage_trip_level
on some revisions of ODrive S1. Refer to the specifications of your device for details.
- resistance: [Ohm] - Float32Property
Value of the brake resistor connected to the ODrive.
Note that 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.
If you set this to a lower value than the true brake resistance then the ODrive will not meed the
max_regen_current
constraint during braking, that is it will sink more thanmax_regen_current
into the power supply. Some power supplies don’t like this. If you set this to a higher value than the true brake resistance then the ODrive will unnecessarily burn more power than required during braking.
- enable_dc_bus_voltage_feedback: BoolProperty
Enables the DC bus voltage feedback brake resistor feature.
If enabled, if the measured DC voltage exceeds
dc_bus_voltage_feedback_ramp_start
, the ODrive will sink additional power into the the brake resistor to bring or hold the voltage down.- The brake duty cycle is increased by the following amount:
ODrive.vbus_voltage
==dc_bus_voltage_feedback_ramp_start
, => brake_duty_cycle += 0%ODrive.vbus_voltage
==dc_bus_voltage_feedback_ramp_end
, => brake_duty_cycle += 100%
- Remarks:
This feature is active even when all motors are disarmed.
This feature is disabled if
resistance
is not a positive value.
- dc_bus_voltage_feedback_ramp_start: Float32Property
See
enable_dc_bus_voltage_feedback
.Do not set this lower than your usual
ODrive.vbus_voltage
,
- dc_bus_voltage_feedback_ramp_end: Float32Property
See
enable_dc_bus_voltage_feedback
.Must be larger than
dc_bus_voltage_feedback_ramp_start
, otherwise the ramp feature is disabled.
- class ODrive.Motor
- alpha_beta_controller: ODrive.AlphaBetaFrameController
- fet_thermistor: ODrive.OnboardThermistorCurrentLimiter
- motor_thermistor: ODrive.OffboardThermistorCurrentLimiter
- acim_estimator: ODrive.AcimEstimator
- sensorless_estimator: ODrive.SensorlessEstimator
- torque_estimate: [Nm] - Float32Property
Motor torque from measured current and
config.motor.torque_constant
- mechanical_power: [W] - Float32Property
Motor mechanical power (torque * speed)
- electrical_power: [W] - Float32Property
Motor electrical power (modulation * voltage * current)
- effective_current_lim: [Amp] - Float32Property
This value is the internally-limited value of phase current allowed according and is the minimum of the following:
config.motor.current_soft_max
, optionally derated based on motor temperature.config.inverter0.current_soft_max
, optionally derated based on ODrive power stage temperature.Maximum measurable current range
- resistance_calibration_I_beta: Float32Property
- input_id: [Amp] - Float32Property
Feedforward term for d-axis current. If ACIM autoflux is enabled, this parameter has no effect.
- input_iq: [Amp] - Float32Property
Feedforward term for q-axis current.
- class ODrive.Mapper
- set_abs_pos(pos) float
Sets the absolute position of the Mapper. This can be useful on the pos_vel_mapper but it’s a bad idea on the commutation_mapper.
- Parameters:
pos (float) –
- status: Property[ODrive.ComponentStatus]
- pos_rel: Float32Property
Relative position since startup in turns. On the
commutation_mapper
this wraps around such that it’s always in [0, 1). On thepos_vel_mapper
this wraps around if and only if<axis>.controller.config.circular_setpoints
is set.
- pos_abs: Float32Property
Absolute position. On
pos_vel_mapper
this is only available if the axis is homed.
- vel: Float32Property
- config: ODrive.Mapper.Config
- class ODrive.OnboardEncoder
- get_field_strength() float
The measurement is a very rough estimate, discretized into 9 values:
<26mT (indicated as 0), 30mT, 45mT, 60mT, 74mT, 88mT, 102mT, 116mT, >120mT (indicated as inf)
Position readings on this encoder will be stopped for roughly 100ms when this function is called.
This is intended for development / end-of-line testing / diagnostics only. The function uses five NVM write cycles on the encoder, which is rated for only 1000 write cycles. Therefore this should not be used during regular operation.
Gives a rough estimate on the magnetic field strength at the encoder in Tesla.
- status: Property[ODrive.ComponentStatus]
- raw: Float32Property
- class ODrive.IncrementalEncoder
- status: Property[ODrive.ComponentStatus]
- pos_min: Float32Property
- pos_max: Float32Property
- pos_residual: Float32Property
- raw: Uint16Property
- class ODrive.HallEncoder
- status: Property[ODrive.ComponentStatus]
- hall_cnt: Uint8Property
- raw_hall_state: Uint8Property
- abs_pos_min: Float32Property
- abs_pos_max: Float32Property
- config: ODrive.HallEncoder.Config
- class ODrive.SpiEncoder
- get_field_strength() float
The unit depends on the encoder mode.
SpiEncoderMode.TLE: scale from 0…1023. This is a copy of the value
MAG
from theD_MAG
register. See TLE5012B user manual for reference. Returns NAN in case of a communication error (e.g. encoder disconnected).All other encoders: Not implemented. Returns NAN.
Gives a rough estimate on the magnetic field strength at the encoder.
- status: Property[ODrive.ComponentStatus]
- raw: Float32Property
- n_errors: Uint32Property
Number of error events of this encoder.
Wraps around to zero at 2^32-1.
- Possible error events:
Transfer took too long.
Encoder reported an error (currently only applicable to
SpiEncoderMode.AMS
).
- inject_errors: BoolProperty
Deliberately injects occasional communication errors. For testing only.
- config: ODrive.SpiEncoder.Config
- class ODrive.EncoderEstimator
- status: Property[ODrive.ComponentStatus]
- pos_estimate: Float32Property
- vel_estimate: Float32Property
- class ODrive.Interpolator
- status: Property[ODrive.ComponentStatus]
- interpolation: Float32Property
- config: ODrive.Interpolator.Config
- class ODrive.AlphaBetaFrameController
- current_meas_phA: Float32Property
- current_meas_phB: Float32Property
- current_meas_phC: Float32Property
- current_meas_status_phA: Uint32Property
- current_meas_status_phB: Uint32Property
- current_meas_status_phC: Uint32Property
- I_bus: [Amp] - Float32Property
The current in the ODrive DC bus. This is also the current seen by the power supply in most systems.
- Ialpha_measured: Float32Property
- Ibeta_measured: Float32Property
- max_measurable_current: [Amp] - Float32Property
Indicates the maximum current that can be measured by the current sensors in the current hardware configuration. This value depends on
<axis>.config.motor.current_hard_max
andconfig.inverterN.current_hard_max
.
- power: [Watt] - Float32Property
DEPRECATED: Use
<axis>.motor.electrical_power
. The electrical power being delivered to the motor.
- n_evt_current_measurement: Uint32Property
Number of current measurement events since startup (modulo 2^32)
- n_evt_pwm_update: Uint32Property
Number of PWM update events since startup (modulo 2^32)
- class ODrive.FieldOrientedController
- p_gain: Float32Property
- i_gain: Float32Property
- I_measured_report_filter_k: Float32Property
- Id_setpoint: Float32Property
- Iq_setpoint: Float32Property
- Vd_setpoint: Float32Property
- Vq_setpoint: Float32Property
- phase: Float32Property
- phase_vel: Float32Property
- Id_measured: [Amp] - Float32Property
The phase current measured along the “d” axis in the FOC control loop.
This should be close to 0 for typical surface permanent magnet motors.
- Iq_measured: [Amp] - Float32Property
The phase current measured along the “q” axis in the FOC control loop.
This is the torque-generating current, so motor torque is approx.
torque_constant * Iq_measured
- v_current_control_integral_d: Float32Property
- v_current_control_integral_q: Float32Property
- mod_d: Float32Property
- mod_q: Float32Property
- final_v_alpha: Float32Property
- final_v_beta: Float32Property
- class ODrive.Oscilloscope
- config(addr0, addr1, addr2, addr3, addr4, addr5, addr6, addr7, addr8)
- trigger_high_res()
Experimental
- size: Uint32Property
- pos: Uint32Property
- rollover: BoolProperty
- recording: BoolProperty
- class ODrive.AcimEstimator
- rotor_flux: [Amp] - Float32Property
estimated magnitude of the rotor flux
- slip_vel: [Hz] - Float32Property
estimated slip between physical and electrical angular velocity}
- phase_offset: [cycles] - Float32Property
estimate offset between physical and electrical angular position}
- stator_phase_vel: [Hz] - Float32Property
calculated setpoint for the electrical velocity}
- stator_phase: [cycles] - Float32Property
calculated setpoint for the electrical phase}
- class ODrive.Controller
- move_incremental(displacement, from_input_pos)
Moves the axes’ goal point by a specified increment.
- input_pos: [rev] - Float32Property
Set the desired position of the axis. Only valid in
ControlMode.POSITION_CONTROL
. InInputMode.TUNING
, this acts as a DC offset for the position sine wave.
- input_vel: [rev/s] - Float32Property
In
ControlMode.VELOCITY_CONTROL
, sets the desired velocity of the axis. InControlMode.POSITION_CONTROL
, sets the feed-forward velocity of the velocity controller InInputMode.TUNING
, this acts as a DC offset for the velocity sine wave.
- input_torque: [Nm] - Float32Property
In
ControlMode.TORQUE_CONTROL
, sets the desired output torque of the axis. InControlMode.VELOCITY_CONTROL
andControlMode.POSITION_CONTROL
, sets the feed-forward torque of the torque controller. InInputMode.TUNING
, this acts as a DC offset for the torque sine wave.
- pos_setpoint: [rev] - Float32Property
The position reference actually being used by the position controller. This is the same as
input_pos
inInputMode.PASSTHROUGH
, but may vary according toInputMode
.
- vel_setpoint: [rev/s] - Float32Property
The velocity reference actually being used by the velocity controller. This is the same as
input_vel
inInputMode.PASSTHROUGH
, but may vary according toInputMode
.
- torque_setpoint: [Nm] - Float32Property
The torque reference actually being used by the torque controller. This is the same as
input_torque
inInputMode.PASSTHROUGH
, but may vary according toInputMode
.
- effective_torque_setpoint: [Nm] - Float32Property
The torque output generated by the controller and fed to the motor model.
- trajectory_done: BoolProperty
Indicates the last commanded Trapezoidal Trajectory movement is complete.
- vel_integrator_torque: [Nm] - Float32Property
The accumulated value of the velocity loop integrator
- autotuning_phase: [rad] - Float32Property
The current phase angle of the
InputMode.TUNING
sine wave generator
- config: ODrive.Controller.Config
- autotuning: ODrive.Controller.Autotuning
- spinout_mechanical_power: [Watt] - Float32Property
Mechanical power estimate. Torque * velocity
- spinout_electrical_power: [Watt] - Float32Property
Electrical power estimate. Vdq*Idq
- class ODrive.SensorlessEstimator
- phase: [rad] - Float32Property
- pll_pos: [rad] - Float32Property
- phase_vel: [rad/s] - Float32Property
- class ODrive.TrapezoidalTrajectory
- class ODrive.Endstop
- endstop_state: BoolProperty
- config: ODrive.Endstop.Config
- class ODrive.MechanicalBrake
- engage()
This function engages the mechanical brake if one is present and enabled.
- release()
This function releases the mechanical brake if one is present and enabled.
- config: ODrive.MechanicalBrake.Config
- class ODrive.TaskTimer
- start_time: Uint32Property
- end_time: Uint32Property
- length: Uint32Property
- max_length: Uint32Property
- class ODrive.InverterConfig
- current_soft_max: [Amp] - Float32Property
Maximum commanded current allowed for this inverter. See also
motor.current_soft_max
.Writes to this parameter are ignored unless in developer mode.
- current_hard_max: [Amp] - Float32Property
Maximum measured current allowed for this inverter. Any measurement above
current_hard_max
will throw aCURRENT_LIMIT_VIOLATION
error. See alsomotor.current_hard_max
.Writes to this parameter are ignored unless in developer mode.
- temp_limit_lower: Float32Property
The lower limit when the controller starts limiting current. Writes to this parameter are ignored unless in developer mode.
- temp_limit_upper: Float32Property
The upper limit when current limit reaches 0 Amps and an over temperature error is triggered. Writes to this parameter are ignored unless in developer mode.
- shunt_conductance: Float32Property
Set this to 1.0 / R_shunt if you have modified the shunt resistors. Writes to this parameter are ignored unless in developer mode.
- drv_config: Uint64Property
Do not modify unless you know what you’re doing. Writes to this parameter are ignored unless in developer mode.
- class ODrive.GpioMode
- DIGITAL = 0 (0x0)
The pin can be used for one or more of these functions: Step, dir, enable, encoder index, hall effect encoder, SPI encoder nCS (this one is exclusive).
- DIGITAL_PULL_UP = 1 (0x1)
Same as DIGITAL but with the internal pull-up resistor enabled.
- DIGITAL_PULL_DOWN = 2 (0x2)
Same as DIGITAL but with the internal pull-down resistor enabled.
- ANALOG_IN = 3 (0x3)
The pin can be used for one or more of these functions: Sin/cos encoders, analog input,
get_adc_voltage()
.
- UART_A = 4 (0x4)
See
config.enable_uart_a
.
- UART_B = 5 (0x5)
This mode is not supported on ODrive v3.x.
- UART_C = 6 (0x6)
This mode is not supported on ODrive v3.x.
- CAN_A = 7 (0x7)
See
config.enable_can_a
.
- I2C_A = 8 (0x8)
See
config.enable_i2c_a
.
- SPI_A = 9 (0x9)
Note that the SPI pins on ODrive v3.x are hardwired so they cannot be configured through software. Consequently
- ENC0 = 11 (0xB)
The pin is used by quadrature encoder 0.
- ENC1 = 12 (0xC)
The pin is used by quadrature encoder 1.
- ENC2 = 13 (0xD)
This mode is not supported on ODrive v3.x.
- MECH_BRAKE = 14 (0xE)
This is to support external mechanical brakes.
- STATUS = 15 (0xF)
The pin is used for status output (see
axis.config.error_gpio_pin
)
- BRAKE_RES = 16 (0x10)
The pin is used to control a brake resistor board.
- AUTO = 17 (0x11)
Let the ODrive decide how to use the pin. If multiple components try to use the same pin only one of them will be initialized and the other one will have a status of kBadConfig.
- class ODrive.StreamProtocolType
- FIBRE = 0 (0x0)
Machine-to-machine protocol which gives access to all features of the ODrive. This protocol is used by the official odrivetool and GUI. Developers who wish to interact with this protocol are advised to do so through libfibre.
- ASCII = 1 (0x1)
Human readable protocol designed for easy implementation for cases where the use of libfibre is not desired or feasible. Refer to this page ` for details.
- STDOUT = 2 (0x2)
Output of printf(). Only intended for developers who modify ODrive firmware.
- ASCII_AND_STDOUT = 3 (0x3)
Combination of Ascii and Stdout.
- OTHER = 4 (0x4)
The port is being used by another component (in the future: flow graph component). Currently this is only the AMT21 component.
- class ODrive.ComponentStatus
- NOMINAL = 0 (0x0)
- NO_RESPONSE = 1 (0x1)
- INVALID_RESPONSE_LENGTH = 2 (0x2)
- PARITY_MISMATCH = 3 (0x3)
- ILLEGAL_HALL_STATE = 4 (0x4)
- POLARITY_NOT_CALIBRATED = 5 (0x5)
- PHASES_NOT_CALIBRATED = 6 (0x6)
- NUMERICAL_ERROR = 7 (0x7)
- MISSING_INPUT = 8 (0x8)
- RELATIVE_MODE = 9 (0x9)
- UNCONFIGURED = 10 (0xA)
- OVERSPEED = 11 (0xB)
- INDEX_NOT_FOUND = 12 (0xC)
- BAD_CONFIG = 13 (0xD)
- NOT_ENABLED = 14 (0xE)
- SPINOUT_DETECTED = 15 (0xF)
- class ODrive.Error
- INITIALIZING = 1 (0x1)
The system is initializing or reconfiguring.
- SYSTEM_LEVEL = 2 (0x2)
Unexpected system error such as memory corruption, stack overflow, frozen thread, assert fail etc. This error is indicates firmware bug.
- TIMING_ERROR = 4 (0x4)
An internal hard timing requirement was violated. This usually means that the device is computationally overloaded, either due to a specific user configuration or due to a firmware bug. This error should not occur during normal operation and can be considered similar to SYSTEM_ERROR.
- MISSING_ESTIMATE = 8 (0x8)
The position estimate, velocity estimate or phase estimate was needed but invalid. This can mean:
The encoder has not been calibrated. Consult the documentation to see how to calibrate various encoder types.
Absolute position control was used before the axis was homed.
One of the active encoders is misbehaving or disconnected. Check the error information of all enabled encoders to see if this is the case.
- BAD_CONFIG = 16 (0x10)
The ODrive configuration is invalid or incomplete. If you configured the ODrive through the GUI, this indicates a bug in the GUI.
Please verify the following:
axis.config.motor.direction is -1 or +1
axis.config.torque_soft_min <= axis.config.torque_soft_max
config.enable_brake_resistor = False or
config.brake_resistor0.resistance
> 0axis.config.motor.phase_resistance and axis.config.motor.phase_inductance are valid, axis.config.motor.phase_resistance_valid = True and, axis.config.motor.phase_inductance_valid = True
- DRV_FAULT = 32 (0x20)
The gate driver chip reported an error.
If this keeps occurring during normal operation within the device’s specified operating conditions this can indicate hardware damage.
- MISSING_INPUT = 64 (0x40)
No value was provided for
input_pos
,input_vel
orinput_torque
.This typically happens when using RC PWM as input and entering
AxisState.CLOSED_LOOP_CONTROL
before any pulse was registered. Make sure the PWM input is configured and connected correctly.
- DC_BUS_OVER_VOLTAGE = 256 (0x100)
The DC voltage exceeded the limit configured in
config.dc_bus_overvoltage_trip_level
.Confirm that you have a brake resistor of the correct value connected securely and that
config.brake_resistor0.resistance
is set to the value of your brake resistor.You can monitor your PSU voltage using liveplotter in odrivetool by entering
start_liveplotter(lambda: [odrv0.vbus_voltage])
. If during a move you see the voltage rise above your PSU’s nominal set voltage then you have your brake resistance set too low. This may happen if you are using long wires or small gauge wires to connect your brake resistor to your odrive which will added extra resistance. This extra resistance needs to be accounted for to prevent this voltage spike. If you have checked all your connections you can also try increasing your brake resistance by ~ 0.01 ohm at a time to a maximum of 0.05 greater than your brake resistor value.
- DC_BUS_UNDER_VOLTAGE = 512 (0x200)
The DC voltage fell below the limit configured in
config.dc_bus_undervoltage_trip_level
.Confirm that your power leads are connected securely. For initial testing a 12V PSU which can supply a couple of amps should be sufficient while the use of low current ‘wall wart’ plug packs may lead to inconsistent behaviour and is not recommended.
You can monitor your PSU voltage using liveplotter in odrivetool by entering
start_liveplotter(lambda: [odrv0.vbus_voltage])
. If you see your votlage drop belowconfig.dc_bus_undervoltage_trip_level
(default: ~ 8V) then you will trip this error. Even a relatively small motor can draw multiple kW momentary and so unless you have a very large PSU or are running of a battery you may encounter this error when executing high speed movements with a high current limit. To limit your PSU power draw you can limit your motor current and/or velocity limit<axis>.controller.config.vel_limit
and<axis>.config.motor.current_soft_max
.
- DC_BUS_OVER_CURRENT = 1024 (0x400)
Too much DC current was pulled, either at the motor level or at the board level (these two are identical for boards that don’t support a brake resistor).
At the motor level:
<axis>.motor.alpha_beta_frame_controller.I_bus
exceeded<axis>.config.I_bus_hard_max
At the board level:
<odrv>.ibus
exceededconfig.dc_max_positive_current
.
- DC_BUS_OVER_REGEN_CURRENT = 2048 (0x800)
Too much DC current was regenerated, either at the motor level or at the board level (these two are identical for boards that don’t support a brake resistor).
At the motor level:
<axis>.motor.alpha_beta_frame_controller.I_bus
exceeded (was more negative than)<axis>.config.I_bus_hard_min
At the board level:
<odrv>.ibus
exceeded (was more negative than)config.dc_max_negative_current
.
This can happen if your brake resistor is unable to handle the braking current. Check that (V_power_supply / brake_resistance) >
<axis>.config.motor.current_hard_max
.
- CURRENT_LIMIT_VIOLATION = 4096 (0x1000)
The motor current exceeded
<axis>.config.motor.current_hard_max
. orconfig.inverterN.current_hard_max
.The current controller tries not to exceed
<axis>.config.motor.current_soft_max
, however a bit of overshoot is normal. Therefore, if you get this error, try to increase the margin between the soft and hard current limits.If you have to increase the margin to more than 40% then something else might be wrong, for instance the motor could be damaged or the current controller might be unstable.
The current controller is a PI controller and its PI gains are automatically calculated based on
config.motor.current_control_bandwidth
and the motor resistance and inductance (pole placement). If you suspect an unstable current controller, make sure to review these variables.
- MOTOR_OVER_TEMP = 8192 (0x2000)
The motor thermistor measured a temperature above
motor.motor_thermistor.config.temp_limit_upper
- INVERTER_OVER_TEMP = 16384 (0x4000)
The inverter thermistor measured a temperature above
motor.fet_thermistor.config.temp_limit_upper
- VELOCITY_LIMIT_VIOLATION = 32768 (0x8000)
The estimated velocity exceeds
vel_limit_tolerance
*vel_limit
- POSITION_LIMIT_VIOLATION = 65536 (0x10000)
- WATCHDOG_TIMER_EXPIRED = 16777216 (0x1000000)
The axis watchdog timer expired.
An amount of time greater than
config.watchdog_timeout
passed without the watchdog being fed.
- ESTOP_REQUESTED = 33554432 (0x2000000)
- An estop was requested from an external source. This can mean:
The estop message was received on CAN
An endstop was pressed
- SPINOUT_DETECTED = 67108864 (0x4000000)
- OTHER_DEVICE_FAILED = 134217728 (0x8000000)
Another device (axis or brake resistor) in the machine failed.
- THERMISTOR_DISCONNECTED = 268435456 (0x10000000)
The motor thermistor is enabled but disconnected. This is determined by the analog voltage lying too close to 0V or 3.3V.
- CALIBRATION_ERROR = 1073741824 (0x40000000)
A calibration procedure failed. See
procedure_result
for details.
- class ODrive.ProcedureResult
- SUCCESS = 0 (0x0)
The procedure finished without any faults.
- BUSY = 1 (0x1)
The procedure has not yet finished.
- CANCELLED = 2 (0x2)
The last procedure was cancelled by the user.
- DISARMED = 3 (0x3)
A fault was encountered and the axis has been disarmed. See
disarm_reason
for more info.
- NO_RESPONSE = 4 (0x4)
The procedure component did not respond as expected
Most likely due to an improperly connected/configured encoder.
Verify the encoder configuration matches the hardware
Check that the encoder is powered and all signals are connected correctly
- POLE_PAIR_CPR_MISMATCH = 5 (0x5)
The values of
...config.motor.pole_pairs
and/or...inc_encoder0.config.cpr
do not corroborate the measured rotations. Please verify these settings match the hardware.Note
If not using an incremental encoder the cpr value is not used and can be ignored
- PHASE_RESISTANCE_OUT_OF_RANGE = 6 (0x6)
The measured motor phase resistance is outside of the plausible range.
During calibration the motor resistance and inductance is measured. If the measured motor resistance or inductance falls outside a predefined range this error will be returned. Check that all motor leads are connected securely.
The measured values can be viewed using odrivetool as is shown below:
In [2]: odrv0.axis0.config.motor.phase_inductance Out[2]: 1.408751450071577e-05 In [3]: odrv0.axis0.config.motor.phase_resistance Out[3]: 0.029788672924041748
Some motors will have a considerably different phase resistance and inductance than this. For example, gimbal motors, some small motors (e.g. < 10A peak current). If you think this applies to you try increasing
config.motor.resistance_calib_max_voltage
from its default value of 1 and repeat the motor calibration process. Increasing this value beyond the feasible range (around half of DC voltage) has no effect. Therefore, if you maxed outconfig.motor.resistance_calib_max_voltage
and still get calibration errors, try reducingconfig.motor.calibration_current
.If your motor has a small peak current rating (e.g. < 20A) you should also decrease
config.motor.calibration_current
from its default value of 10A.In general, you need:
- PHASE_INDUCTANCE_OUT_OF_RANGE = 7 (0x7)
The measured motor phase inductance is outside of the plausible range.
See
PHASE_RESISTANCE_OUT_OF_RANGE
for details.
- UNBALANCED_PHASES = 8 (0x8)
The motor phase resistances are not balanced. Please check your connections.
- INVALID_MOTOR_TYPE = 9 (0x9)
The value of
...config.motor.motor_type
is not defined in theMotorType
enum.
- ILLEGAL_HALL_STATE = 10 (0xA)
During hall encoder calibration the ODrive detected too many bad hall states. Make sure your encoder is wired correctly and produces a clean signal.
- TIMEOUT = 11 (0xB)
- HOMING_WITHOUT_ENDSTOP = 12 (0xC)
Homing was requested without enabling the endstop. Make sure
<axis>.min_endstop.config.enabled <ODrive.Endstop.Config>enabled
is True.
- INVALID_STATE = 13 (0xD)
The requested state must be a valid
AxisState
.
- NOT_CALIBRATED = 14 (0xE)
The requested state could not be entered because the axis is not calibrated.
The required calibrations depend on the axis configuration, the requested state and the requested control mode.
The most common cause for this error is requesting
AxisState.CLOSED_LOOP_CONTROL
before first runningAxisState.MOTOR_CALIBRATION
andAxisState.ENCODER_OFFSET_CALIBRATION
.
- NOT_CONVERGING = 15 (0xF)
The calibration did not converge.
The measurements made during a calibration task did not reach sufficient statistical significance.
For instance during
AxisState.ENCODER_OFFSET_CALIBRATION
the encoder did not move sufficiently to determine the direction between encoder and motor.Try changing the calibration parameters.
- class ODrive.EncoderId
- NONE = 0 (0x0)
- INC_ENCODER0 = 1 (0x1)
- INC_ENCODER1 = 2 (0x2)
- INC_ENCODER2 = 3 (0x3)
- SENSORLESS_ESTIMATOR = 4 (0x4)
- SPI_ENCODER0 = 5 (0x5)
- SPI_ENCODER1 = 6 (0x6)
- SPI_ENCODER2 = 7 (0x7)
- HALL_ENCODER0 = 8 (0x8)
- HALL_ENCODER1 = 9 (0x9)
- AMT21_ENCODER0 = 10 (0xA)
- AMT21_ENCODER1 = 11 (0xB)
- AMT21_ENCODER2 = 12 (0xC)
- ONBOARD_ENCODER0 = 13 (0xD)
- ONBOARD_ENCODER1 = 14 (0xE)
- class ODrive.SpiEncoderMode
- DISABLED = 0 (0x0)
- RLS = 1 (0x1)
- AMS = 2 (0x2)
- CUI = 3 (0x3)
- AEAT = 4 (0x4)
- MA732 = 5 (0x5)
- TLE = 6 (0x6)
- class ODrive.MotorType
- HIGH_CURRENT = 0 (0x0)
Used for all standard “hobby-style” motors Permanant Magnet AC (PMAC) or Brushless DC (BLDC) motors. This is the default. Note: Assumes sinusoidal back-EMF, “wye” connected motors. Trapezoidal bEMF may have reduced controllability.
- GIMBAL = 2 (0x2)
Enables voltage-only FOC where V=IR can be assumed to be correct. Used for high-phase-resistance motors (> 1 ohm), which are typically sold as “Gimbal” motors.
- ACIM = 3 (0x3)
Used for FOC control of AC Induction Motors (ACIM), aka Asynchronous motors,
- class ODrive.SystemStats.Usb
- rx_cnt: Uint32Property
- tx_cnt: Uint32Property
- tx_overrun_cnt: Uint32Property
- class ODrive.SystemStats.I2C
- addr: Uint8Property
- addr_match_cnt: Uint32Property
- rx_cnt: Uint32Property
- error_cnt: Uint32Property
- class ODrive.Amt21EncoderGroup0.Config
- enable: BoolProperty
- rs485: Uint8Property
- gpio: Uint8Property
- addr0: Uint8Property
- event_driven_mode: BoolProperty
- class ODrive.Can.Config
- baud_rate: Uint32Property
The baudrate of the CAN bus. Only compatible baudrates are accepted. The baud rate must be integer-divisible by 10’000’000. Note that baudrates above 1’000’000 violate the CAN classic specification.
- protocol: Property[ODrive.Can.Protocol]
- class ODrive.Axis.Config
- startup_max_wait_for_ready: [sec] - Float32Property
Maximum time to wait for
active_errors_
to go clear before trying to start any of the startup actions. Default 3 seconds.
- startup_motor_calibration: BoolProperty
Run motor calibration at startup, skip otherwise
- startup_encoder_index_search: BoolProperty
Run encoder index search after startup, skip otherwise this only has an effect if
commutation_mapper.config.use_index_gpio
is also true
- startup_encoder_offset_calibration: BoolProperty
Run encoder offset calibration after startup, skip otherwise
- startup_closed_loop_control: BoolProperty
Enable closed loop control after calibration/startup
- startup_homing: BoolProperty
Enable homing after calibration/startup
- enable_step_dir: BoolProperty
Enable step/dir input after calibration. Make sure to set the corresponding GPIO’s mode to
GpioMode.DIGITAL
.
- step_dir_always_on: BoolProperty
Keep step/dir enabled while the motor is disabled. This is ignored if enable_step_dir is false. This setting only takes effect on a state transition into idle or out of closed loop control.
- calib_range: Float32Property
- calib_scan_distance: Float32Property
- calib_scan_vel: Float32Property
- index_search_at_target_vel_only: BoolProperty
- watchdog_timeout: [sec] - Float32Property
- enable_watchdog: BoolProperty
Enables the watchdog for this axis.
When the watchdog expires (after
config.watchdog_timeout
), the axis is put intoAxisState.IDLE
. The watchdog can be reset by the functionaxis.watchdog_feed()
, or by certain UART or CAN messages. See the respective interface documenation for details.
- step_gpio_pin: Uint16Property
- dir_gpio_pin: Uint16Property
- error_gpio_pin: Uint16Property
- enable_error_gpio: BoolProperty
- calibration_lockin: ODrive.Axis.Config.CalibrationLockin
- sensorless_ramp: ODrive.Axis.LockinConfig
- general_lockin: ODrive.Axis.LockinConfig
- load_encoder: Property[ODrive.EncoderId]
- commutation_encoder: Property[ODrive.EncoderId]
- encoder_bandwidth: Float32Property
Applies to both commutation and load encoder. If the same encoder is used for both axes, this is ignored on axis0.
- I_bus_hard_min: [Amp] - Float32Property
If the controller fails to keep this motor’s DC current (
axis.motor.alpha_beta_frame_controller.I_bus
) above this value the motor gets disarmed immediately. Most likely you want a negative value here. Set to-inf
to disable. Take noise into account when choosing a value.
- I_bus_hard_max: [Amp] - Float32Property
If the controller fails to keep this motor’s DC current (
axis.motor.alpha_beta_frame_controller.I_bus
) below this value the motor gets disarmed immediately. Usually this is set in conjunction withI_bus_hard_min
. Set toinf
to disable. Take noise into account when choosing a value.
- torque_soft_min: [Nm] - Float32Property
Minimum negative commanded torque allowed in the torque loop. This is usually a negative number.
- torque_soft_max: [Nm] - Float32Property
Maximum positive commanded torque allowed in the torque loop. If you set this, in all likelihood you also want to set
torque_soft_min
.
- motor: ODrive.Axis.Config.Motor
- class ODrive.Axis.TaskTimes
- thermistor_update: ODrive.TaskTimer
- sensorless_estimator_update: ODrive.TaskTimer
- endstop_update: ODrive.TaskTimer
- can_heartbeat: ODrive.TaskTimer
- controller_update: ODrive.TaskTimer
- open_loop_vector_generator_update: ODrive.TaskTimer
- acim_estimator_update: ODrive.TaskTimer
- motor_update: ODrive.TaskTimer
- current_controller_update: ODrive.TaskTimer
- current_sense: ODrive.TaskTimer
- pwm_update: ODrive.TaskTimer
- class ODrive.Axis.LockinConfig
- initial_pos: [erev] - Float32Property
Sets the electrical angle at which the lockin spin starts. In most cases this can be left at zero.
- current: [Amp] - Float32Property
- ramp_time: [sec] - Float32Property
- ramp_distance: [erev] - Float32Property
- accel: [erev/s^2] - Float32Property
- vel: [erev/s] - Float32Property
- finish_distance: [erev] - Float32Property
- finish_on_vel: BoolProperty
- finish_on_distance: BoolProperty
- class ODrive.Axis.CanConfig
- node_id: Uint32Property
Changes take effect after a reboot
- is_extended: BoolProperty
Changes take effect after a reboot
- version_msg_rate_ms: Uint32Property
- heartbeat_msg_rate_ms: Uint32Property
- encoder_msg_rate_ms: Uint32Property
- iq_msg_rate_ms: Uint32Property
- error_msg_rate_ms: Uint32Property
- temperature_msg_rate_ms: Uint32Property
- bus_voltage_msg_rate_ms: Uint32Property
- torques_msg_rate_ms: Uint32Property
- class ODrive.Axis.AxisState
- UNDEFINED = 0 (0x0)
will fall through to idle
- IDLE = 1 (0x1)
Disable motor PWM and do nothing.
- STARTUP_SEQUENCE = 2 (0x2)
Run the startup procedure.
the actual sequence is defined by the config.startup… flags
- FULL_CALIBRATION_SEQUENCE = 3 (0x3)
Run motor calibration and then encoder offset calibration (or encoder index search if
commutation.config.use_index_gpio
is True).
- MOTOR_CALIBRATION = 4 (0x4)
Measure phase resistance and phase inductance of the motor.
To store the results save the configuration (
save_configuration()
).
After that you don’t have to run the motor calibration on the next start up. * This modifies the variables
config.motor.phase_resistance
andconfig.motor.phase_inductance
.
- ENCODER_INDEX_SEARCH = 6 (0x6)
Turn the motor in one direction until the encoder index is traversed.
This state can only be entered if
commutation.config.use_index_gpio
is True).
- ENCODER_OFFSET_CALIBRATION = 7 (0x7)
Turn the motor in one direction for a few seconds and then back to measure the offset between the encoder position and the electrical phase.
Can only be entered if the motor is calibrated
- CLOSED_LOOP_CONTROL = 8 (0x8)
Run closed loop control.
The action depends on the controller.config.control_mode.
Can only be entered if the motor is calibrated
- LOCKIN_SPIN = 9 (0x9)
Run lockin spin.
Can only be entered if the motor is calibrated (
config.motor.phase_resistance_valid
and
- ENCODER_DIR_FIND = 10 (0xA)
Run encoder direction search.
Can only be entered if the motor is calibrated (
config.motor.phase_resistance_valid
and
- HOMING = 11 (0xB)
Run axis homing function.
Endstops must be enabled to use this feature.
- ENCODER_HALL_POLARITY_CALIBRATION = 12 (0xC)
Rotate the motor in lockin and calibrate hall polarity
ODrive assumes 120 degree electrical hall spacing. This routine determines if that is the case and sets the polarity if the halls are on 60 degree electrical spacing
- ENCODER_HALL_PHASE_CALIBRATION = 13 (0xD)
Rotate the motor for 30s to calibrate hall sensor edge offsets
The phase offset is not calibrated at this time, so the map is only relative
- class ODrive.Axis.Config.CalibrationLockin
- current: Float32Property
- ramp_time: Float32Property
- ramp_distance: Float32Property
- accel: Float32Property
- vel: Float32Property
- class ODrive.Axis.Config.Motor
- motor_type: Property[ODrive.MotorType]
- pole_pairs: Uint32Property
Number of magnet pole pairs in the motor’s rotor.
This is the number of magnet poles in the rotor, divided by two. This is not the same as the number of coils in the stator.
To find this, you can simply count the number of permanent magnets in the rotor, if you can see them.
Otherwise 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_.
- phase_resistance: [Ohm] - Float32Property
- phase_inductance: [Henry] - Float32Property
- phase_resistance_valid: BoolProperty
Indicates whether phase resistance is valid. This flag is automatically set to true after successful motor calibration. It can also be set manually if phase_resistance is set manually. The motor will not spin unless this is true.
- phase_inductance_valid: BoolProperty
Indicates whether phase_resistance and phase_inductance are valid. This flag is automatically set to true after successful motor calibration. It can also be set manually if phase_inductance is set manually. The motor will not spin unless this is true.
- torque_constant: [Nm / A] - Float32Property
Torque constant of the motor.
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).
If you decide that you would rather command torque in units of Amps, you could simply set the torque constant to 1.
If you don’t command/monitor torque directly but only use velocity/position control, this value has no effect.
- direction: Float32Property
Direction of the motor (+1 or -1) with respect to the axis position space. This affects the spin direction of calibration procedures.
- current_control_bandwidth: [rad/s] - Float32Property
Sets the PI gains of the Q and D axis FOC control according to phase_resistance and phase_inductance to create a critically-damped controller with a -3dB bandwidth at this frequency.
- wL_FF_enable: BoolProperty
Enables automatic feedforward of the R and omega*L term in the current controller.
- bEMF_FF_enable: BoolProperty
Enables automatic feedforward of the bEMF term in the current controller.
- ff_pm_flux_linkage: Float32Property
Flux linkage of the motor, used by the motor model.
By default the back-EMF feedforward term assumes a flux linkage of: flux_linkage = 2/3 * torque_constant / pole_pairs which is equivalent to flux_linkage = 5.51328895422 / (pole_pairs * motor_kv)
This default can be overriden by specifying this parametter and setting (
ff_pm_flux_linkage_valid = True
).
- ff_pm_flux_linkage_valid: BoolProperty
- motor_model_l_d: [Henry] - Float32Property
d-axis phase inductance of the motor, used by the motor model
If specified (
motor_model_l_dq_valid = True
), overrides the d-axis phase inductance used by the motor model (feedforward and field weakening). This does not affect the current controller gains. If left empty (motor_model_l_dq_valid = False
) phase_inductance is used instead.
- motor_model_l_q: [Henry] - Float32Property
q-axis phase inductance of the motor, used by the motor model
If specified (
motor_model_l_dq_valid = True
), overrides the q-axis phase inductance used by the motor model (feedforward and field weakening). This does not affect the current controller gains. If left empty (motor_model_l_dq_valid = False
) phase_inductance is used instead.
- motor_model_l_dq_valid: BoolProperty
- calibration_current: Float32Property
The current used to measure resistance during
AxisState.MOTOR_CALIBRATION
.
- resistance_calib_max_voltage: Float32Property
The maximum voltage allowed during
AxisState.MOTOR_CALIBRATION
.This should be set to less than (0.5 * vbus_voltage), but high enough to satisfy V=IR during motor calibration, where I is config.calibration_current and R is config.phase_resistance
- current_soft_max: [Amp] - Float32Property
Maximum commanded current allowed for this motor. There is a separate limit
current_soft_max
that pertains to the ODrive’s power stage.
- current_hard_max: [Amp] - Float32Property
Maximum measured current allowed. Any measurement above
current_hard_max
will throw aCURRENT_LIMIT_VIOLATION
error. Changing this variable can lead to reconfiguration of low level hardware at the next opportunity (when the axis is in IDLE). This will incur a 0.7s delay until the axis can be activated again. There is a separate limitcurrent_hard_max
that pertains to the ODrive’s power stage.
- current_slew_rate_limit: [Amp/s] - Float32Property
Maximum slew rate for the current setpoint.
Must be strictly positive.
- acim_gain_min_flux: Float32Property
- acim_autoflux_enable: BoolProperty
- acim_autoflux_min_Id: Float32Property
- acim_autoflux_attack_gain: Float32Property
- acim_autoflux_decay_gain: Float32Property
- acim_nominal_slip_vel: [Hz] - Float32Property
1/(2*pi*rotor_tau), where rotor_tau is time constant of the rotor (L_r/R_r)
- sensorless_observer_gain: [rad/s] - Float32Property
- sensorless_pll_bandwidth: [rad/s] - Float32Property
- sensorless_pm_flux_linkage: Float32Property
Flux linkage of the motor, used by the sensorless estimator.
By default the sensorless estimator derives the motor flux linkage as: flux_linkage = 2/3 * torque_constant / pole_pairs which is equivalent to flux_linkage = 5.51328895422 / (pole_pairs * motor_kv)
This default can be overriden by specifying this parametter and setting (
sensorless_pm_flux_linkage_valid = True
).
- sensorless_pm_flux_linkage_valid: BoolProperty
- class ODrive.Mapper.Config
- circular: BoolProperty
- circular_output_range: Float32Property
- scale: Float32Property
- offset_valid: BoolProperty
- offset: Float32Property
- index_offset_valid: BoolProperty
- index_offset: Float32Property
- use_index_gpio: BoolProperty
- index_search_always_on: BoolProperty
Listen for index pulses even when not explicitly running index search and even when the motor is disarmed. In case the index pulse is fairly wide (low resolution encoders or hall effect sensors), care must be taken as to which direction the motor is spun to register the index.
- index_gpio: Uint8Property
- use_endstop: BoolProperty
- class ODrive.IncrementalEncoder.Config
- enabled: BoolProperty
- cpr: Uint32Property
Counts per revolution of the encoder. This is 4x the Pulse Per Revolution (PPR) value. Usually this is indicated in the datasheet of your encoder.
- class ODrive.HallEncoder.Config
- enabled: BoolProperty
- hall_polarity: Uint8Property
- hall_polarity_calibrated: BoolProperty
- ignore_illegal_hall_state: BoolProperty
- class ODrive.SpiEncoder.Config
- ncs_gpio: Uint8Property
- mode: Property[ODrive.SpiEncoderMode]
- delay: [sec] - Float32Property
Delay of the position reading of the encoder. The position reading is forward-projected based on the velocity estimate and this value.
- max_error_rate: Float32Property
Maximum packet error rate
Increasing this value allows the motor to continue operating even if some SPI responses are corrupted (e.g. bad parity bit). However it also leads to slower reaction in case the encoder is disconnected.
- baudrate: [Hz] - Uint32Property
Experimental
Maximum SCLK frequency
The actual selected baudrate will usually be lower than this and depend on the nearest clock prescaler setting.
It is recommended to leave this value at its default.
Setting this value too low can lead to missed control deadline errors because the transfer takes too long. Setting this value too high can lead to bad signal integrity, especially on long wires with high capacitance.
Requires a reboot to take effect.
- class ODrive.OffboardThermistorCurrentLimiter.Config
- gpio_pin: Uint16Property
- r_ref: [Ohm] - Float32Property
Resistance of the thermistor at the reference temperature. Usually denoted R_25 in the thermistor’s datasheet.
- t_ref: [Celcius] - Float32Property
Reference temperature corresponding to
r_ref
, in °C. Usually this is equal to 25°C and denoted T_25 in the thermistor’s datasheet.
- beta: [Kelvin] - Float32Property
Beta (or B) value of the thermistor. Can be found in the thermistor’s datasheet.
- temp_limit_lower: [Celcius] - Float32Property
The lower limit when the controller starts limiting current.
- temp_limit_upper: [Celcius] - Float32Property
The upper limit when current limit reaches 0 Amps and an over temperature error is triggered.
- enabled: BoolProperty
Whether this thermistor is enabled.
- class ODrive.Controller.Config
- enable_vel_limit: BoolProperty
- enable_torque_mode_vel_limit: BoolProperty
Enable velocity limit in torque control mode (requires a valid velocity estimator).
- enable_gain_scheduling: BoolProperty
Enable the experimental “gain scheduling” module, which reduces the pos_gain, vel_gain, and vel_integrator_gain according to the position error. Also known as “anti-hunt”
- gain_scheduling_width: [turn] - Float32Property
Distance over which the gain scheduling operates.
- enable_overspeed_error: BoolProperty
Enables the velocity controller’s overspeed error
- control_mode: Property[ODrive.Controller.ControlMode]
- input_mode: Property[ODrive.Controller.InputMode]
- pos_gain: [(rev/s) / rev] - Float32Property
- vel_gain: [Nm / (rev/s)] - Float32Property
- vel_integrator_gain: [(Nm/s) / (rev/s)] - Float32Property
- vel_integrator_limit: [Nm] - Float32Property
Limit the integrator output (independent of proportional gain output). Set to infinity to disable.
- vel_limit: [rev/s] - Float32Property
Infinity to disable.
- vel_limit_tolerance: Float32Property
Ratio to vel_limit. Infinity to disable.
- vel_ramp_rate: [rev/s^2] - Float32Property
- torque_ramp_rate: [Nm/s] - Float32Property
- circular_setpoints: BoolProperty
- circular_setpoint_range: Float32Property
circular range in [turns] for position setpoints when circular_setpoints is True
- absolute_setpoints: BoolProperty
True: Position setpoints are absolute with respect to some calibration method (usually homing). Position control will not work if the absolute position is not known yet. False: Position setpoints are relative to the startup position.
Requires the axis to be in
AxisState.IDLE
to take effect.
- use_commutation_vel: BoolProperty
Experimental
When using two separate encoders for position control and commutation, this selects which of the two encoders is used for velocity control. If false, the position encoder is used, else the commutation encoder is used. commutation_vel_scale must be set accordingly.
- commutation_vel_scale: Float32Property
Experimental
If use_commutation_vel is true, this defines the scale to apply to the commutation velocity. If the position encoder is mounted after a gearbox with a reduction ratio 1:N, this variable must be set to 1/pole_pairs/N (positive or negative, depending on the setup).
- steps_per_circular_range: Int32Property
Number of steps within the circular setpoint range. Set this and the circular setpoint range to powers of 2 for the best results.
- homing_speed: [rev/s] - Float32Property
The speed at which the axis moves towards the min_endstop during
AxisState.HOMING
- inertia: [Nm / (rev/s^2)] - Float32Property
- input_filter_bandwidth: [rad/s] - Float32Property
The desired bandwidth for
InputMode.POS_FILTER
.Sets the position filter’s P and I gains to emulate a critically-damped 2nd order mass-spring-damper motion.
- spinout_mechanical_power_bandwidth: [rad/s] - Float32Property
Bandwidth for mechanical power estimate. Used for spinout detection
- spinout_electrical_power_bandwidth: [rad/s] - Float32Property
Bandwidth for electrical power estimate. Used for spinout detection. Dot product of Vdq and Idq
- spinout_mechanical_power_threshold: [Watt] - Float32Property
Mechanical power threshold for spinout detection. This should be a negative value
- spinout_electrical_power_threshold: [Watt] - Float32Property
Electrical power threshold for spinout detection. This should be a positive value
- class ODrive.Controller.Autotuning
- frequency: [Hz] - Float32Property
- pos_amplitude: [rev] - Float32Property
- vel_amplitude: [rev/s] - Float32Property
- torque_amplitude: [Nm] - Float32Property
- vel_burst_factor: Uint8Property
- class ODrive.Controller.ControlMode
- VOLTAGE_CONTROL = 0 (0x0)
Note: This mode is not used internally. For voltage-only FOC, use
MotorType.GIMBAL
- TORQUE_CONTROL = 1 (0x1)
Uses only the inner torque control loop. Use
input_torque
to command desired torque. Note the settingconfig.motor.torque_constant
. Note the settingenable_torque_mode_vel_limit
.
- VELOCITY_CONTROL = 2 (0x2)
Uses both the inner torque control loop and the velocity control loop. Use
input_vel
to command desired velocity, andinput_torque
.
- POSITION_CONTROL = 3 (0x3)
Uses the inner torque loop, the velocity control loop, and the outer position control loop. Use
input_pos
to command desired position,input_vel
to command velocity feed-forward, andinput_torque
for torque feed-forward.
- class ODrive.Controller.InputMode
- INACTIVE = 0 (0x0)
Disable inputs. Setpoints retain their last value.
- PASSTHROUGH = 1 (0x1)
Pass input_xxx through to xxx_setpoint directly.
Valid Inputs
Valid Control Modes
- VEL_RAMP = 2 (0x2)
Ramps a velocity command from the current value to the target value.
Configuration Values
config.vel_ramp_rate
[rev/s]config.inertia
[Nm/(rev/s^2))]
Valid Inputs
Valid Control Modes
- POS_FILTER = 3 (0x3)
Implements a 2nd order position tracking filter.
Intended for use with step/dir interface, but can also be used with position-only commands.
Result of a step command from 1000 to 0
Configuration Values
Valid Inputs
Valid Control Modes
- MIX_CHANNELS = 4 (0x4)
Not Implemented.
- TRAP_TRAJ = 5 (0x5)
Implementes an online trapezoidal trajectory planner.
Configuration Values
Valid Inputs
Valid Control Modes
- TORQUE_RAMP = 6 (0x6)
Ramp a torque command from the current value to the target value.
Configuration Values
Valid Inputs
Valid Control Modes
- MIRROR = 7 (0x7)
Implements “electronic mirroring”.
not supported on ODrive Pro/S1
This is like electronic camming, but you can only mirror exactly the movements of the other motor, according to a fixed ratio.
Configuration Values
config.axis_to_mirror
config.mirror_ratio
Valid Inputs
None. Inputs are taken directly from the other axis encoder estimates
Valid Control Modes
- TUNING = 8 (0x8)
Implements a tuning mode
Used for tuning your odrive, this mode allows the user to set different frequencies. Set control_mode for the loop you want to tune, then set the frequency desired. The ODrive will send a 1 turn amplitude sine wave to the controller with the given frequency and phase.
- class ODrive.TrapezoidalTrajectory.Config
- vel_limit: [rev/s] - Float32Property
- accel_limit: [rev/s^2] - Float32Property
- decel_limit: [rev/s^2] - Float32Property