WestsideRobotics / FTC-Power-Monitoring

Contains a wiki article on FTC Power Monitoring
1 stars 0 forks source link

Motor current measurement scales with duty cycle #1

Open FromenActual opened 1 year ago

FromenActual commented 1 year ago

To get an accurate measurement of motor current, I believe the value returned by motor.getCurrent() needs to be multiplied by abs(motor.getPower()). Assuming this is correct, would be great to update with Wiki with this!

I was playing around with the motor current measurement, and I noticed when at low duty cycle, the value returned by motor.getCurrent() was much higher than measured by my power supply (eg. off by roughly 4x when at 25% duty cycle).

Skimming through the datasheet of the VNH5050 motor driver (used on the Lynx board according to GM0), Figure 11 suggests including an RC filter at the output of the CS (current sense) pin. If this exact circuit were implemented on the Lynx board, then this scaling by the duty cycle wouldn't be required. However, I suspect the Lynx board actually implements an envelope detector circuit of some kind, thus requiring this scaling. My testing has shown it to be fairly accurate.

WestsideRobotics commented 1 year ago

Thanks for your note! Your idea could be useful to the FTC community.

I am not currently set up to evaluate this further. For now I have linked this Issue at the end of the section Motor Current (Java), so readers can find your suggestion.

Hopefully others will contribute to the discussion. Feel free to add more notes as you explore and validate your findings. Thanks again!

FromenActual commented 1 year ago

Happy to help! And thanks for putting this information out there in the first place (including the other repos), fantastic content!

I did some more proper quantitative testing. I created an OpMode that increments the duty cycle of a motor (NeveRest 20) in 10% increments, while recording the current measured by both the Lynx board and motor driver (averaged over 250ms once motor speed had settled). Theoretically, these should measure the same current (after subtracting the base-load measured by the Lynx board). My data is in this spreadsheet, but here are the plots for easy reference:

image

In each plot, the blue line is the current measured by the Lynx module (it matches the reading from my power supply fairly accurately), with the base-load current subtracted. In the left plots, the red line is the raw motor current measurement. In the right plots, the red line is the motor current multiplied by the duty cycle. In the top plots, the motor could spin freely. In the bottom plots, the motor was stalled.

The current measured by the Lynx board and motor drivers should be the same, but that's pretty clearly not the case in the left plots (raw motor current measurement). Multiplying the measured motor current by the duty cycle (right plots) results in a much closer match between the lines, so I'm more confident that this is required for a more accurate measurement of motor current.

Interestingly, I looked at the current sense circuit on the Lynx board, and it's not quite what I expected. Envelope detector circuits usually include a diode, but there's none to be found on the Lynx's current sense circuit (credit to Eeshware in the FTC Discord for getting a good photo for me!):

image

Looks to me like it's a couple resistors in series to ground, with a capacitor at the middle node forming a low-pass RC filter. That should result in a voltage that scales with the duty cycle, no? Idk, will have to think about that one.

Anyways, hope this helps!

WestsideRobotics commented 1 year ago

That's a terrific presentation, very clear and compelling. Well done! This should benefit teams wanting to learn more about FTC robot power management.

FromenActual commented 1 year ago

Ok, I read some stuff and did some more testing today, and I think I misunderstood what's actually going on here. This page has a good explanation of how PWM frequency can affect the motor current, which turns out is very relevant to this discussion. I had assumed the average current going through the motor should be the same as the average current coming from the supply/battery, but I believe that's actually incorrect in this case.

What I previously thought:

I assumed the motor current would settle significantly faster than the PWM pulses, and would look something like the blue line here:

image

As an example to walk through my thought process, let's say I was running at 50% duty cycle, and the motor current settled at 1A during each pulse. I would see an average of 0.5A coming from my supply/battery, and the average motor current would also be 0.5A. However the motor driver was instead reporting 1A, so I figured that must mean the current sense circuit was using an envelope detector to measure the peak current during each pulse. So to get the average current, that reported value had to be multiplied by the duty cycle to get the "correct" value of 0.5A.

What's actually happening (I think):

In reality, the motor current actually looks like the red line here:

image

It turns out that Rev chose to use 10kHz for the PWM frequency (100us), which is nowhere near enough time for the motor current to settle during each pulse. Using the same example from above, if the motor current is approximately 1A within each pulse, it's also about 1A outside of each pulse. That means the average motor current really is 1A, so multiplying by the duty cycle is wrong. However the average current from the supply/battery is still 0.5A. The reason for this discrepancy is because the motor only pulls current from the supply/battery within each pulse. Outside of each pulse, we're seeing the recirculation current, which is sustained by the inductor. That's why the average motor current is not the same as the average current coming from the supply/battery.

So I believe if someone is trying to estimate the torque being exerted by the motor, the value reported by DcMotorEx.getCurrent() is the correct current to use. The true test to confirm this would be to actually measure the torque, and compare that to the measured current; they should be proportional. I don't have the right equipment for this, but would love if someone could test it to confirm!

Sorry for the misleading information at the start of this discussion, I hope no one gets too confused by it! I think I've at least got a better understanding of brushed DC motors now, and how the PWM frequency actually matters when measuring the current.

Also, another good read is this application note from ST; Figure 32 and 33 explain the current sense circuitry in more detail. It's basically just a couple current mirrors created from the high-side MOSFETs, which are summed together before the CS pin.

Windwoes commented 1 year ago

Note: firmware 1.7.2 uses 1KHz PWM, while 1.8.2 uses 10KHz

FromenActual commented 1 year ago

Oh, interesting! Curious why they changed it? Now I'm tempted to revert my firmware to that version and test again. Will follow up if I do!

Windwoes commented 1 year ago

The higher frequency makes the response more linear and improved closed loop control IIRC.