What encoder are you using? I will be getting the same motor here in a few days: do you happen to have some 3D printable or lasercuttable test stand? That would help me reproduce your issue faster.
The encoder we’ve been using is a HEDS-9140#A00 with HEDS-5140#A12 codewheel, we’ve also tried fitting 3 Hall sensors, honeywell ss41 and also running sensorless. All three methods result in the same error, Brake Current Out of Range, although the Hall sensors produce the error at a much lower rpm. Sensorless errors about the same rpm as using the encoder wheel.
I’ve also had slightly different maximum rpm from 3 different power supplies, albiet with a previous version of hardware. There is a post from Texas Instruments about the DRV8301 where someone asks for a guide on bulk capacitance, to which their reply is rather vague, which is hinting to me that maybe the capacitance needs beefing up, so I’ve ordered 15 of these capacitors to add to the ones on board.
And this is with basically just the motor spinning, no significant external load mass or drag?
What is the settings you use for controller.config (for both encoder fb case, and sensorless), and what about encoder.config when using the HEDS encoder?
I suppose more bus caps could help stabilize the current controller, but it shouldn’t be necessary. I will investigate the instability issue when I have time to set up the test rig with the 580kv Propdrive motor.
We are generally running the motor at this test stage unloaded, but have applied a light load to see if that makes any difference, there was no significant difference.
The controller config we use for the HEDS encoder is:
control_mode = 2 (int)
pos_gain = 1.0 (float)
vel_gain = 0.0010000000474974513 (float)
vel_integrator_gain = 0.0010000000474974513 (float)
vel_limit = 400000.0 (float)
The controller config we use for sensorless is:
control_mode = 2 (int)
pos_gain = 20.0 (float)
vel_gain = 0.009999999776482582 (float)
vel_integrator_gain = 0.05000000074505806 (float)
vel_limit = 400000.0 (float)
The encoder config we use for the HEDS encoder is:
mode = 0 (int)
use_index = False (bool)
pre_calibrated = True (bool)
idx_search_speed = 10.0 (float)
cpr = 2000 (int)
offset = 1021 (int)
offset_float = 1.2579481601715088 (float)
bandwidth = 1000.0 (float)
calib_range = 0.019999999552965164 (float)
Thanks Oskar
Tried fitting extra bulk caps, no luck. It even had the effect of LOWERING the rpm at which the error occurs by about 400 rpm.
I tried the motor, and I was able to spot the cause of the issue on my oscilloscope current probe: the ripple current is way too large. The combination of ODrive’s low default switching frequency and the low inductance of the propdrive motor gives excessive ripple current.
The duty cycle of an unloaded motor is given by:
Your issue was the worst at around 5000 RPM, which for a 580 Kv motor gives a duty cycle of about 40% when on a 30V supply.
Here is the theoretical ripple current as a function of duty cycle for your motor:
At 40% duty you would be getting a ripple current of almost 140A. This explains why the bus voltage was starting to ripple. Also the current controller would be getting issues because the current sensors were saturating. I’ll make a note to add an explicit fault for current sensor saturation so nothing gets destroyed in a situation like this, and so error messages are more helpful.
The way to fix this is simply to use a higher switching frequency. The hardware is designed to switch at 24kHz, but we are currently switching at 8kHz. The reason is that the trigger for the execution of the control loop is tied directly to the switching frequency, and we don’t have the CPU to run the controller that fast. The obvious solution is to decouple the control loop execution to only run every Nth switching cycle. This is a bit of work to do, and we haven’t had a reason to until now.
I’ll make a feature request on github as soon as their servers are back to working again.
Great work Oskar. Thank you.
We now have 24kHz switching frequency with 8kHz control frequency on devel
!
@Neil_FV please go ahead and try it, it should reduce the ripple current by factor 3.
I was mistaken on how difficult decoupling the control rate from the PWM frequency was, it turns out it was quite straightforward. There was one complication to do with timestamping the control performance, but I was able to deal with that. Also thanks @Wetmelon for your help with this.
I tried it on the same low inductance motor: the Propdrive 5050 580kv. The ripple current goes from about 4.2A pk-pk to about 1.2A pk-pk. Note that the current clamp has a ~5us time constant low pass filter, the real waveform would be sharp sawtooths.
Before:
After:
Great work @madcowswe and @Wetmelon, I can confirm the ripple is reduced to about a third, though the motor still errors at the same speed with the same error.
Interesting. I’ll try spooling it up to a higher speed here when I get the time.
Do you have a script to ramp up the speed, or how do you ramp the speed up in a controlled way for testing? That would be useful for my testing on this end.
I’ve been using this script to facilitate testing, I’ve only been using axis0, so its only really set up for that.
Thanks
Hi,
Sorry not just yet. I have the test rig all set up, and it’s at the top of my todo list. Hopefully in a day or two.
I have started investigating.
I found one issue, which seems to be that I have put too much capacitive loading on the current sense amplifier, so it overshoots. This plot is of the current sense outputs for phase B and C (channel 1, 2). Note that during some of the switching cycle the current doesn’t flow through the shunt, hence the square waves. On channel 4 I have a current clamp (that was reversed in this case) verifying the current in phase B.
At low modulation (low speed / voltage), we sample in the flat region, so it’s not a big deal. However at high modulation, we can end up sampling in the overshoot part. In the following diagram I have lined up the center vertical gridline to where it would sample. Note how it would be on the overshoot region in this case, and hence sample an incorrect (too large) value. (This time the current clamp is in the same direction as the ODrive measures).
The failure mode seems to be that the current controller goes unstable. The current limit was set to 10A, but here it oscillated up to 50A before erroring out with BRAKE_CURRENT_OUT_OF_RANGE.
So it seems there is this overshoot ring to the current sense, but after that the value seems completely usable. To test to see if we can fix it this way, I picked a new blanking time of 3.5us, and hence got a max modulation of 65%. I spun up the motor and unfortunately the current controller still went unstable at around the same speed (~6k RPM). I verified with the scope (didn’t save pics of that sorry), and with the new blanking time it would appear that the ADC should indeed read clean (after the ring) samples every time.
So there could be something else going on. Maybe the capacitive loading also means the sawtooth waveform of the current ripple gets skewed and gives a correlated error that causes the loss of control margin. Maybe it’s something completely different. One thing that is interesting is that 6k rpm mechanical is 700 Hz on this motor which is getting into the stop-band of the current controller bandwidth, and we are getting only about 12 control cycles per electrical rotation. So it could be an issue that presents itself at high eRPM.
I will keep investigating.
Is this what happens when I get ERROR_CURRENT_SENSE_SATURATION? I get this error when I try to run the 150kv odrive motor at speed of towards 4000rpm.
I have noticed that I can set vel_limit higher if I decrease vel_gain.
If I increase to vel_gain = 5/10000 I get 0x400 but at vel_gain = 3/10000 it seems to work at vel_limit 500000.
These are the parameters I’m using:
odrv0.axis0.motor.config.current_lim = 60
odrv0.axis0.motor.config.calibration_current = 60
odrv0.axis0.controller.config.pos_gain = 100
odrv0.axis0.controller.config.vel_gain = 3/10000
odrv0.axis0.controller.config.vel_integrator_gain = 0
odrv0.axis0.controller.config.vel_limit = 500000
and I’m testing it by setting pos_setpoint = 10000 and pos_setpoint = 800000.
My setup:
odrive 3.5 48V
odrive motor D6374 150KV
16s lipo batteries
Load: Ballscrew with some friction
Thanks for the detailed report. Yes it’s likely related.
We are still working on this, thanks for your patience (especially @Neil_FV, whos waited a long time I know).
Btw I have to ask:
Doesn’t that go over 48V?
Yes you’re right. I forgot how to math for a second there, it is 3*4s so 12s. I measured it to be 43v.
Based on this data, I seem to be able to calculate the limit value of ODrive’s erpm. 50000/8192x60x7=25634. Am I right about this? Oh. Is this an approximation of ODrive’s erpm?
Maybe that’s the case, but I’m not sure yet if it works exactly like that, or if the inductance of the motor and the back emf shape plays a role. Also the current controller bandwidth may play a role.