High Velocity Breaking causes Error

Hi ODrive Community,

As a new user I have spent a few days on getting my ODrive unit to work on a custom built coreless motor with 16 magnets (8 Poles). The motor works great with a standard ESC controller in open loop, but with the motor under load the motor controller shuts down during breaking with the motor error code 3, PHASE_RESISTANCE_OUT_OF_RANGE and PHASE_INDUCTANCE_OUT_OF_RANGE.

I need closed loop control for high torque, variable load robot applications.

Initially, I had trouble getting it to work and run the calibration. After setting the Calibration voltage to 5 and the Calibration current to 2, I got it to beep and find the index point (Edit: I thought it was finding the index, but I did not have that configured correctly, got it fixed with help form hbtousa). After playing with many of various gain and other settings, I was able to get it to work well with a slow velocity setting.

I have the motor connected to a mass based dyno for loading and initial testing. I have a 1200W programable power supply rated to 60 Volts at 50 Amps, so power should not be the issue.

My initial velocity setting was 100,000 (approx. 730 rpm). All worked well and tuned to not overshoot with good position holding response. I have been using the Position_setpoint command to run the motor from 100,000 to -100,000.

I increased the velocity setting to 200,000 or 300,000 and the motor accelerates great, but every time when breaking, the motor controller shuts down with the motor error code 3, PHASE_RESISTANCE_OUT_OF_RANGE and PHASE_INDUCTANCE_OUT_OF_RANGE.

I have been unable to make any progress from here…

While tuning I frequently get this same error code 3 and always when breaking. I have the break resistor that came with the unit installed and set the break resistor setting to 2.1, but also tried settings from 2.0 to 2.3.

Here are the motor parameters reported from the controller:

error = 0x0000 (int)
armed_state = 3 (int)
is_calibrated = True (bool)
current_meas_phB = 0.09581756591796875 (float)
current_meas_phC = -0.03451991081237793 (float)
DC_calib_phB = -0.9421103000640869 (float)
DC_calib_phC = -1.9998149871826172 (float)
phase_current_rev_gain = 0.012500000186264515 (float)
current_control:
  p_gain = 0.0015518594300374389 (float)
  i_gain = 10.576704978942871 (float)
  v_current_control_integral_d = 0.004234021063894033 (float)
  v_current_control_integral_q = 0.030545257031917572 (float)
  Ibus = 0.00023002925445325673 (float)
  final_v_alpha = -0.00974909495562315 (float)
  final_v_beta = 0.029686549678444862 (float)
  Iq_setpoint = 0.07871683686971664 (float)
  Iq_measured = 0.07864609360694885 (float)
  max_allowed_current = 35.999996185302734 (float)
gate_driver:
  drv_fault = 0 (int)
timing_log:
  TIMING_LOG_GENERAL = 0 (int)
  TIMING_LOG_ADC_CB_I = 917 (int)
  TIMING_LOG_ADC_CB_DC = 10955 (int)
  TIMING_LOG_MEAS_R = 4351 (int)
  TIMING_LOG_MEAS_L = 4189 (int)
  TIMING_LOG_ENC_CALIB = 4693 (int)
  TIMING_LOG_IDX_SEARCH = 0 (int)
  TIMING_LOG_FOC_VOLTAGE = 4627 (int)
  TIMING_LOG_FOC_CURRENT = 6853 (int)
config:
  pre_calibrated = False (bool)
  pole_pairs = 8 (int)
  calibration_current = 2.0 (float)
  resistance_calib_max_voltage = 5.0 (float)
  phase_inductance = 7.759297295706347e-05 (float)
  phase_resistance = 0.5288352370262146 (float)
  direction = -1 (int)
  motor_type = 0 (int)
  current_lim = 20.0 (float)
  requested_current_range = 20.0 (float)
  current_control_bandwidth = 20.0 (float)
set_current_control_bandwidth(current_control_bandwidth: float)

I would greatly appreciate any insights you may provide.

Thank you,

Steve

Can you please show odrv0.axis0 ?

Thanks

This is before the error:

error = 0x0000 (int)
enable_step_dir = False (bool)
current_state = 8 (int)
requested_state = 0 (int)
loop_counter = 277631 (int)
config:
  startup_motor_calibration = False (bool)
  startup_encoder_index_search = False (bool)
  startup_encoder_offset_calibration = False (bool)
  startup_closed_loop_control = False (bool)
  startup_sensorless_control = False (bool)
  enable_step_dir = False (bool)
  counts_per_step = 2.0 (float)
  ramp_up_time = 0.4000000059604645 (float)
  ramp_up_distance = 12.566370964050293 (float)
  spin_up_current = 10.0 (float)
  spin_up_acceleration = 400.0 (float)
  spin_up_target_vel = 400.0 (float)
get_temp()
motor:
  error = 0x0000 (int)
  armed_state = 3 (int)
  is_calibrated = True (bool)
  current_meas_phB = -0.04807001352310181 (float)
  current_meas_phC = 0.11835908889770508 (float)
  DC_calib_phB = -0.8983349204063416 (float)
  DC_calib_phC = -1.9509797096252441 (float)
  phase_current_rev_gain = 0.012500000186264515 (float)
  current_control: ...
  gate_driver: ...
  timing_log: ...
  config: ...
  set_current_control_bandwidth(current_control_bandwidth: float)
controller:
  pos_setpoint = 0.0 (float)
  vel_setpoint = 0.0 (float)
  vel_integrator_current = -0.11136190593242645 (float)
  current_setpoint = 0.0 (float)
  config: ...
  set_pos_setpoint(pos_setpoint: float, vel_feed_forward: float, current_feed_forward: float)
  set_vel_setpoint(vel_setpoint: float, current_feed_forward: float)
  set_current_setpoint(current_setpoint: float)
  start_anticogging_calibration()
encoder:
  error = 0x0000 (int)
  is_ready = True (bool)
  index_found = False (bool)
  shadow_count = -2 (int)
  count_in_cpr = 8190 (int)
  offset = -3645 (int)
  interpolation = 0.5 (float)
  phase = -2.7787084579467773 (float)
  pos_estimate = -1.9600900411605835 (float)
  pos_cpr = 8190.2421875 (float)
  hall_state = 3 (int)
  pll_vel = 0.0 (float)
  config: ...
sensorless_estimator:
  error = 0x0000 (int)
  phase = 3.121124267578125 (float)
  pll_pos = 3.1234312057495117 (float)
  pll_vel = -0.3510768413543701 (float)
  config: …

This is After the Error:

error = 0x0003 (int)
enable_step_dir = False (bool)
current_state = 1 (int)
requested_state = 0 (int)
loop_counter = 814919 (int)
config:
  startup_motor_calibration = False (bool)
  startup_encoder_index_search = False (bool)
  startup_encoder_offset_calibration = False (bool)
  startup_closed_loop_control = False (bool)
  startup_sensorless_control = False (bool)
  enable_step_dir = False (bool)
  counts_per_step = 2.0 (float)
  ramp_up_time = 0.4000000059604645 (float)
  ramp_up_distance = 12.566370964050293 (float)
  spin_up_current = 10.0 (float)
  spin_up_acceleration = 400.0 (float)
  spin_up_target_vel = 400.0 (float)
get_temp()
motor:
  error = 0x0000 (int)
  armed_state = 0 (int)
  is_calibrated = True (bool)
  current_meas_phB = 0.01939988136291504 (float)
  current_meas_phC = -0.015513420104980469 (float)
  DC_calib_phB = -0.9058563709259033 (float)
  DC_calib_phC = -1.9380782842636108 (float)
  phase_current_rev_gain = 0.012500000186264515 (float)
  current_control: ...
  gate_driver: ...
  timing_log: ...
  config: ...
  set_current_control_bandwidth(current_control_bandwidth: float)
controller:
  pos_setpoint = 0.0 (float)
  vel_setpoint = 0.0 (float)
  vel_integrator_current = 0.0 (float)
  current_setpoint = 0.0 (float)
  config: ...
  set_pos_setpoint(pos_setpoint: float, vel_feed_forward: float, current_feed_forward: float)
  set_vel_setpoint(vel_setpoint: float, current_feed_forward: float)
  set_current_setpoint(current_setpoint: float)
  start_anticogging_calibration()
encoder:
  error = 0x0000 (int)
  is_ready = True (bool)
  index_found = False (bool)
  shadow_count = -61516 (int)
  count_in_cpr = 4020 (int)
  offset = -3645 (int)
  interpolation = 1.0 (float)
  phase = 3.0534844398498535 (float)
  pos_estimate = -61516.7421875 (float)
  pos_cpr = 4019.357421875 (float)
  hall_state = 2 (int)
  pll_vel = -122183.4765625 (float)
  config: ...
sensorless_estimator:
  error = 0x0000 (int)
  phase = -3.0159854888916016 (float)
  pll_pos = -3.0301365852355957 (float)
  pll_vel = -710.1941528320312 (float)
  config: ...

I would try first to calibrate the encoder to clear its errors. As you can see the index never has been found.
Follow this directions described on documents:

  • Run <axis>.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH . This will make the motor turn in one direction until it finds the encoder index.
  • Follow the calibration instructions for an encoder without index signal.
  • Set <axis>.encoder.config.pre_calibrated to True to confirm that the offset is valid with respect to the index pulse.

Also if you want run first AXIS_STATE_FULL_CALIBRATION_SEQUENCE to see if index sets to true. Don’t forget to tell the Odrive to save the calibration to memmory by using odrv0.axis0.motor.config.pre_calibrated = True only if your settings look good. no errors.
Hope this helps

hbtousa, Thanks for the quick response. Very helpful so far, got the encoder working and learned a bunch from that.

Still has the same issue of working at low velocity setting and erroring out when breaking at higher velocity.

Here is the updated axis dump…

error = 0x0000 (int)
enable_step_dir = False (bool)
current_state = 1 (int)
requested_state = 0 (int)
loop_counter = 251094 (int)
config:
  startup_motor_calibration = True (bool)
  startup_encoder_index_search = True (bool)
  startup_encoder_offset_calibration = True (bool)
  startup_closed_loop_control = False (bool)
  startup_sensorless_control = False (bool)
  enable_step_dir = False (bool)
  counts_per_step = 2.0 (float)
  ramp_up_time = 0.4000000059604645 (float)
  ramp_up_distance = 12.566370964050293 (float)
  spin_up_current = 10.0 (float)
  spin_up_acceleration = 400.0 (float)
  spin_up_target_vel = 400.0 (float)
get_temp()
motor:
  error = 0x0000 (int)
  armed_state = 0 (int)
  is_calibrated = True (bool)
  current_meas_phB = 0.028574347496032715 (float)
  current_meas_phC = -0.016721248626708984 (float)
  DC_calib_phB = -0.8946169018745422 (float)
  DC_calib_phC = -1.977215051651001 (float)
  phase_current_rev_gain = 0.012500000186264515 (float)
  current_control: ...
  gate_driver: ...
  timing_log: ...
  config: ...
  set_current_control_bandwidth(current_control_bandwidth: float)
controller:
  pos_setpoint = 0.0 (float)
  vel_setpoint = 0.0 (float)
  vel_integrator_current = 0.0 (float)
  current_setpoint = 0.0 (float)
  config: ...
  set_pos_setpoint(pos_setpoint: float, vel_feed_forward: float, current_feed_forward: float)
  set_vel_setpoint(vel_setpoint: float, current_feed_forward: float)
  set_current_setpoint(current_setpoint: float)
  start_anticogging_calibration()
encoder:
  error = 0x0000 (int)
  is_ready = True (bool)
  index_found = True (bool)
  shadow_count = 7809 (int)
  count_in_cpr = 7809 (int)
  offset = 4381 (int)
  interpolation = 0.5 (float)
  phase = 2.179872989654541 (float)
  pos_estimate = 7809.7890625 (float)
  pos_cpr = 7809.76904296875 (float)
  hall_state = 3 (int)
  pll_vel = 0.0 (float)
  config: ...
sensorless_estimator:
  error = 0x0000 (int)
  phase = -2.7215256690979004 (float)
  pll_pos = -2.7188754081726074 (float)
  pll_vel = 0.1300521045923233 (float)
  config: ...

Good very good. Can you show me please"
odrv0.axiso0.motor and odrv0.config?

Thanks

Here you go… BTW, is there a resource that goes beyond “Getting Started” that gives a description of each parameter and configuration considerations?

Thank you.

odrv0.axis0.motor:

error = 0x0000 (int)
armed_state = 3 (int)
is_calibrated = True (bool)
current_meas_phB = -0.1646418571472168 (float)
current_meas_phC = 0.06357717514038086 (float)
DC_calib_phB = -0.9026662111282349 (float)
DC_calib_phC = -2.017408609390259 (float)
phase_current_rev_gain = 0.012500000186264515 (float)
current_control:
  p_gain = 0.003875140566378832 (float)
  i_gain = 25.005874633789062 (float)
  v_current_control_integral_d = 0.009758684784173965 (float)
  v_current_control_integral_q = 0.05772272124886513 (float)
  Ibus = 0.000367648754036054 (float)
  final_v_alpha = 0.000525756215211004 (float)
  final_v_beta = -0.0587262399494648 (float)
  Iq_setpoint = 0.1350923329591751 (float)
  Iq_measured = 0.13881893455982208 (float)
  max_allowed_current = 35.999996185302734 (float)
gate_driver:
  drv_fault = 0 (int)
timing_log:
  TIMING_LOG_GENERAL = 0 (int)
  TIMING_LOG_ADC_CB_I = 1373 (int)
  TIMING_LOG_ADC_CB_DC = 10953 (int)
  TIMING_LOG_MEAS_R = 4231 (int)
  TIMING_LOG_MEAS_L = 4345 (int)
  TIMING_LOG_ENC_CALIB = 4573 (int)
  TIMING_LOG_IDX_SEARCH = 4555 (int)
  TIMING_LOG_FOC_VOLTAGE = 4505 (int)
  TIMING_LOG_FOC_CURRENT = 4915 (int)
config:
  pre_calibrated = True (bool)
  pole_pairs = 8 (int)
  calibration_current = 2.0 (float)
  resistance_calib_max_voltage = 5.0 (float)
  phase_inductance = 7.75028092903085e-05 (float)
  phase_resistance = 0.5001174807548523 (float)
  direction = -1 (int)
  motor_type = 0 (int)
  current_lim = 20.0 (float)
  requested_current_range = 20.0 (float)
  current_control_bandwidth = 50.0 (float)
set_current_control_bandwidth(current_control_bandwidth: float)

odrv0.config:

brake_resistance = 2.0999999046325684 (float)
enable_uart = True (bool)
enable_i2c_instead_of_can = False (bool)
enable_ascii_protocol_on_usb = True (bool)
dc_bus_undervoltage_trip_level = 8.0 (float)
dc_bus_overvoltage_trip_level = 51.840003967285156 (float)
gpio1_pwm_mapping:
  endpoint = (0, 0) (RemoteProperty)
  min = 0.0 (float)
  max = 0.0 (float)
gpio2_pwm_mapping:
  endpoint = (0, 0) (RemoteProperty)
  min = 0.0 (float)
  max = 0.0 (float)
gpio3_pwm_mapping:
  endpoint = (0, 0) (RemoteProperty)
  min = 0.0 (float)
  max = 0.0 (float)
gpio4_pwm_mapping:
  endpoint = (0, 0) (RemoteProperty)
  min = 0.0 (float)
  max = 0.0 (float)

Why do you have motor type = 0 and also the brake resistance = 2.099?.

resource that goes beyond “Getting Started” that gives a description of each parameter and configuration considerations? I was blind, probably still I am, when I started. I read the material million times and I took lots of notes specially doing initial configurations. I had to re flash the odrive more than once, and I used the erase_configuration() several times. Setting this puppy up is time consuming, but it is doable. Notes are very important, specially since each situation (end-user) is very specific. I saw your picture and I would remove anything attached to the motor just to be safe.

Thanks

Yes, I am building extensive notes also;)

I may have misunderstood, but motor type = 0 is for MOTOR_TYPE_HIGH_CURRENT, the other setting is for low speed gimbal. My application is not for a gimbal and I need to motor to intermittently run from 0 RPM to max velocity and back to 0 RPM.

The resistance is set at 2.1 at this point, though I have tried many other settings. My Multi-meter says it is 2.5 and I have now gone back to that setting.

The motor and controller works with a high velocity setting without a load.

My issues is with the motor under load, it errors with error #3 when breaking. While connected to the load, It accelerates and runs fine until the controller starts breaking, then it errors out. So, it needs to be connected to he load resolve the issue of getting the motor and controller to break under load.

I hope my explanations are clear…

High_Current is good then. Usually brake resistance is = 0.47, Try that number. Also, I forgot to ask you for odrv0.axis0.encoder to see what you have there.

Thanks

I am using the ODrive 3.5 - 48V version, it ships with a different resistor. I tried 0.47, no change. Still does not work.

odrv0.axis0.encoder:

error = 0x0000 (int)
is_ready = True (bool)
index_found = True (bool)
shadow_count = -61693 (int)
count_in_cpr = 3843 (int)
offset = 4287 (int)
interpolation = 1.0 (float)
phase = -2.7256510257720947 (float)
pos_estimate = -61695.20703125 (float)
pos_cpr = 3840.758056640625 (float)
hall_state = 0 (int)
pll_vel = -119999.6015625 (float)
config:
  mode = 0 (int)
  use_index = True (bool)
  pre_calibrated = True (bool)
  idx_search_speed = 10.0 (float)
  cpr = 8192 (int)
  offset = 4287 (int)
  offset_float = 1.2120343446731567 (float)
  bandwidth = 1000.0 (float)
  calib_range = 0.019999999552965164 (float)

I don’t see anything else I can think of as a right now. Check all your wires, don’t assume they are fine. Also, reboot the odrive and make sure this number (pos_estimate = -61695.20703125);after rebooting, it should be around 0 if your motor is calibrated.Otherwise, it will spin out of control when you execute the close_loop statement.

Thanks

Hbtousa, Thanks for your help!

This sounds really cool! I’d love to see some videos once you get it working ;D


I think you don’t have motor error 0x3; you have axis error 0x3. This means you have axis error ERROR_DC_BUS_UNDER_VOLTAGE and ERROR_INVALID_STATE, not the resistance and inductance errors you indicated.

Do you have an oscilloscope to check what the DC power bus is doing during your tests? What voltage are you running your tests at? If there are any relevant settings on your power supply then please share.

Also why did you set this so low?

Thanks for the input. I will check my setup with this info and reply with more details.

I am traveling this week, so I will return to the project when I return.

Looks like you do an amazing job of providing feedback on this forum! Thank you, and I am looking forward to making progress.