Help With Initial Configuration

I am trying to setup the spindle for my Shapeoko CNC to use an ODrive. The Spindle is a Makita BLDC trim router. The motor is 1500kV with 2 pole pairs. It has a hall sensor. I used 12 gauge wire for the 3 phases. They are twisted together to reduce the EMI. The hall sensor wires are run through Cat7 wire. They are double shielded and the A, B, and C wires are twisted around ground. The shielding is also tied to ground on the ODrive end. I have checked continuity on the hall wires and they all are reading good. Both the 3 Phase wires and the wires for the hall are about 8 feet long. The hall sensor wires coming from the motor are Blue, Yellow, and White so it is possible I have them hooked up wrong. Also when I measure the voltage at the ODrive on the A, B, Z pins they are reading either 0 or 3.2V. When I read the voltages on those lines at the motor they are about 4.6V. Not sure if that would be an issue.

I have followed the Getting Started doc and the Hoverboard doc. When I get up to the point where I am supposed to run this command:

odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION

the motor wiggles the shaft back and forth about 1/16th of a turn then stops. When I check the encoder it gives:

error = 0x0004 (int)

From what I can tell it is supposed make at least a full revolution. Here are my controller, motor, and encoder configs:

In [24]: odrv0.axis0.controller
Out[24]:
pos_setpoint = 0.0 (float)
set_pos_setpoint(pos_setpoint: float, vel_feed_forward: float, current_feed_forward: float)
vel_ramp_target = 0.0 (float)
vel_ramp_enable = False (bool)
config:
  vel_integrator_gain = 0.10000000149011612 (float)
  vel_ramp_rate = 10000.0 (float)
  control_mode = 2 (int)
  pos_gain = 1.0 (float)
  vel_gain = 0.019999999552965164 (float)
  vel_limit_tolerance = 1.2000000476837158 (float)
  setpoints_in_cpr = False (bool)
  vel_limit = 1000.0 (float)
current_setpoint = 0.0 (float)
move_incremental(displacement: float, from_goal_point: bool)
move_to_pos(pos_setpoint: float)
set_vel_setpoint(vel_setpoint: float, current_feed_forward: float)
set_current_setpoint(current_setpoint: float)
error = 0x0000 (int)
vel_setpoint = 0.0 (float)
start_anticogging_calibration()
vel_integrator_current = 0.0 (float)

In [25]: odrv0.axis0.motor
Out[25]:
armed_state = 0 (int)
error = 0x0000 (int)
phase_current_rev_gain = 0.02500000037252903 (float)
thermal_current_lim = 45.572303771972656 (float)
current_meas_phB = -0.024804890155792236 (float)
current_meas_phC = 0.08902627229690552 (float)
get_inverter_temp()
config:
  calibration_current = 10.0 (float)
  inverter_temp_limit_lower = 100.0 (float)
  current_lim = 10.0 (float)
  requested_current_range = 60.0 (float)
  phase_resistance = 0.037017758935689926 (float)
  current_lim_tolerance = 1.25 (float)
  resistance_calib_max_voltage = 2.0 (float)
  motor_type = 0 (int)
  pole_pairs = 2 (int)
  pre_calibrated = False (bool)
  inverter_temp_limit_upper = 120.0 (float)
  direction = 0 (int)
  phase_inductance = 8.348929441126529e-06 (float)
  current_control_bandwidth = 1000.0 (float)
DC_calib_phB = -0.7407018542289734 (float)
is_calibrated = True (bool)
timing_log:
  TIMING_LOG_ADC_CB_I = 2710 (int)
  TIMING_LOG_FOC_VOLTAGE = 6854 (int)
  TIMING_LOG_ENC_CALIB = 6910 (int)
  TIMING_LOG_FOC_CURRENT = 0 (int)
  TIMING_LOG_MEAS_L = 6570 (int)
  TIMING_LOG_IDX_SEARCH = 0 (int)
  TIMING_LOG_MEAS_R = 6566 (int)
  TIMING_LOG_GENERAL = 0 (int)
  TIMING_LOG_ADC_CB_DC = 12858 (int)
DC_calib_phC = -0.4513227343559265 (float)
gate_driver:
  drv_fault = 0 (int)
current_control:
  final_v_beta = 0.0 (float)
  v_current_control_integral_d = 0.0 (float)
  I_measured_report_filter_k = 1.0 (float)
  i_gain = 37.01776123046875 (float)
  max_allowed_current = 60.75 (float)
  final_v_alpha = 0.0 (float)
  Ibus = 0.0 (float)
  Iq_measured = 0.0 (float)
  v_current_control_integral_q = 0.0 (float)
  Iq_setpoint = 0.0 (float)
  overcurrent_trip_level = 67.5 (float)
  Id_measured = 0.0 (float)
  p_gain = 0.008348929695785046 (float)

In [26]: odrv0.axis0.encoder
Out[26]:
count_in_cpr = 3 (int)
interpolation = 0.5 (float)
error = 0x0004 (int)
hall_state = 6 (int)
config:
  zero_count_on_find_idx = True (bool)
  offset_float = 0.0 (float)
  cpr = 12 (int)
  calib_scan_distance = 50.26548385620117 (float)
  calib_range = 0.019999999552965164 (float)
  ignore_illegal_hall_state = False (bool)
  find_idx_on_lockin_only = False (bool)
  calib_scan_omega = 12.566370964050293 (float)
  pre_calibrated = False (bool)
  bandwidth = 100.0 (float)
  use_index = False (bool)
  offset = 0 (int)
  enable_phase_interpolation = True (bool)
  mode = 1 (int)
  idx_search_unidirectional = False (bool)
pos_estimate = 3.975128173828125 (float)
pos_cpr = 3.975128173828125 (float)
index_found = False (bool)
set_linear_count(count: int)
phase = -2.6179938316345215 (float)
is_ready = False (bool)
calib_scan_response = 0.0 (float)
vel_estimate = 0.0 (float)
shadow_count = 3 (int)

Any help getting this working is greatly appreciated.

Oh and the shadow_count goes up when I spin the motor.

I think I may have found the problem. Looking at the code, the error gets set to ERROR_NO_RESPONSE if the shadow_count does not go up or down by 8 during calibration. My CPR is 12 so to go up by 8 the shaft would need to make 2/3 of a revolution. During calibration it is only moving about 1/16th of a turn. Is there a way I can adjust this?

Well I figured that out. Had to increase the calibration current.

Now the only problem is when I request more than 1500 RPM out of the spindle there is a ERROR_CURRENT_UNSTABLE error:

In [263]: odrv0.axis0.motor
Out[263]:
armed_state = 0 (int)
error = 0x1000 (int)
phase_current_rev_gain = 0.02500000037252903 (float)
thermal_current_lim = 54.5060920715332 (float)
current_meas_phB = 0.3683515787124634 (float)
current_meas_phC = -0.06976497173309326 (float)
get_inverter_temp()
config:
  calibration_current = 12.0 (float)
  inverter_temp_limit_lower = 100.0 (float)
  current_lim = 12.0 (float)
  requested_current_range = 60.0 (float)
  phase_resistance = 0.03541401028633118 (float)
  current_lim_tolerance = 1.25 (float)
  resistance_calib_max_voltage = 2.0 (float)
  motor_type = 0 (int)
  pole_pairs = 2 (int)
  pre_calibrated = True (bool)
  inverter_temp_limit_upper = 120.0 (float)
  direction = 1 (int)
  phase_inductance = 8.397357305511832e-06 (float)
  current_control_bandwidth = 1000.0 (float)
DC_calib_phB = -0.7309862375259399 (float)
is_calibrated = True (bool)
timing_log:
  TIMING_LOG_ADC_CB_I = 2442 (int)
  TIMING_LOG_FOC_VOLTAGE = 0 (int)
  TIMING_LOG_ENC_CALIB = 0 (int)
  TIMING_LOG_FOC_CURRENT = 7514 (int)
  TIMING_LOG_MEAS_L = 0 (int)
  TIMING_LOG_IDX_SEARCH = 0 (int)
  TIMING_LOG_MEAS_R = 0 (int)
  TIMING_LOG_GENERAL = 0 (int)
  TIMING_LOG_ADC_CB_DC = 12858 (int)
DC_calib_phC = -0.4536522328853607 (float)
gate_driver:
  drv_fault = 0 (int)
current_control:
  final_v_beta = 0.9863940477371216 (float)
  v_current_control_integral_d = -0.6877565383911133 (float)
  I_measured_report_filter_k = 1.0 (float)
  i_gain = 35.41400909423828 (float)
  max_allowed_current = 60.75 (float)
  final_v_alpha = 2.8499350547790527 (float)
  Ibus = 2.502821445465088 (float)
  Iq_measured = 13.132708549499512 (float)
  v_current_control_integral_q = 2.9435958862304688 (float)
  Iq_setpoint = 12.0 (float)
  overcurrent_trip_level = 67.5 (float)
  Id_measured = -7.542918682098389 (float)
  p_gain = 0.008397357538342476 (float)

I want to be able to reach 35000 RPM.

Hi Ct Ive seen this before somewhere so try this

in the hope that this may help!

Regards Jerry :grinning: :australia:

Well switching axis0 to axis1 did not help. I have checked all my connections and they seem good. May try resoldering the terminals on the motor. Other than that I am kind of at a loss. Not really sure how this error is triggered so I am not sure what exactly to look for.

In your configuration, I noticed that you have current_lim set to 12. You should be able to reach higher speeds if you increase that value. A good first try would be 25 or 30.

Thanks. I have sense upped the current to 20 and still having issues. I will try 30 and see if that helps. I was reading another thread that mentioned low Phase Inductance can cause this error as well. Mine is

phase_inductance = 8.348929441126529e-06 (float)

Could that be the issue?

Changing current_lim to 30A did not help :pensive:

The phase inductance of your motor could be the problem. Here’s a thread where someone added inductors in series with the phase windings to bump up the phase inductance: thread.

What is your bus voltage?
I think 8uH is a little bit on the low side, but probably not the core reason why it can’t spin at any significant speed. More likely is the fact that we don’t have velocity feed-forward to the current controller, and so if the motor accelerates very fast, it can cause current transients that cause the error.
I would suggest that you try using the velocity ramp mode and see how that goes.

That was the thread I was reading. Is there anything else I should try first?

I did just order 3 of these guys: https://www.mouser.com/ProductDetail/652-PQ2617BHA-220K

I am assuming I can put those close to the ODrive.

bus voltage is 24 volts. My power supply can output between 21 and 27 volts with the adjustment pot.

I am using the ramp mode. Ramp rate is 500.

Just to see what happens, can you try a lower ramp rate? like 100?
And to be clear, you are still getting ERROR_CURRENT_UNSTABLE? Around what speed?

With ramp rate of 100 I can get to about 1995 count/s and the error is still ERROR_CURRENT_UNSTABLE.

So I have been messing with this most of the day. The only thing I can see that might be able to prevent this is to mess around with the current_lim_tolerance but that does not seem like the best idea.

Can you set up a liveplotter graph with motor.current_control.Iq_setpoint and .Iq_measured?

I switched to sensorless this morning and have been able to get up to 20k RPM. Not entirely sure what that means, but I will take it.

maybe getting a higher cpr encoder will solve this?

cpr shouldn’t be an issue at high speed. more likely there isn’t enough voltage to reverse the phase current quickly enough against the motor inductance.
reducing motor.config.current_control_bandwidth to 500 or lower might help - it did for my eBike wheel motor