Motor Breaking When Changing Velocity

Hello,
I’m trying to use an ODrive to interface with some Sky’s Edge Robowheels.
However, my team and I are running into some problems with the motor at runtime.

The Problem

Here’s what’s happening.

  • Lets assume the wheels are full-stop.
  • I set the wheel speed to 1
  • The wheels spin up to
  • I set the wheel speed to 0.5
  • The wheel fully stops (within 1 or so miliseconds), then speeds up to 0.5 from the sull-stop position

Anybody know what could be causing this problem, and what could be a fix?

Here’s the config file from the ODrive as well:

Summary
{
	"axis0": {
		"acim_estimator": {
			"config": {
				"slip_velocity": 14.706000328063965
			}
		},
		"config": {
			"dir_gpio_pin": 2,
			"enable_sensorless_mode": false,
			"enable_step_dir": false,
			"enable_watchdog": false,
			"startup_closed_loop_control": false,
			"startup_encoder_index_search": false,
			"startup_encoder_offset_calibration": false,
			"startup_homing": false,
			"startup_motor_calibration": false,
			"step_dir_always_on": false,
			"step_gpio_pin": 1,
			"watchdog_timeout": 0.0,
			"calibration_lockin": {
				"accel": 20.0,
				"current": 10.0,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 40.0
			},
			"can": {
				"encoder_rate_ms": 10,
				"heartbeat_rate_ms": 100,
				"is_extended": false,
				"node_id": 0
			},
			"general_lockin": {
				"accel": 20.0,
				"current": 10.0,
				"finish_distance": 100.0,
				"finish_on_distance": false,
				"finish_on_enc_idx": false,
				"finish_on_vel": false,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 40.0
			},
			"sensorless_ramp": {
				"accel": 200.0,
				"current": 10.0,
				"finish_distance": 100.0,
				"finish_on_distance": false,
				"finish_on_enc_idx": false,
				"finish_on_vel": true,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 400.0
			}
		},
		"controller": {
			"config": {
				"axis_to_mirror": 255,
				"circular_setpoint_range": 1.0,
				"circular_setpoints": false,
				"control_mode": 2,
				"electrical_power_bandwidth": 20.0,
				"enable_gain_scheduling": false,
				"enable_overspeed_error": true,
				"enable_torque_mode_vel_limit": true,
				"enable_vel_limit": true,
				"gain_scheduling_width": 10.0,
				"homing_speed": 0.25,
				"inertia": 0.0,
				"input_filter_bandwidth": 2.0,
				"input_mode": 2,
				"load_encoder_axis": 0,
				"mechanical_power_bandwidth": 20.0,
				"mirror_ratio": 1.0,
				"pos_gain": 20.0,
				"spinout_electrical_power_threshold": 10.0,
				"spinout_mechanical_power_threshold": -10.0,
				"steps_per_circular_range": 1024,
				"torque_mirror_ratio": 0.0,
				"torque_ramp_rate": 0.009999999776482582,
				"vel_gain": 0.1666666716337204,
				"vel_integrator_gain": 0.3333333432674408,
				"vel_integrator_limit": Infinity,
				"vel_limit": 20.0,
				"vel_limit_tolerance": 1.2000000476837158,
				"vel_ramp_rate": 0.5,
				"anticogging": {
					"anticogging_enabled": true,
					"calib_anticogging": false,
					"calib_pos_threshold": 1.0,
					"calib_vel_threshold": 1.0,
					"cogging_ratio": 1.0,
					"index": 0,
					"pre_calibrated": false
				}
			}
		},
		"encoder": {
			"config": {
				"abs_spi_cs_gpio_pin": 1,
				"bandwidth": 1000.0,
				"calib_range": 0.019999999552965164,
				"calib_scan_distance": 94.19999694824219,
				"calib_scan_omega": 12.566370964050293,
				"cpr": 3200,
				"direction": -1,
				"enable_phase_interpolation": true,
				"find_idx_on_lockin_only": false,
				"hall_polarity_calibrated": false,
				"hall_polarity": 0,
				"ignore_illegal_hall_state": false,
				"index_offset": 0.0,
				"mode": 0,
				"phase_offset_float": -0.4884558916091919,
				"phase_offset": -1650,
				"pre_calibrated": false,
				"sincos_gpio_pin_cos": 4,
				"sincos_gpio_pin_sin": 3,
				"use_index_offset": true,
				"use_index": false
			}
		},
		"max_endstop": {
			"config": {
				"debounce_ms": 50,
				"enabled": false,
				"gpio_num": 0,
				"is_active_high": false,
				"offset": 0.0
			}
		},
		"mechanical_brake": {
			"config": {
				"gpio_num": 0,
				"is_active_low": true
			}
		},
		"min_endstop": {
			"config": {
				"debounce_ms": 50,
				"enabled": false,
				"gpio_num": 0,
				"is_active_high": false,
				"offset": 0.0
			}
		},
		"motor": {
			"config": {
				"I_bus_hard_max": Infinity,
				"I_bus_hard_min": -Infinity,
				"I_leak_max": 0.10000000149011612,
				"R_wL_FF_enable": false,
				"acim_autoflux_attack_gain": 10.0,
				"acim_autoflux_decay_gain": 1.0,
				"acim_autoflux_enable": false,
				"acim_autoflux_min_Id": 10.0,
				"acim_gain_min_flux": 10.0,
				"bEMF_FF_enable": false,
				"calibration_current": 4.0,
				"current_control_bandwidth": 1000.0,
				"current_lim_margin": 8.0,
				"current_lim": 10.0,
				"dc_calib_tau": 0.20000000298023224,
				"inverter_temp_limit_lower": 100.0,
				"inverter_temp_limit_upper": 120.0,
				"motor_type": 0,
				"phase_inductance": 0.0018608097452670336,
				"phase_resistance": 0.9289747476577759,
				"pole_pairs": 15,
				"pre_calibrated": true,
				"requested_current_range": 10.0,
				"resistance_calib_max_voltage": 10.0,
				"torque_constant": 0.03999999910593033,
				"torque_lim": Infinity
			},
			"fet_thermistor": {
				"config": {
					"enabled": true,
					"temp_limit_lower": 100.0,
					"temp_limit_upper": 120.0
				}
			},
			"motor_thermistor": {
				"config": {
					"enabled": false,
					"gpio_pin": 4,
					"poly_coefficient_0": 0.0,
					"poly_coefficient_1": 0.0,
					"poly_coefficient_2": 0.0,
					"poly_coefficient_3": 0.0,
					"temp_limit_lower": 100.0,
					"temp_limit_upper": 120.0
				}
			}
		},
		"sensorless_estimator": {
			"config": {
				"observer_gain": 1000.0,
				"pll_bandwidth": 1000.0,
				"pm_flux_linkage": 0.0015800000401213765
			}
		},
		"trap_traj": {
			"config": {
				"accel_limit": 0.5,
				"decel_limit": 0.5,
				"vel_limit": 2.0
			}
		}
	},
	"axis1": {
		"acim_estimator": {
			"config": {
				"slip_velocity": 14.706000328063965
			}
		},
		"config": {
			"dir_gpio_pin": 8,
			"enable_sensorless_mode": false,
			"enable_step_dir": false,
			"enable_watchdog": false,
			"startup_closed_loop_control": false,
			"startup_encoder_index_search": false,
			"startup_encoder_offset_calibration": false,
			"startup_homing": false,
			"startup_motor_calibration": false,
			"step_dir_always_on": false,
			"step_gpio_pin": 7,
			"watchdog_timeout": 0.0,
			"calibration_lockin": {
				"accel": 20.0,
				"current": 10.0,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 40.0
			},
			"can": {
				"encoder_rate_ms": 10,
				"heartbeat_rate_ms": 100,
				"is_extended": false,
				"node_id": 1
			},
			"general_lockin": {
				"accel": 20.0,
				"current": 10.0,
				"finish_distance": 100.0,
				"finish_on_distance": false,
				"finish_on_enc_idx": false,
				"finish_on_vel": false,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 40.0
			},
			"sensorless_ramp": {
				"accel": 200.0,
				"current": 10.0,
				"finish_distance": 100.0,
				"finish_on_distance": false,
				"finish_on_enc_idx": false,
				"finish_on_vel": true,
				"ramp_distance": 3.1415927410125732,
				"ramp_time": 0.4000000059604645,
				"vel": 400.0
			}
		},
		"controller": {
			"config": {
				"axis_to_mirror": 255,
				"circular_setpoint_range": 1.0,
				"circular_setpoints": false,
				"control_mode": 2,
				"electrical_power_bandwidth": 20.0,
				"enable_gain_scheduling": false,
				"enable_overspeed_error": true,
				"enable_torque_mode_vel_limit": true,
				"enable_vel_limit": true,
				"gain_scheduling_width": 10.0,
				"homing_speed": 0.25,
				"inertia": 0.0,
				"input_filter_bandwidth": 2.0,
				"input_mode": 2,
				"load_encoder_axis": 1,
				"mechanical_power_bandwidth": 20.0,
				"mirror_ratio": 1.0,
				"pos_gain": 20.0,
				"spinout_electrical_power_threshold": 10.0,
				"spinout_mechanical_power_threshold": -10.0,
				"steps_per_circular_range": 1024,
				"torque_mirror_ratio": 0.0,
				"torque_ramp_rate": 0.009999999776482582,
				"vel_gain": 0.1666666716337204,
				"vel_integrator_gain": 0.3333333432674408,
				"vel_integrator_limit": Infinity,
				"vel_limit": 20.0,
				"vel_limit_tolerance": 1.2000000476837158,
				"vel_ramp_rate": 0.5,
				"anticogging": {
					"anticogging_enabled": true,
					"calib_anticogging": false,
					"calib_pos_threshold": 1.0,
					"calib_vel_threshold": 1.0,
					"cogging_ratio": 1.0,
					"index": 0,
					"pre_calibrated": false
				}
			}
		},
		"encoder": {
			"config": {
				"abs_spi_cs_gpio_pin": 1,
				"bandwidth": 1000.0,
				"calib_range": 0.019999999552965164,
				"calib_scan_distance": 94.19999694824219,
				"calib_scan_omega": 12.566370964050293,
				"cpr": 3200,
				"direction": 1,
				"enable_phase_interpolation": true,
				"find_idx_on_lockin_only": false,
				"hall_polarity_calibrated": false,
				"hall_polarity": 0,
				"ignore_illegal_hall_state": false,
				"index_offset": 0.0,
				"mode": 0,
				"phase_offset_float": 1.3537969589233398,
				"phase_offset": 1476,
				"pre_calibrated": false,
				"sincos_gpio_pin_cos": 4,
				"sincos_gpio_pin_sin": 3,
				"use_index_offset": true,
				"use_index": false
			}
		},
		"max_endstop": {
			"config": {
				"debounce_ms": 50,
				"enabled": false,
				"gpio_num": 0,
				"is_active_high": false,
				"offset": 0.0
			}
		},
		"mechanical_brake": {
			"config": {
				"gpio_num": 0,
				"is_active_low": true
			}
		},
		"min_endstop": {
			"config": {
				"debounce_ms": 50,
				"enabled": false,
				"gpio_num": 0,
				"is_active_high": false,
				"offset": 0.0
			}
		},
		"motor": {
			"config": {
				"I_bus_hard_max": Infinity,
				"I_bus_hard_min": -Infinity,
				"I_leak_max": 0.10000000149011612,
				"R_wL_FF_enable": false,
				"acim_autoflux_attack_gain": 10.0,
				"acim_autoflux_decay_gain": 1.0,
				"acim_autoflux_enable": false,
				"acim_autoflux_min_Id": 10.0,
				"acim_gain_min_flux": 10.0,
				"bEMF_FF_enable": false,
				"calibration_current": 4.0,
				"current_control_bandwidth": 1000.0,
				"current_lim_margin": 8.0,
				"current_lim": 10.0,
				"dc_calib_tau": 0.20000000298023224,
				"inverter_temp_limit_lower": 100.0,
				"inverter_temp_limit_upper": 120.0,
				"motor_type": 0,
				"phase_inductance": 0.0019364545587450266,
				"phase_resistance": 0.8772994875907898,
				"pole_pairs": 15,
				"pre_calibrated": true,
				"requested_current_range": 10.0,
				"resistance_calib_max_voltage": 10.0,
				"torque_constant": 0.03999999910593033,
				"torque_lim": Infinity
			},
			"fet_thermistor": {
				"config": {
					"enabled": true,
					"temp_limit_lower": 100.0,
					"temp_limit_upper": 120.0
				}
			},
			"motor_thermistor": {
				"config": {
					"enabled": false,
					"gpio_pin": 4,
					"poly_coefficient_0": 0.0,
					"poly_coefficient_1": 0.0,
					"poly_coefficient_2": 0.0,
					"poly_coefficient_3": 0.0,
					"temp_limit_lower": 100.0,
					"temp_limit_upper": 120.0
				}
			}
		},
		"sensorless_estimator": {
			"config": {
				"observer_gain": 1000.0,
				"pll_bandwidth": 1000.0,
				"pm_flux_linkage": 0.0015800000401213765
			}
		},
		"trap_traj": {
			"config": {
				"accel_limit": 0.5,
				"decel_limit": 0.5,
				"vel_limit": 2.0
			}
		}
	},
	"can": {
		"config": {
			"baud_rate": 250000,
			"protocol": 1
		}
	},
	"config": {
		"brake_resistance": 2.0,
		"dc_bus_overvoltage_ramp_end": 59.92000198364258,
		"dc_bus_overvoltage_ramp_start": 59.92000198364258,
		"dc_bus_overvoltage_trip_level": 59.92000198364258,
		"dc_bus_undervoltage_trip_level": 8.0,
		"dc_max_negative_current": -10.0,
		"dc_max_positive_current": Infinity,
		"enable_brake_resistor": false,
		"enable_can_a": true,
		"enable_dc_bus_overvoltage_ramp": false,
		"enable_i2c_a": false,
		"enable_uart_a": true,
		"enable_uart_b": false,
		"enable_uart_c": false,
		"error_gpio_pin": 0,
		"gpio10_mode": 11,
		"gpio11_mode": 2,
		"gpio12_mode": 12,
		"gpio13_mode": 12,
		"gpio14_mode": 2,
		"gpio15_mode": 7,
		"gpio16_mode": 7,
		"gpio1_mode": 4,
		"gpio2_mode": 4,
		"gpio3_mode": 3,
		"gpio4_mode": 3,
		"gpio5_mode": 3,
		"gpio6_mode": 0,
		"gpio7_mode": 0,
		"gpio8_mode": 0,
		"gpio9_mode": 11,
		"max_regen_current": 0.0,
		"uart0_protocol": 3,
		"uart1_protocol": 3,
		"uart2_protocol": 3,
		"uart_a_baudrate": 115200,
		"uart_b_baudrate": 115200,
		"uart_c_baudrate": 115200,
		"usb_cdc_protocol": 3,
		"gpio1_pwm_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		},
		"gpio2_pwm_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		},
		"gpio3_analog_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		},
		"gpio3_pwm_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		},
		"gpio4_analog_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		},
		"gpio4_pwm_mapping": {
			"endpoint": null,
			"max": 0.0,
			"min": 0.0
		}
	}
}

Additional Details

  • Motor we are using: Sky’s Edge Robowheels.
  • We’re using the encoders instead of the hall effect sensor, which had previously given us massive issues that we were never able to resolve.

Thank you!

karpova1,

I have my Deck Donkey:
Deck Donkey Project

I have a pair of SkysEdge-Robowheels on DD and take it for a spin every morning.
If your summary is just a config file it is quite long compared to the one I use which I found on this forum —`

odrv0.config.enable_brake_resistor = True # Using included 2ohm resistor #remove enable_
odrv0.axis0.motor.config.calibration_current = 2 # highest integer value where I heard the square wave was 4
odrv0.axis0.motor.config.pole_pairs = 15
odrv0.axis0.motor.config.resistance_calib_max_voltage = 6 # motor config still worked with this set to 6
odrv0.axis0.motor.config.requested_current_range = 35 # 35 was the lowest value that produced and audible square wave.
odrv0.axis0.motor.config.current_control_bandwidth = 100.0
odrv0.axis0.motor.config.torque_constant = 8.27 / 10 # KV 10
odrv0.axis1.motor.config.calibration_current = 2 # highest integer value where I heard the square wave was 4
odrv0.axis1.motor.config.pole_pairs = 15
odrv0.axis1.motor.config.resistance_calib_max_voltage = 6 # motor config still worked with this set to 6
odrv0.axis1.motor.config.requested_current_range = 35 # 35 was the lowest value that produced and audible square wave.
odrv0.axis1.motor.config.current_control_bandwidth = 100.0
odrv0.axis1.motor.config.torque_constant = 8.27 / 10 # KV 10

encoder

odrv0.axis0.encoder.config.mode = ENCODER_MODE_INCREMENTAL
odrv0.axis0.encoder.config.cpr = 3200
odrv0.axis0.encoder.config.bandwidth = 1000
odrv0.axis1.encoder.config.mode = ENCODER_MODE_INCREMENTAL
odrv0.axis1.encoder.config.cpr = 3200
odrv0.axis1.encoder.config.bandwidth = 1000

odrv0.axis0.controller.config.input_mode = INPUT_MODE_VEL_RAMP
odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.axis0.controller.config.pos_gain = 1
odrv0.axis0.controller.config.vel_gain = 0.002 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr
odrv0.axis0.controller.config.vel_integrator_gain = 0.01 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr
odrv0.axis0.controller.config.vel_limit = 5
odrv0.axis1.controller.config.input_mode = INPUT_MODE_VEL_RAMP
odrv0.axis1.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.axis1.controller.config.pos_gain = 1
odrv0.axis1.controller.config.vel_gain = 0.002 * odrv0.axis1.motor.config.torque_constant * odrv0.axis1.encoder.config.cpr
odrv0.axis1.controller.config.vel_integrator_gain = 0.01 * odrv0.axis1.motor.config.torque_constant * odrv0.axis1.encoder.config.cpr
odrv0.axis1.controller.config.vel_limit = 5

BREAK HERE

odrv0.save_configuration()
odrv0.reboot()

odrv0.axis0.requested_state = AXIS_STATE_MOTOR_CALIBRATION

dump_errors(odrv0)

odrv0.axis1.requested_state = AXIS_STATE_MOTOR_CALIBRATION

odrv0.axis0.motor.config.pre_calibrated = True
odrv0.axis1.motor.config.pre_calibrated = True

BREAK HERE

odrv0.save_configuration()
odrv0.reboot()

Encoder

odrv0.axis0.encoder.config.calib_range = 0.05
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis1.encoder.config.calib_range = 0.05
odrv0.axis1.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION

Movement

odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis0.controller.input_vel = 0.5
odrv0.axis1.controller.input_vel = 0.5

Your motor should spin here

odrv0.axis0.controller.input_vel = 0
odrv0.axis1.controller.input_vel = 0
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis1.requested_state = AXIS_STATE_IDLE

I run my DD using ASCII protocol in velocity mode but will start to explore the position mode also.
I use Qtcreator on Ubuntu for developing my “ddod” interface.

If you are changing the config every time you change your speed that maybe what causes the motor to stop.

On my setup I have to calibrate the encoder each power up but not the config I can change the speed on the fly using ASCII protocol velocity mode.

2 Likes