4
\$\begingroup\$

For my caving robot project, I have 8 motors for which I need torque control (they will mainly be stalled or nearly stalled.)

Each motor is driven by a DRV8801PWPR H-bridge (commanded by one digital and one PWM signal from a STM32F723.)

In order to get the torque, I was planning to measure the current.

The DRV8801 provides a VPROPI pin, which gives a voltage proportional to the current in the sense resistor.

Which kind of current measure is the most accurate to estimate torque:

  1. The average current (ie adding a low pass filter to VPROPI.)

  2. The current at some well chosen moment of the PWM cycle (probably choosing the most "stable" moment of the PWM high.)

  3. The same as 2, but multiplied by the duty cycle of the PWM (can easily be done, as it's the same micro-controller generating the PWM and measuring)

  4. Something else?

PS: I started my PCB design with solution 1, but @bobflux's answer in my question about cross-talk made me rethink about what I really need to measure.

\$\endgroup\$
13
  • 1
    \$\begingroup\$ @tlfong01 : the DRV8801 supports external sense resistor (and I'm using one). Even beter, it has the "VPROPI" pin acting as amplifier, in order to be able to use a small resistor while getting decent voltage (specially usefull in a battery powered project like mine, where I don't want to loose 1V out of 12 in a sense resistor) \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 9:42
  • 1
    \$\begingroup\$ @tlfong01 : I have ni idea how to give a complete "description" of my robot on this site without being out of topic (If you have, it might be usefull to refer to it as most of my questions relate to this robot). Or if you are just currious, we could do a skype. For short, it's a robot to explore vertical narrow cracks, by driving blocked between the 2 opposit walls. Basicaly, the robot is made of 8 arms (2 horrizental "X") with a wheel at the end of each arm. Each wheel is pushed agains the wall (to avoid the robot slipping down) by a motor (those I'm asking about) pulling some elastic band. \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 18:55
  • 1
    \$\begingroup\$ The motors are very small geared DC motors (<1A, weigting less than 20g). The weight is a very important factor for this robot, as the force needed for the arms (ie motor torque) is proportionnal to the weight of the robot. The goal of torque control is to ensure constant force against the walls (ie "constant torque" changing a bit depending on the position of the arms) \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 18:58
  • 1
    \$\begingroup\$ Brushless motors, and stepper motors, can be held still with adjustable torque, normal DC motors tend to spin! \$\endgroup\$ Feb 4, 2022 at 7:34
  • 1
    \$\begingroup\$ Not exactly, @tlfong01: stepper and brushless motors need current to generate torque. Without current, steppers are a little "stiffy", i.e. they tend to oppose movements, but quite weakly - brushless ones spin easily instead. \$\endgroup\$ Feb 4, 2022 at 8:10

1 Answer 1

1
\$\begingroup\$

Motor current only flows through the sense resistor during PWM 'on' time. During the 'off' time it circulates inside the bridge and cannot be directly measured. However if the current is continuous then it will decay to the value you see when the next PWM 'on' period starts, so the average current during both on and off periods should be the same.

If the PWM ratio and/or frequency is low then current may decay to zero during the off period, and then you won't know what the average current was over that time. If current decays faster then the average when off will be lower.

Here's an idealized simulation of applying 50% PWM to a DC motor. Red trace is FET Drain current (and motor current) during the 'on' period ramp up. Green trace is decaying motor current during PWM 'off' time. Note the large spike when the FET is switched on, caused by flyback diode recovery time and parasitic capacitance. You may need to delay reading current for a few microseconds to avoid this spike.

enter image description here

And here's what it looks like with 20% PWM. Current has become discontinuous becaue motor inductance is not quite sufficient to keep it above zero during the PWM 'off' period.

enter image description here

In practice the waveforms will be messier due to commutation and back-emf ripple. Best way to measure the current is with a high speed ADC. Take as many readings as practicable during the 'on' period, and average them over several PWM cycles to reduce noise. Assume that average current during the 'off' period is the same, perhaps with compensation for more rapid decay at low PWM ratios.

\$\endgroup\$
9
  • \$\begingroup\$ Thanks. So you would recommand driving the motors in such way that the current is far from reaching maximum(otherwise the curve would look exponential and not linear), but still far from being nearly constant? If so, why? \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 10:15
  • \$\begingroup\$ When you say taking as many samples as possible during on period, you mean during the 'on' of the PWM? If so, it's not the easiest to do : I will have to start and stop high frequency ADC measurements for each motor at different moments (because the rising edge of PWM can be synchronized, but not the falling edges). Or I have to do permanent measurements, and somehow determine which ones actually where during on time. \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 10:21
  • \$\begingroup\$ @Sandro can you read the ADC on a fixed time interval (cyclic interrupt) and, in the interrupt handler, see if the PWM is on (the output pin status is reflected into some register)? Doing so, you will have a "high" value and a "low" value. The low value indicates how much the current decayed while the pwm was off. \$\endgroup\$ Feb 3, 2022 at 10:31
  • \$\begingroup\$ @Sandro beware, if using the cyclic ADC sampling, to choose an interval which will not beat (synchronize) with PWM. \$\endgroup\$ Feb 3, 2022 at 10:34
  • \$\begingroup\$ @linuxfansaysReinstateMonica : yes, it might be a solution. However, it will very CPU intensive, as it mean I have to do high frequency sampling with an interupt for every single conversion (I was hopping to use DMA, but it will no longer work with this solution). So for low PWM frequency I should be fine, but for higher frequency? Even with a 216MHz MPU, at let's say 10kHz PWM and 10 samples/PWM period, for 8 motors, it lets only 270 instructions per measurement (supposing I do nothing else) \$\endgroup\$
    – Sandro
    Feb 3, 2022 at 10:43

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.