Problem with encoder calibration and board reset after firmware + odrivetool update

Hi all,

After updating the board firmware and odrivetool, the motor is not calibrating properly (no beeping sound) and the ODrive keeps reset (shown on the bottom). It used to work great before these updates. I am using the ‘SunnySky M8 135 KV motor’ with ‘CUI AMT102’ encoder purchased from ODrive.

First, I have downloaded the latest firmware .elf file at Release Firmware version 0.5.3 · odriverobotics/ODrive · GitHub, and then uploaded using STLink. When ‘odrivetool dfu’ command is used, the following error messages were seen and unable to detect when the odrivetool is ran:

ODrive control utility v0.5.3.post0
Waiting for ODrive...
Found ODrive 206437835753 (v3.6-56V) with firmware v0.5.3
Checking online for newest firmware... found v0.5.3

You are about to flash firmware v0.5.3 which is the same version as the firmware on the device (v0.5.3).
Do you want to flash this firmware anyway? [y/N] y
Downloading firmware v0.5.3...
Saving configuration to /var/folders/n5/dqmhqsf54xs882xwc0dtxzth0000gn/T/odrive-config-206437835753.json...
Configuration saved.
Putting device 206437835753 into DFU mode...
Erasing... done            
Flashing... (sector 4/7)  
Traceback (most recent call last):
  File "/usr/local/bin/odrivetool", line 149, in <module>
    odrive.dfu.launch_dfu(args, logger, app_shutdown_token)
  File "/usr/local/lib/python3.9/site-packages/odrive/dfu.py", line 512, in launch_dfu
    update_device(device, firmware, logger, cancellation_token)
  File "/usr/local/lib/python3.9/site-packages/odrive/dfu.py", line 434, in update_device
    dfudev.write_sector(sector, data)
  File "/usr/local/lib/python3.9/site-packages/odrive/dfuse/DfuDevice.py", line 219, in write_sector
    raise make_exception(status)
RuntimeError: An error occured. Device Status: (0, 2, 0, 0)

Once the latest firmware is uploaded using STLink, the following parameters are set, and then, ran the calibration process.

ODrive control utility v0.5.3.post0
Connected to ODrive 206437835753 as odrv0
Website: https://odriverobotics.com/
Docs: https://docs.odriverobotics.com/
Forums: https://discourse.odriverobotics.com/
Discord: https://discord.gg/k3ZZ3mS
Github: https://github.com/odriverobotics/ODrive/

Please connect your ODrive.
You can also type help() or quit().

In [1]: odrv0.erase_configuration()
Oh no odrv0 disappeared

Reconnected to ODrive 206437835753 as odrv0
In [2]: odrv0.config.brake_resistance = 0.123
   ...: 
   ...: odrv0.axis0.motor.config.pole_pairs = 21
   ...: odrv0.axis0.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis0.motor.config.calibration_current = 1.0
   ...: odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis0.config.calibration_lockin.current = 1.0
   ...: odrv0.axis0.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis0.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis0.controller.config.pos_gain = 56
   ...: odrv0.axis0.controller.config.vel_gain = 0.02
   ...: odrv0.axis0.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis1.motor.config.pole_pairs = 21
   ...: odrv0.axis1.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis1.motor.config.calibration_current = 1.0
   ...: odrv0.axis1.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis1.config.calibration_lockin.current = 1.0
   ...: odrv0.axis1.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis1.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis1.controller.config.pos_gain = 56
   ...: odrv0.axis1.controller.config.vel_gain = 0.02
   ...: odrv0.axis1.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis0.controller.config.vel_limit = 1660
   ...: odrv0.axis0.config.sensorless_ramp.vel = 200
   ...: odrv0.axis0.config.sensorless_ramp.accel = 100
   ...: odrv0.axis0.config.sensorless_ramp.finish_distance = 50
   ...: odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (21 * 135)
   ...: 
   ...: odrv0.axis1.controller.config.vel_limit = 1660
   ...: odrv0.axis1.config.sensorless_ramp.vel = 200
   ...: odrv0.axis1.config.sensorless_ramp.accel = 100
   ...: odrv0.axis1.config.sensorless_ramp.finish_distance = 50
   ...: odrv0.axis1.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (21 * 135)
   ...: 
   ...: odrv0.config.enable_brake_resistor = True
   ...: 
   ...: odrv0.axis0.encoder.config.cpr = 8192
   ...: odrv0.axis0.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis0.encoder.config.calib_range = 0.04
   ...: 
   ...: odrv0.axis1.encoder.config.cpr = 8192
   ...: odrv0.axis1.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis1.encoder.config.calib_range = 0.04

In [3]: odrv0.save_configuration()
Oh no odrv0 disappeared

Reconnected to ODrive 206437835753 as odrv0
In [4]: odrv0.axis0.motor.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.use_index = True
   ...: odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
In [5]: odrv0.axis0.motor.config.pre_calibrated = True
   ...: odrv0.axis0.encoder.config.pre_calibrated = True

In [6]: odrv0.save_configuration()
Oh no odrv0 disappeared

Reconnected to ODrive 206437835753 as odrv0
In [7]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [8]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [9]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [10]: odrv0.axis0.controller.config.input_mode = INPUT_MODE_POS_FILTER
    ...: odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    ...: odrv0.axis0.controller.input_pos = 0

Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0

Here are two problems:

  1. When it was working properly, it found the index signal first (beep), and then rotate back and forth to complete the calibration process. However, with the updated firmware, it just rotates back and forth to complete (no beep), and then, unable to find the position when AXIS_STATE_ENCODER_INDEX_SEARCH is called
  2. This could be happening due to the calibration problem, but when the torque is enabled, the ODrive board gets disconnected and connected back and forth

It would be appreciated if anyone could share the simple solution to fix this problem. The motor was working just fine for the last 6 months, but suddenly, everything is not working at this point.

Thanks!

Oh, I see in the post you did an erase_configuration(). So basically it’s failing to find the index is what you’re saying. That’s curious.

Does it work if you revert to 0.5.2?

Thanks for prompt reply.

Reverting to 0.5.1 seems working fine. Find the index signal first, and then, rotate back and forth to complete the calibration process. After running AXIS_STATE_ENCODER_INDEX_SEARCH, it finds the correct calibrated position. No board disappearing and connecting back and forth.

FYI, I have used the .elf file and git branch on this one.

$ python3 odrivetool
ODrive control utility v0.5.1
Connected to ODrive 204F35823056 as odrv0
Website: https://odriverobotics.com/
Docs: https://docs.odriverobotics.com/
Forums: https://discourse.odriverobotics.com/
Discord: https://discord.gg/k3ZZ3mS
Github: https://github.com/madcowswe/ODrive/

Please connect your ODrive.
You can also type help() or quit().

In [1]: odrv0.erase_configuration()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [2]: odrv0.config.brake_resistance = 0.123
   ...: 
   ...: odrv0.axis0.motor.config.pole_pairs = 21
   ...: odrv0.axis0.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis0.motor.config.calibration_current = 1.0
   ...: odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis0.config.calibration_lockin.current = 1.0
   ...: odrv0.axis0.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis0.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis0.controller.config.pos_gain = 56
   ...: odrv0.axis0.controller.config.vel_gain = 0.02
   ...: odrv0.axis0.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis1.motor.config.pole_pairs = 21
   ...: odrv0.axis1.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis1.motor.config.calibration_current = 1.0
   ...: odrv0.axis1.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis1.config.calibration_lockin.current = 1.0
   ...: odrv0.axis1.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis1.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis1.controller.config.pos_gain = 56
   ...: odrv0.axis1.controller.config.vel_gain = 0.02
   ...: odrv0.axis1.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis0.controller.config.vel_limit = 1660
   ...: odrv0.axis0.config.sensorless_ramp.vel = 200
   ...: odrv0.axis0.config.sensorless_ramp.accel = 100
   ...: odrv0.axis0.config.sensorless_ramp.finish_distance = 50
   ...: odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (21 * 135)
   ...: 
   ...: odrv0.axis1.controller.config.vel_limit = 1660
   ...: odrv0.axis1.config.sensorless_ramp.vel = 200
   ...: odrv0.axis1.config.sensorless_ramp.accel = 100
   ...: odrv0.axis1.config.sensorless_ramp.finish_distance = 50
   ...: 
   ...: odrv0.axis0.encoder.config.cpr = 8192
   ...: odrv0.axis0.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis0.encoder.config.calib_range = 0.04
   ...: 
   ...: odrv0.axis1.encoder.config.cpr = 8192
   ...: odrv0.axis1.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis1.encoder.config.calib_range = 0.04

In [3]: odrv0.save_configuration()

In [4]: odrv0.reboot()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [5]: odrv0.axis0.motor.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.use_index = True
   ...: odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

In [6]: dump_errors(odrv0)
axis0
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error
axis1
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error

In [7]: odrv0.axis0.motor.config.pre_calibrated = True
   ...: odrv0.axis0.encoder.config.pre_calibrated = True

In [8]: odrv0.save_configuration()

In [9]: odrv0.reboot()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [10]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [11]: odrv0.axis0.controller.config.input_mode = INPUT_MODE_POS_FILTER
    ...: odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    ...: odrv0.axis0.controller.input_pos = 0

I’ve made a github issue for this to track it and brought it up with the development team. Encoder Index Search Fails on 0.5.3 · Issue #605 · odriverobotics/ODrive · GitHub

1 Like

I found out that the board still disconnects and reconnects back and forth (when torque is enabled) in fw-v0.5.1. When the motor was working properly before updating the odrivetool to fw-v0.5.3, this board reset has never happened.

First, I have flashed the firmware using the ‘dfu-util’ command (rather than using ST-Link) and ‘bin’ file from fw-v0.5.1 page

$ sudo dfu-util -S BOARD_SERIAL -a 0 -s 0x08000000 -D ODriveFirmware_v3.6-56V.bin

This is the test log

$ python3 odrivetool
ODrive control utility v0.5.1
Connected to ODrive 204F35823056 as odrv0
Website: https://odriverobotics.com/
Docs: https://docs.odriverobotics.com/
Forums: https://discourse.odriverobotics.com/
Discord: https://discord.gg/k3ZZ3mS
Github: https://github.com/madcowswe/ODrive/

Please connect your ODrive.
You can also type help() or quit().

In [1]: odrv0.erase_configuration()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [2]: odrv0.config.brake_resistance = 0.123
   ...: 
   ...: odrv0.axis0.motor.config.pole_pairs = 21
   ...: odrv0.axis0.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis0.motor.config.calibration_current = 1.0
   ...: odrv0.axis0.motor.config.direction = 1
   ...: odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis0.config.calibration_lockin.current = 1.0
   ...: odrv0.axis0.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis0.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis0.controller.config.pos_gain = 56
   ...: odrv0.axis0.controller.config.vel_gain = 0.02
   ...: odrv0.axis0.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis1.motor.config.pole_pairs = 21
   ...: odrv0.axis1.motor.config.motor_type = MOTOR_TYPE_GIMBAL
   ...: odrv0.axis1.motor.config.calibration_current = 1.0
   ...: odrv0.axis1.motor.config.direction = 1
   ...: odrv0.axis1.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
   ...: odrv0.axis1.config.calibration_lockin.current = 1.0
   ...: odrv0.axis1.controller.config.input_filter_bandwidth = 1.0
   ...: odrv0.axis1.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
   ...: odrv0.axis1.controller.config.pos_gain = 56
   ...: odrv0.axis1.controller.config.vel_gain = 0.02
   ...: odrv0.axis1.controller.config.vel_integrator_gain = 0.015
   ...: 
   ...: odrv0.axis0.controller.config.vel_limit = 1660
   ...: odrv0.axis0.config.sensorless_ramp.vel = 200
   ...: odrv0.axis0.config.sensorless_ramp.accel = 100
   ...: odrv0.axis0.config.sensorless_ramp.finish_distance = 50
   ...: odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (21 * 135)
   ...: 
   ...: odrv0.axis1.controller.config.vel_limit = 1660
   ...: odrv0.axis1.config.sensorless_ramp.vel = 200
   ...: odrv0.axis1.config.sensorless_ramp.accel = 100
   ...: odrv0.axis1.config.sensorless_ramp.finish_distance = 50
   ...: odrv0.axis1.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (21 * 135)
   ...: 
   ...: odrv0.axis0.encoder.config.cpr = 8192
   ...: odrv0.axis0.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis0.encoder.config.calib_range = 0.04
   ...: 
   ...: odrv0.axis1.encoder.config.cpr = 8192
   ...: odrv0.axis1.encoder.config.mode = ENCODER_MODE_INCREMENTAL
   ...: odrv0.axis1.encoder.config.calib_range = 0.04

In [3]: odrv0.save_configuration()

In [4]: odrv0.reboot()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [5]: odrv0.axis0.motor.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.pre_calibrated = False
   ...: odrv0.axis0.encoder.config.use_index = True
   ...: odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

In [6]: odrv0.axis1.motor.config.pre_calibrated = False
   ...: odrv0.axis1.encoder.config.pre_calibrated = False
   ...: odrv0.axis1.encoder.config.use_index = True
   ...: odrv0.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

In [7]: dump_errors(odrv0)
axis0
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error
axis1
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error

In [8]: odrv0.axis0.motor.config.pre_calibrated = True
   ...: odrv0.axis0.encoder.config.pre_calibrated = True
   ...: odrv0.axis1.motor.config.pre_calibrated = True
   ...: odrv0.axis1.encoder.config.pre_calibrated = True

In [9]: odrv0.save_configuration()

In [10]: odrv0.reboot()
Oh no odrv0 disappeared

Reconnected to ODrive 204F35823056 as odrv0
In [11]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [12]: odrv0.axis0.controller.config.input_mode = INPUT_MODE_POS_FILTER
    ...: odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    ...: odrv0.axis0.controller.input_pos = 0

In [13]: odrv0.axis1.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [14]: odrv0.axis1.controller.config.input_mode = INPUT_MODE_POS_FILTER
    ...: odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    ...: odrv0.axis1.controller.input_pos = 0

Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
In [15]: odrv0.axis0.controller.input_pos = 0.5

Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
In [16]: odrv0.axis0.controller.input_pos = 0

Oh no odrv0 disappeared
Reconnected to ODrive 204F35823056 as odrv0
Oh no odrv0 disappeared
In [17]: 

This is another test log (worst case):


In [12]: odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH

In [13]: dump_errors(odrv0)
axis0
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error
axis1
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error

In [14]: odrv0.axis0.controller.config.input_mode = INPUT_MODE_POS_FILTER
    ...: odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
    ...: odrv0.axis0.controller.input_pos = 0

Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
USB device init failed (bus 20, device 3). Ignoring this device. More info: Traceback (most recent call last):
  File ".../ODrive/Firmware/fibre/python/fibre/usbbulk_transport.py", line 195, in discover_channels
    logger.debug(bulk_device.info())
  File ".../ODrive/Firmware/fibre/python/fibre/usbbulk_transport.py", line 35, in info
    for cfg in self.dev:
  File ".../homebrew/lib/python3.9/site-packages/usb/core.py", line 1140, in __iter__
    yield Configuration(self, i)
  File ".../homebrew/lib/python3.9/site-packages/usb/core.py", line 605, in __init__
    desc = backend.get_configuration_descriptor(
  File ".../homebrew/lib/python3.9/site-packages/usb/backend/libusb1.py", line 773, in get_configuration_descriptor
    _check(self.lib.libusb_get_config_descriptor(
  File ".../homebrew/lib/python3.9/site-packages/usb/backend/libusb1.py", line 604, in _check
    raise USBError(_strerror(ret), ret, _libusb_errno[ret])
usb.core.USBError: [Errno None] Other error
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared
Reconnected to ODrive 206437835753 as odrv0
Oh no odrv0 disappeared

This kind of behavior can be common - for certain configurations, for certain users, enabling the motors crashes the USB due to electrical noise. The fix is typically to add ferrite rings to the motor phase wires, as shown in the pictures on the shop. Ferrite Ring ESD-R-28C-1 — ODrive

Sometimes it happens to people using the calibration, but sometimes it also happens only once the closed loop control is enabled, particularly if the pos/vel gains are set higher.

The failing index search is not common and still needs to be diagnosed.

3 Likes

Thanks for the recommendation.

The board disconnect/reconnect issue has been fixed by flashing the firmware using the STM32CubeProgrammer.

2 Likes

Is there anything new on this topic?

We have a system with 4 ODrives that we are trying to make work for quite some time now. 0.5.1 somehow worked, but we nearly burnt the motor when the ODrive failed in unexpected way (no error thrown, but high phase current nearly destroyed the motor). Since 0.5.1 lacks filtering of the thermistor values, the readings are very unstable and useless.

Tried with 0.5.2, but the ODrive would randomly loose timing and spin-out the motor then switch to error mode.

Tried with 0.5.4 quickly, but there appears to be issues with motor calibration as well.

Most of the things appear to work with 0.5.3 - we only have the issue with index search on 2 of the 4 ODrives and only on the axis1. All ODrive should have been configured with the same settings, but the two that are failing have been configured with inverse operation in the past (before multiple erase_configuration executions), but that setting shouldn’t be present anymore.

This is how it behaves:

  • first time after power-up, the index search results in predictable operation (smooth and slow reverse motion and stop on index) and indeed finds the index and can switch into close loop
  • if the index search fails (e.g. start position too close to the end stop), repeated index search ignores the index signal input. The motion also appears to be acccelerating in the reverse direction and is much faster than the first (correct) operation.

We really need to make this work soon - will there be an update to 0.5.3?
The settings structure is changing too much between versions and even CAN messages are changing, requiring constant changes to the interface we are using…

Are you using the ferrite rings? They help a lot in preventing the motor from emitting high frequency noise that can be picked up by the encoder, especially the index signal which seems more sensitive.

I am aware of the electric noise and the proper shielding was done in the installation. Since the problem is not random in nature and is fully repeatable, it shouldn’t be the result of noise and thus the ferrite rings will not help.

Note that motor calibration was fully operational with 0.5.1 in the same HW setup.

Update on the issue - it is definitely a firmware bug.

If odrv0.axis1.config.enable_step_dir is set to False, the calibration sequence is again correctly executed.

The issue appears to be related to axis1 only with step/dir signals on pins 7/8.

We need the step/dir interface as we are controlling 8 axes in sync - do you propose any solution to the issue? We have CAN interface to all ODrives, but no UART or USB apart from debugging/setup.

edit: can the issue be somehow related to the condition in line 235 in axis.cpp not met? The problematic index search motion appears to be very erratic (oscillating) with the velocity far from being constant.

edit 2: the issue is identical in 0.5.4

Turns out that pin 7 shares an interrupt line with the index pin. There are several workarounds. See this thread: