Torque control performance/tuning

I’m using an ODrive S1 with a small Steadywin PM1806 motor and an AS5048A encoder.

I was able to get everything working through the GUI and odrivetools, including calibration, position control, UART communication, and CAN communication.

My goal was to use the motor in torque/current control mode, but I found that the current measurement (and thus the estimated torque) looks quite noisy. Since the motor’s maximum current is only about ±1.5 A, I was surprised by the size of the observed error.

I have a few questions:

  • Is this level of current error/noise expected?
  • Are there ways to further tune the current control parameters?
  • Is there a way to access iq_setpoint? I was commanding non-zero torque, but I always got zeros for iq_setpoint through both UART and CAN. Should I just calculate it myself using the torque constant? Ideally, I’d like to directly compare the commanded current with the measured current reported by the driver.

Hi!

  • Is this level of current error/noise expected?

Generally yes, with a few caveats.

  1. First, the GUI samples much slower than the actual ODrive loop frequency. Onboard, the current noise is more of a gaussian noise / pink noise, which results in little to no increase in power dissipation or actual meaningful torque noise (given motor inertia) – however the GUI samples slow enough that it looks all weird and error-filled. However the noise spectra does reduce the current control fidelity.
  2. The S1 definitely has a good amount of current noise, it’s optimized for higher current motors in general, where ~100mA 3sigma noise isn’t noticeable. The ODrive Micro may be a better solution for your motor – the micro has about 1-2 orders of magnitude less current noise than the S1/Pro
  3. You’re also seeing encoder noise in there, since the encoder estimator and current controllers are intrinsically coupled. And the AS5048 is a noisy encoder.
  • Are there ways to further tune the current control parameters?

You can reduce current_control_bandwidth to maybe 250. There’s also the three feedforward terms, but those really help more with transient performance at higher speeds, and less with zero-speed current noise. You could also add a low-pass filter to the reported current values via I_measured_report_filter_k to match it to 1/2 the sampling frequency of the GUI – maybe 100Hz, so you’d want to set I_measured_report_filter_k so that the resulting filter bandwidth is 50Hz, so 50Hz == -8000 ln (1-k)/2pi → k = 0.0385. That’ll give a more realistic representation of the actual motor current, minus the spikes/noise caused by sampling aliasing.

  • Is there a way to access iq_setpoint? I was commanding non-zero torque, but I always got zeros for iq_setpoint through both UART and CAN. Should I just calculate it myself using the torque constant? Ideally, I’d like to directly compare the commanded current with the measured current reported by the driver.

Yes, however it’s strange you were getting zeroes. Are you in PMSM_VOLTAGE_CONTROL mode? If so, the ODrive will turn off the current controller and use direct voltage control only (so Iq_setpoint will always be zero, it’ll use Vq_setpoint instead). Otherwise you should be able to access it fine via UART with r axis0.motor.foc.Iq_setpoint\n or over CAN with either the Get_Iq message or arbitrary parameter access.

Note all the above regarding the current_control_bandwidth and encoder noise coupling isn’t applicable if you’re in PMSM_VOLTAGE_CONTROL mode (“gimbal” mode in the GUI).

1 Like

Hi Solomon,

Thanks for the quick and detailed response. This is really helpful!

I don’t have the setup with me so I will try what you suggested tomorrow.

For the control mode, I believe I used “CONTROL_MODE_TORQUE_CONTROL.” But I set it up as a Gimbal motor through GUI because calibration step always failed when I set it up as a high current motor.

So based on what you said, it may be voltage controlled in torque mode instead of current controlled?

Hey there,

But I set it up as a Gimbal motor through GUI because calibration step always failed when I set it up as a high current motor.

Ah, yes that would do it. I think that for such a high resistance motor, gimbal mode (the name for PMSM_VOLTAGE_CONTROL in the GUI) is the right choice for the S1. But you can also try changing motor_type to “High Current” mode (PMSM_CURRENT_CONTROL) – you can consult the motor calibration parameters docs page to help troubleshoot calibration. You can also manually write to phase_resistance (2.95 == 2.95 ohm for that motor) and phase_inductance (650e-6 == 650uH for that motor), in order to not require the motor calibration step. You will also have to set phase_resistance_valid and phase_inductance_valid to True, then run save configuration. After that, you should be able to control the motor in current control mode. I think that the results may be a bit noisier, but PMSM_CURRENT_CONTROL will have much better torque accuracy at higher speeds than PMSM_VOLTAGE_CONTROL.

1 Like

Hi Solomon,

Switching to a high-current motor setup didn’t help—in fact, it made things even more jittery.

But then I tried an ODrive Micro (which I’d ordered a few weeks ago), and it worked like magic! I had originally thought the S1 would be the more stable choice since it’s been around longer, but as you mentioned, it’s probably tuned for much more powerful motors. The Micro seems like the right fit for this small motor. On top of that, I can now access iq_setpoint—two birds with one stone. :wink:

I really appreciate your quick and helpful response. Can’t thank you enough.

Hope you have a wonderful day!

Best,
Jinwon

Wonderful, super glad to hear it’s all working out! Please let me know if there’s anything else I can help with.