Closed Loop violent vibrations

Hello all,

I was using Sensor-less mode because I was waiting for he encoders and the motors were working with some minor issues when stopping abruptly.
I have received the AMT102-V encoders and have been trying the past couple of days to use the ODrive tool to control the motors but to no avail. It is time I ask for some help!

So the current setup is:

  • Odrive 24v powered by a PSU at 12.5V 60A( can go higher but the motors are limited to 15v and don’t want to risk it!)

  • Turnigy Aerodrive SK3 - 2830-920kv (out runner)

  • and finally the AMT102-V encoder.

The encoder came without a wire so I made my own using the housings and pins required as mentioned in its datasheet and solder them direlty onto the Odrive.

What I have tried so far is :

  1. reset the odrive and calibrate it

    odrv1.erase_configuration()
    odrv1.reboot()
    odrv1.axis0.encoder.config.use_index = True
    odrv1.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
    odrv1.axis0.encoder.config.pre_calibrated = True
    odrv1.axis0.motor.config.pre_calibrated = True
    odrv1.axis0.config.startup_encoder_index_search = True
    odrv1.axis0.config.startup_closed_loop_control = True
    odrv1.save_configuration()
    odrv1.reboot()

  2. after calibration enter the closed loop state

  3. Try setting a pos_setpoint (eg 10000) or vel_setpoint — Nothing happens or I get the ERROR_OVERSPEED)

  4. Increase the vel_limit to 100000 - This solves the overspeed, however it starts vibrating and the motor isn’t moving at all.

The above steps were with the default values.

I have tried the exact same steps with the values ( gains ) I got from the Sensoreless setup and increase the motor.config.current_lim to 20. I know that the motors were working with these values.

Here is the output from the odrv.axis:

In [77]: odrv1.axis0
Out[77]: 
error = 0x0000 (int)
step_dir_active = False (bool)
current_state = 1 (int)
requested_state = 0 (int)
loop_counter = 32738166 (int)
lockin_state = 0 (int)
config:
  startup_motor_calibration = False (bool)
  startup_encoder_index_search = True (bool)
  startup_encoder_offset_calibration = False (bool)
  startup_closed_loop_control = True (bool)
  startup_sensorless_control = False (bool)
  enable_step_dir = False (bool)
  counts_per_step = 2.0 (float)
  watchdog_timeout = 0.0 (float)
  step_gpio_pin = 1 (int)
  dir_gpio_pin = 2 (int)
  calibration_lockin: ...
  sensorless_ramp: ...
  general_lockin: ...
motor:
  error = 0x0000 (int)
  armed_state = 0 (int)
  is_calibrated = True (bool)
  current_meas_phB = -0.28109169006347656 (float)
  current_meas_phC = 0.035080693662166595 (float)
  DC_calib_phB = -1.652514934539795 (float)
  DC_calib_phC = 0.08589068055152893 (float)
  phase_current_rev_gain = 0.02500000037252903 (float)
  thermal_current_lim = 48.00704574584961 (float)
  get_inverter_temp()
  current_control: ...
  gate_driver: ...
  timing_log: ...
  config: ...
controller:
  error = 0x0000 (int)
  pos_setpoint = -7610.765625 (float)
  vel_setpoint = 0.0 (float)
  vel_integrator_current = -0.3915861248970032 (float)
  current_setpoint = 0.0 (float)
  vel_ramp_target = 0.0 (float)
  vel_ramp_enable = False (bool)
  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)
  move_to_pos(pos_setpoint: float)
  move_incremental(displacement: float, from_goal_point: bool)
  start_anticogging_calibration()
encoder:
  error = 0x0000 (int)
  is_ready = True (bool)
  index_found = True (bool)
  shadow_count = -5636 (int)
  count_in_cpr = 2556 (int)
  interpolation = 0.5 (float)
  phase = 0.9716787338256836 (float)
  pos_estimate = -5635.765625 (float)
  pos_cpr = 2556.234375 (float)
  hall_state = 0 (int)
  vel_estimate = 0.0 (float)
  calib_scan_response = 9329.0 (float)
  config: ...
  set_linear_count(count: int)
sensorless_estimator:
  error = 0x0000 (int)
  phase = -2.2962546348571777 (float)
  pll_pos = -2.297368049621582 (float)
  vel_estimate = 0.04372486472129822 (float)
  config: ...
trap_traj:
  config: ...
watchdog_feed()

HW / FW versions:

hw_version_major = 3 (int)
hw_version_minor = 6 (int)
hw_version_variant = 24 (int)
fw_version_major = 0 (int)
fw_version_minor = 4 (int)
fw_version_revision = 11 (int)
fw_version_unreleased = 0 (int)

Also, I have another question about the tuning procedure. Do you enter the closed loop mode and set a vel or pos_setpoint so it will be ‘energized’ and then you start the tuning? If not could someone please clarify the steps before initializing the tuning procedure?

Thank you in advance,

Michail

What control mode are you in when you’re trying to send velocity commands?

@Wetmelon When I try controlling it with the vel_setpoint coommand the control_mode is set to velocity control and when I try to control it with the position setpoint I switch to the position control.

I made some progress, the default values were not working with this motor ( its KV are much higher than most of the threads ive seen here ). I have reduced the gains quite significantly. To be exact :

odrv0.axis0.controller.config.pos_gain = 5 
odrv0.axis0.controller.config.vel_gain = 0.00005
odrv0.axis0.controller.config.vel_integrator_gain = 0.00025 

also changed these :

odrv0.axis0.motor.config.current_lim = 15
odrv0.axis0.motor.config.current_lim_tolerance = 1.5
odrv0.axis0.controller.config.vel_limit = 100000

However, like that if i try to stop the motor with my finger its quite easy. Max A the motor can take is 17A.
Do you think it needs further tuning ? if so any empirical input would be very helpful!

Thank you very much.

When you put your finger on it and stop the motor, check motor.current_control.Iq_setpoint. If that’s 15, then you’re putting all of your current to the motor already.

@Wetmelon Thank you very much! Will check that first thing thing the morning on Monday!