Integrator_gain for velocity mode

Hello again,
I have a little problem with our two ODrives. I am driving 4 Hoverboard Hub motors. Its an university project where we build an autonomous vehicle for agriculture.
The ODrives are in Velocity Control Mode. Settings are all the same from Hoverboard Guide.
The problem is that the motors try to sync position with each other, dispite they are in velocity control mode. For example: I set both motors of one of the ODrives to the same velocity (vel_gain is set to 0.02, vel_integrator_gain is set to 0.1). Then I brake one of the motors with my hands, so its spinning slower than the other one. After I release my hand from the motor, the motor spins up again, but overshoots to get the same position as the other motor. I confirmed that by marking the motor positions at the beginning with some iso tape and after the test, it had the exactly same position.
That behaviour isnt very ideal, when we drive through rough terrain, where it can happen that one wheel has more traction than the other one. It resulted in random motor movements.
The problem disappeared after we set the vel_integrator_gain to 0. So it seems that the vel_integrator_gain wants to regulate the motor position instead of the velocity.
At the moment we drive through terrain with only vel_gain activated, but we would like to use an integrator_gain.
I hope I could explain my problem properly and someone can help me with this.
Thanks in advance!

Marc

Yeah the integral of velocity is position
And the integral of velocity error is position error

vel_integrator_gain is multiplied by the integral of velocity error. Aka the position error

It’s not weird it’s 100% expected

Why do you feel you need integrator_gain on velocity but not position? They are the same

Mmh okay thanks, that makes sense. I thought the integrator gain raises the current over time.
But I need an integrator gain, that raises only the current, based on the velocity error. I could simply increase the vel_gain, but then my motors start to shake, because of the low encoder resolution. And the vel_integrator_gain trys to hold a specific position, but this results in weird robot movements, even if I set the velocity back to 0, the wheels still trys to achieve a position. So I just need the extra power when the motor is stalled. I wonder if there is a way to do that directly on the ODrive.
Thanks for your help!

Are you trying to command both position and velocity separately? Can you give us an example of your config and commands?

@Wetmelon I am just commanding the velocity (drive.axis0.controller.vel_setpoint = 50) in Velocity Control Mode. There is no pos_setpoint. Here is my ODrive config. The config of the other Odrive is exactly the same.

hw_version_major = 3 (int)
hw_version_minor = 6 (int)
hw_version_variant = 56 (int)
fw_version_major = 0 (int)
fw_version_minor = 4 (int)
fw_version_revision = 10 (int)
fw_version_unreleased = 0 (int)

odrv0.axis0

error = 0x0000 (int)
step_dir_active = False (bool)
current_state = 1 (int)
requested_state = 0 (int)
loop_counter = 1740182 (int)
lockin_state = 0 (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)
  watchdog_timeout = 0.0 (float)
  step_gpio_pin = 1 (int)
  dir_gpio_pin = 2 (int)
  lockin: ...
motor:
  error = 0x0000 (int)
  armed_state = 0 (int)
  is_calibrated = True (bool)
  current_meas_phB = -0.05089250206947327 (float)
  current_meas_phC = -0.020748257637023926 (float)
  DC_calib_phB = 0.4739897549152374 (float)
  DC_calib_phC = 0.7255887985229492 (float)
  phase_current_rev_gain = 0.012500000186264515 (float)
  thermal_current_lim = 95.72190856933594 (float)
  get_inverter_temp()
  current_control: ...
  gate_driver: ...
  timing_log: ...
  config: ...
controller:
  error = 0x0000 (int)
  pos_setpoint = 0.0 (float)
  vel_setpoint = 0.0 (float)
  vel_integrator_current = 0.0 (float)
  current_setpoint = 0.0 (float)
  vel_ramp_target = 0.0 (float)
  vel_ramp_enable = False (bool)
  config:
    control_mode = 2 (int)
    pos_gain = 0.0 (float)
    vel_gain = 0.03999999910593033 (float)
    vel_integrator_gain = 0.05 (float)
    vel_limit = 1000.0 (float)
    vel_limit_tolerance = 1.2000000476837158 (float)
    vel_ramp_rate = 10000.0 (float)
    setpoints_in_cpr = False (bool)
  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 = False (bool)
  shadow_count = 0 (int)
  count_in_cpr = 0 (int)
  interpolation = 0.5 (float)
  phase = -2.0893731117248535 (float)
  pos_estimate = 0.0 (float)
  pos_cpr = 0.0 (float)
  hall_state = 1 (int)
  vel_estimate = 0.0 (float)
  calib_scan_response = 0.0 (float)
  config:
    mode = 1 (int)
    use_index = False (bool)
    find_idx_on_lockin_only = False (bool)
    pre_calibrated = True (bool)
    zero_count_on_find_idx = True (bool)
    cpr = 90 (int)
    offset = 31 (int)
    offset_float = 1.4952031373977661 (float)
    enable_phase_interpolation = True (bool)
    bandwidth = 100.0 (float)
    calib_range = 0.019999999552965164 (float)
    calib_scan_distance = 50.26548385620117 (float)
    calib_scan_omega = 12.566370964050293 (float)
    idx_search_unidirectional = False (bool)
    ignore_illegal_hall_state = False (bool)
  set_linear_count(count: int)

Here is a picture of our robot. If one wheel tries to get his position, its working “against” the other wheels, that dont move. And then the current is very high in this wheel, despite the velocity command is set to 0. We are currently reconstructing the robot in the upper half, so I cant make a video from this driving behaviour in the moment. But if a video would be helpful, I could manage to make one on wednesday.

Ok, then it’s working correctly. In velocity control mode, the integrator only adjusts the current according to the velocity error. However like the other poster said, the integral of velocity is position, so it will tend to return to the same angle after removing the disturbance.

Here’s a thought: What happens if one wheel is smaller than the other?

It would result in the same behaviour I currently have, because both wheels get the same velocity command, but the smaller wheel would cover less distance. Then the wheels would again work against each other (in case of no wheel spin)…

So the vel_integrator_gain isnt suitable for my application. In my program, where I send the commands to the motors, I added a function that checks if the wheels are slower than the vel_setpoint. If they are slower, the program raises the vel_gain slowly, so the controller puts more current into it. I just tested it on rough terrain and the vehicle drives much better and doesnt get stuck anymore. Anyway, thanks for your help!

1 Like