Making ODrive Pro as agressive as possible

Hi Everyone,

I am making a linear actuator powered by an ODrive Pro. It is working great so far but I’m in need of making the linear actuator more aggressive meaning I want it to get to the commanded position as quickly as possible with the least amount of phase shift as possible. I do not care too much about jerky movements or overshoots.

I have been playing around with Filtered Position Control and this works pretty well but the phase shift introduced from the input filter is quite large at the frequency I am commanding. I have also tried the Passthrough mode but I kept getting CURRENT_LIMIT_VIOLATION errors. And from my understanding if I keep increasing the bandwidth of the Filtered Position Control’s input filter it approaches the Passthrought mode?

I have also tried Trajectory Control mode and this seems to be the most promising for my application as it does not have the input filter lag and I can tune acceleration and velocity limits. However, I still get CURRENT_LIMIT_VIOLATION errors when I command sin waves at high frequencies. What is the best way to stop getting these errors? Is increasing the margin between soft and hard current limit of the motor the best way?

If it is relevant I am moving somewhat large weights around with the linear actuator. So it would require large currents to accelerate and decelerate the weights.

Is there any other control modes or tips that would help me get the most performance out of the ODrives? And to stop getting CURRENT_LIMIT_VIOLATION errors?

Any help would be greatly appreciated :smile:

Hi - great question! I think I definitely need to know a bit more about your system to really help, there’s a few different ways you can help the current limit errors.

Specifically, could you let me know your:

  • Motor
  • Encoder
  • Power supply or battery voltage
  • All your ODrive configuration – screenshots in the GUI is fine, but if you have ODrivetool, you can run odrivetool backup-config config.json and paste the resulting config.json here.

To elucidate – typically yes, at high transients you can see current spikes above the soft max, so you’d want to increase the your current hard max. However, there’s a few things during setup that can be suboptimal that can cause this, and a few things that you can do to help this – it’ll definitely depend on your system, so if you’re able to get me that config.json file that would help a ton.

Hi,

Thank you for the quick reply.

Here are the devices I am using.

  • Motor: D5065 270kv
  • Encoder: 16384 CPR Absolute RS485 (CUI Devices AMT212B)
  • Battery: 13s
{
  "can.config.baud_rate": 1000000,
  "can.config.data_baud_rate": 10000000,
  "can.config.tx_brs": 0,
  "can.config.protocol": 1,
  "config.enable_uart_a": false,
  "config.uart_a_baudrate": 115200,
  "config.usb_cdc_protocol": 3,
  "config.uart0_protocol": 3,
  "config.max_regen_current": 0.0,
  "config.dc_bus_undervoltage_trip_level": 41.599998474121094,
  "config.dc_bus_overvoltage_trip_level": 55.25,
  "config.dc_max_positive_current": Infinity,
  "config.dc_max_negative_current": -Infinity,
  "config.user_config_0": 0,
  "config.user_config_1": 0,
  "config.user_config_2": 0,
  "config.user_config_3": 0,
  "config.user_config_4": 0,
  "config.user_config_5": 0,
  "config.user_config_6": 0,
  "config.user_config_7": 0,
  "config.gpio0_mode": 17,
  "config.gpio1_mode": 17,
  "config.gpio2_mode": 17,
  "config.gpio3_mode": 17,
  "config.gpio4_mode": 17,
  "config.gpio5_mode": 17,
  "config.gpio6_mode": 0,
  "config.gpio7_mode": 0,
  "config.gpio8_mode": 17,
  "config.gpio9_mode": 17,
  "config.gpio10_mode": 17,
  "config.gpio11_mode": 17,
  "config.gpio12_mode": 17,
  "config.gpio13_mode": 17,
  "config.gpio14_mode": 17,
  "config.gpio15_mode": 17,
  "config.gpio16_mode": 17,
  "config.gpio17_mode": 17,
  "config.gpio18_mode": 17,
  "config.gpio8_pwm_mapping.endpoint": null,
  "config.gpio8_pwm_mapping.min": 0.0,
  "config.gpio8_pwm_mapping.max": 0.0,
  "config.gpio9_pwm_mapping.endpoint": null,
  "config.gpio9_pwm_mapping.min": 0.0,
  "config.gpio9_pwm_mapping.max": 0.0,
  "config.gpio15_analog_mapping.endpoint": null,
  "config.gpio15_analog_mapping.min": 0.0,
  "config.gpio15_analog_mapping.max": 0.0,
  "config.gpio16_analog_mapping.endpoint": null,
  "config.gpio16_analog_mapping.min": 0.0,
  "config.gpio16_analog_mapping.max": 0.0,
  "config.inverter0.current_soft_max": 100.0,
  "config.inverter0.current_hard_max": 150.0,
  "config.inverter0.temp_limit_lower": 83.95999908447266,
  "config.inverter0.temp_limit_upper": 103.11000061035156,
  "config.inverter0.mod_magn_max": 0.8651593923568726,
  "config.inverter0.shunt_conductance": 1999.9998779296875,
  "config.inverter0.drv_config": 9029553772700800,
  "config.odrv_fan.upper": 80.0,
  "config.odrv_fan.lower": 70.0,
  "config.odrv_fan.enabled": false,
  "config.motor_fan.upper": 80.0,
  "config.motor_fan.lower": 70.0,
  "config.motor_fan.enabled": false,
  "axis0.config.startup_max_wait_for_ready": 3.0,
  "axis0.config.startup_motor_calibration": false,
  "axis0.config.startup_encoder_index_search": false,
  "axis0.config.startup_encoder_offset_calibration": false,
  "axis0.config.startup_closed_loop_control": false,
  "axis0.config.startup_homing": false,
  "axis0.config.init_torque": 0.0,
  "axis0.config.init_vel": 0.0,
  "axis0.config.init_pos": NaN,
  "axis0.config.enable_step_dir": false,
  "axis0.config.step_dir_always_on": false,
  "axis0.config.calib_range": 0.019999999552965164,
  "axis0.config.calib_scan_distance": 8.0,
  "axis0.config.calib_scan_vel": 2.0,
  "axis0.config.index_search_at_target_vel_only": false,
  "axis0.config.watchdog_timeout": 0.0,
  "axis0.config.enable_watchdog": false,
  "axis0.config.step_gpio_pin": 8,
  "axis0.config.dir_gpio_pin": 9,
  "axis0.config.error_gpio_pin": 10,
  "axis0.config.enable_error_gpio": false,
  "axis0.config.calibration_lockin.current": 10.0,
  "axis0.config.calibration_lockin.ramp_time": 0.4000000059604645,
  "axis0.config.calibration_lockin.ramp_distance": 0.5,
  "axis0.config.calibration_lockin.accel": 3.183098793029785,
  "axis0.config.calibration_lockin.vel": 6.36619758605957,
  "axis0.config.sensorless_ramp.initial_pos": 0.0,
  "axis0.config.sensorless_ramp.current": 10.0,
  "axis0.config.sensorless_ramp.ramp_time": 0.4000000059604645,
  "axis0.config.sensorless_ramp.ramp_distance": 0.5,
  "axis0.config.sensorless_ramp.accel": 31.83098793029785,
  "axis0.config.sensorless_ramp.vel": 63.6619758605957,
  "axis0.config.sensorless_ramp.finish_distance": 15.915493965148926,
  "axis0.config.sensorless_ramp.finish_on_vel": true,
  "axis0.config.sensorless_ramp.finish_on_distance": false,
  "axis0.config.general_lockin.initial_pos": 0.0,
  "axis0.config.general_lockin.current": 10.0,
  "axis0.config.general_lockin.ramp_time": 0.4000000059604645,
  "axis0.config.general_lockin.ramp_distance": 3.1415927410125732,
  "axis0.config.general_lockin.accel": 20.0,
  "axis0.config.general_lockin.vel": 40.0,
  "axis0.config.general_lockin.finish_distance": 100.0,
  "axis0.config.general_lockin.finish_on_vel": false,
  "axis0.config.general_lockin.finish_on_distance": false,
  "axis0.config.can.node_id": 1,
  "axis0.config.can.version_msg_rate_ms": 0,
  "axis0.config.can.heartbeat_msg_rate_ms": 100,
  "axis0.config.can.encoder_msg_rate_ms": 100,
  "axis0.config.can.iq_msg_rate_ms": 100,
  "axis0.config.can.error_msg_rate_ms": 100,
  "axis0.config.can.temperature_msg_rate_ms": 100,
  "axis0.config.can.bus_voltage_msg_rate_ms": 100,
  "axis0.config.can.torques_msg_rate_ms": 100,
  "axis0.config.can.powers_msg_rate_ms": 0,
  "axis0.config.can.input_vel_scale": 1000,
  "axis0.config.can.input_torque_scale": 1000,
  "axis0.config.load_encoder": 10,
  "axis0.config.commutation_encoder": 10,
  "axis0.config.encoder_bandwidth": 1000.0,
  "axis0.config.commutation_encoder_bandwidth": NaN,
  "axis0.config.I_bus_hard_min": -Infinity,
  "axis0.config.I_bus_hard_max": Infinity,
  "axis0.config.I_bus_soft_min": -Infinity,
  "axis0.config.I_bus_soft_max": Infinity,
  "axis0.config.P_bus_soft_min": -Infinity,
  "axis0.config.P_bus_soft_max": Infinity,
  "axis0.config.torque_soft_min": -Infinity,
  "axis0.config.torque_soft_max": Infinity,
  "axis0.config.motor.motor_type": 0,
  "axis0.config.motor.pole_pairs": 7,
  "axis0.config.motor.phase_resistance": 0.037000883370637894,
  "axis0.config.motor.phase_inductance": 1.616781264601741e-05,
  "axis0.config.motor.phase_resistance_valid": true,
  "axis0.config.motor.phase_inductance_valid": true,
  "axis0.config.motor.torque_constant": 0.030629629269242287,
  "axis0.config.motor.direction": 1.0,
  "axis0.config.motor.current_control_bandwidth": 1000.0,
  "axis0.config.motor.wL_FF_enable": false,
  "axis0.config.motor.bEMF_FF_enable": false,
  "axis0.config.motor.ff_pm_flux_linkage": 0.0,
  "axis0.config.motor.ff_pm_flux_linkage_valid": false,
  "axis0.config.motor.motor_model_l_d": 0.0,
  "axis0.config.motor.motor_model_l_q": 0.0,
  "axis0.config.motor.motor_model_l_dq_valid": false,
  "axis0.config.motor.calibration_current": 10.0,
  "axis0.config.motor.resistance_calib_max_voltage": 2.0,
  "axis0.config.motor.current_soft_max": 65.0,
  "axis0.config.motor.current_hard_max": 85.0,
  "axis0.config.motor.current_slew_rate_limit": 10000.0,
  "axis0.config.motor.fw_enable": false,
  "axis0.config.motor.fw_mod_setpoint": 0.7786434292793274,
  "axis0.config.motor.fw_fb_bandwidth": 500.0,
  "axis0.config.motor.acim_gain_min_flux": 10.0,
  "axis0.config.motor.acim_autoflux_enable": false,
  "axis0.config.motor.acim_autoflux_min_Id": 10.0,
  "axis0.config.motor.acim_autoflux_attack_gain": 10.0,
  "axis0.config.motor.acim_autoflux_decay_gain": 1.0,
  "axis0.config.motor.acim_nominal_slip_vel": 2.3399999141693115,
  "axis0.config.motor.sensorless_observer_gain": 1000.0,
  "axis0.config.motor.sensorless_pll_bandwidth": 1000.0,
  "axis0.config.motor.sensorless_pm_flux_linkage": 0.0,
  "axis0.config.motor.sensorless_pm_flux_linkage_valid": false,
  "axis0.config.motor.power_torque_report_filter_bandwidth": 8000.0,
  "axis0.config.anticogging.enabled": false,
  "axis0.config.anticogging.max_torque": 0.15000000596046448,
  "axis0.config.anticogging.calib_start_vel": 1.0,
  "axis0.config.anticogging.calib_end_vel": 0.15000000596046448,
  "axis0.config.anticogging.calib_coarse_tuning_duration": 60.0,
  "axis0.config.anticogging.calib_fine_tuning_duration": 120.0,
  "axis0.config.anticogging.calib_fine_dist_scale": 1.0,
  "axis0.config.anticogging.calib_coarse_integrator_gain": 10.0,
  "axis0.config.anticogging.calib_bidirectional": true,
  "axis0.motor.motor_thermistor.config.gpio_pin": 3,
  "axis0.motor.motor_thermistor.config.r_ref": 10000.0,
  "axis0.motor.motor_thermistor.config.t_ref": 25.0,
  "axis0.motor.motor_thermistor.config.beta": 3435.0,
  "axis0.motor.motor_thermistor.config.temp_limit_lower": 110.0,
  "axis0.motor.motor_thermistor.config.temp_limit_upper": 130.0,
  "axis0.motor.motor_thermistor.config.enabled": true,
  "axis0.controller.config.enable_vel_limit": true,
  "axis0.controller.config.enable_torque_mode_vel_limit": true,
  "axis0.controller.config.enable_gain_scheduling": false,
  "axis0.controller.config.gain_scheduling_width": 0.0010000000474974513,
  "axis0.controller.config.enable_overspeed_error": true,
  "axis0.controller.config.control_mode": 3,
  "axis0.controller.config.input_mode": 5,
  "axis0.controller.config.pos_gain": 20.0,
  "axis0.controller.config.vel_gain": 0.1666666716337204,
  "axis0.controller.config.vel_integrator_gain": 0.3333333432674408,
  "axis0.controller.config.vel_integrator_limit": Infinity,
  "axis0.controller.config.vel_limit": 100.0,
  "axis0.controller.config.vel_limit_tolerance": 1.2000000476837158,
  "axis0.controller.config.vel_ramp_rate": 10.0,
  "axis0.controller.config.torque_ramp_rate": 0.009999999776482582,
  "axis0.controller.config.circular_setpoints": false,
  "axis0.controller.config.circular_setpoint_range": 1.0,
  "axis0.controller.config.absolute_setpoints": true,
  "axis0.controller.config.use_commutation_vel": false,
  "axis0.controller.config.use_load_encoder_for_commutation_vel": false,
  "axis0.controller.config.commutation_vel_scale": 1.0,
  "axis0.controller.config.steps_per_circular_range": 1024,
  "axis0.controller.config.homing_speed": 0.25,
  "axis0.controller.config.inertia": 0.0,
  "axis0.controller.config.input_filter_bandwidth": 20.0,
  "axis0.controller.config.spinout_mechanical_power_bandwidth": 20.0,
  "axis0.controller.config.spinout_electrical_power_bandwidth": 20.0,
  "axis0.controller.config.spinout_mechanical_power_threshold": -1000.0,
  "axis0.controller.config.spinout_electrical_power_threshold": 1000.0,
  "axis0.trap_traj.config.vel_limit": 150.0,
  "axis0.trap_traj.config.accel_limit": 1200.0,
  "axis0.trap_traj.config.decel_limit": 1200.0,
  "axis0.min_endstop.config.gpio_num": 7,
  "axis0.min_endstop.config.enabled": true,
  "axis0.min_endstop.config.offset": 0.0,
  "axis0.min_endstop.config.is_active_high": true,
  "axis0.min_endstop.config.debounce_ms": 50,
  "axis0.max_endstop.config.gpio_num": 6,
  "axis0.max_endstop.config.enabled": true,
  "axis0.max_endstop.config.offset": 0.0,
  "axis0.max_endstop.config.is_active_high": true,
  "axis0.max_endstop.config.debounce_ms": 50,
  "axis0.enable_pin.config.gpio_num": 11,
  "axis0.enable_pin.config.enabled": false,
  "axis0.enable_pin.config.offset": 0.0,
  "axis0.enable_pin.config.is_active_high": false,
  "axis0.enable_pin.config.debounce_ms": 50,
  "axis0.mechanical_brake.config.gpio_num": 0,
  "axis0.mechanical_brake.config.is_active_low": true,
  "axis0.pos_vel_mapper.config.circular": false,
  "axis0.pos_vel_mapper.config.circular_output_range": 1.0,
  "axis0.pos_vel_mapper.config.scale": 1.0,
  "axis0.pos_vel_mapper.config.offset_valid": false,
  "axis0.pos_vel_mapper.config.offset": 0.0,
  "axis0.pos_vel_mapper.config.approx_init_pos_valid": false,
  "axis0.pos_vel_mapper.config.approx_init_pos": 0.0,
  "axis0.pos_vel_mapper.config.index_offset_valid": false,
  "axis0.pos_vel_mapper.config.index_offset": 0.0,
  "axis0.pos_vel_mapper.config.use_index_gpio": false,
  "axis0.pos_vel_mapper.config.passive_index_search": false,
  "axis0.pos_vel_mapper.config.index_gpio": 7,
  "axis0.pos_vel_mapper.config.use_endstop": false,
  "axis0.commutation_mapper.config.circular": true,
  "axis0.commutation_mapper.config.circular_output_range": 1.0,
  "axis0.commutation_mapper.config.scale": 7.0,
  "axis0.commutation_mapper.config.offset_valid": true,
  "axis0.commutation_mapper.config.offset": -2.703303813934326,
  "axis0.commutation_mapper.config.approx_init_pos_valid": false,
  "axis0.commutation_mapper.config.approx_init_pos": 0.0,
  "axis0.commutation_mapper.config.index_offset_valid": false,
  "axis0.commutation_mapper.config.index_offset": 0.0,
  "axis0.commutation_mapper.config.use_index_gpio": false,
  "axis0.commutation_mapper.config.passive_index_search": false,
  "axis0.commutation_mapper.config.index_gpio": 7,
  "axis0.commutation_mapper.config.use_endstop": false,
  "axis0.interpolator.config.dynamic": true,
  "rs485_encoder_group0.config.mode": 2,
  "rs485_encoder_group1.config.mode": 0,
  "inc_encoder0.config.enabled": false,
  "inc_encoder0.config.cpr": 8192,
  "inc_encoder1.config.enabled": false,
  "inc_encoder1.config.cpr": 8192,
  "hall_encoder0.config.enabled": false,
  "hall_encoder0.config.hall_polarity": 0,
  "hall_encoder0.config.hall_polarity_calibrated": false,
  "hall_encoder0.config.ignore_illegal_hall_state": false,
  "hall_encoder0.config.edges_calibrated": false,
  "hall_encoder0.config.edge0": NaN,
  "hall_encoder0.config.edge1": NaN,
  "hall_encoder0.config.edge2": NaN,
  "hall_encoder0.config.edge3": NaN,
  "hall_encoder0.config.edge4": NaN,
  "hall_encoder0.config.edge5": NaN,
  "hall_encoder1.config.enabled": true,
  "hall_encoder1.config.hall_polarity": 0,
  "hall_encoder1.config.hall_polarity_calibrated": false,
  "hall_encoder1.config.ignore_illegal_hall_state": false,
  "hall_encoder1.config.edges_calibrated": true,
  "hall_encoder1.config.edge0": 0.73529052734375,
  "hall_encoder1.config.edge1": 1.401298464324817e-45,
  "hall_encoder1.config.edge2": 0.0,
  "hall_encoder1.config.edge3": 0.0,
  "hall_encoder1.config.edge4": 0.0,
  "hall_encoder1.config.edge5": 1.1479437019748901e-41,
  "spi_encoder0.config.ncs_gpio": 17,
  "spi_encoder0.config.mode": 0,
  "spi_encoder0.config.delay": 0.0,
  "spi_encoder0.config.max_error_rate": 0.004999999888241291,
  "spi_encoder0.config.baudrate": 1687500,
  "spi_encoder0.config.biss_c_bits": 18,
  "spi_encoder1.config.ncs_gpio": 17,
  "spi_encoder1.config.mode": 0,
  "spi_encoder1.config.delay": 0.0,
  "spi_encoder1.config.max_error_rate": 0.004999999888241291,
  "spi_encoder1.config.baudrate": 1687500,
  "spi_encoder1.config.biss_c_bits": 18
}

My notes:

  • Your motor’s current soft max is 65A, hard max is 85A. That’s some margin, but I can definitely see momentary spikes surpassing that, especially when driving the motor hard. You can bump axis0.config.motor.current_hard_max up to 100-120A and the issue should go away.
  • Your vel_gain, vel_integrator_gain, and pos_gain are all set at the default, I’d check out the tuning guide.
  • To improve control at high accelerations, you can set axis0.config.motor.current_control_bandwidth and axis0.config.encoder_bandwidth to around 2000 each – it may increase audible noise a bit, but will help transient response
  • You can also set axis0.config.motor.wL_FF_enable and axis0.config.motor.bEMF_FF_enable to True – this will enable some additional internal feedforwards that helps response speed and accuracy at high speeds
  • Since you’re using the thermistor with the 5065 motor, you can definitely increase axis0.config.motor.current_soft_max up to the max peak current of 85A (you may want axis0.config.motor.current_hard_max around 120A if you do this) to get some more torque – the ODrive will automatically reduce the motor current if it detects it getting too hot.
  • If you upgrade to the (newly released) firmware version 0.6.11, you can also enable axis0.config.motor.dI_dt_FF_enable, which will additionally help transient performance.
  • If you can calculate the system inertia, you can set axis0.controller.config.inertia for an additional feedforward in POS_FILTER and TRAP_TRAJ input modes

Generally, if you’re streaming in position setpoints, you should use POS_FILTER. You saw a lot of phase shift because the filter bandwidth is still set to the default of 20 – this usually should be set to the frequency that you’re streaming points into the ODrive – e.g. if you’re streaming new position setpoints at 250Hz, axis0.controller.config.input_filter_bandwidth should be set to 250. However, if you’re doing pure point-to-point movement, TRAP_TRAJ is the way to go.