Tag Archives: torque

Measuring torque ripple

Recently I described some changes I made to improve the low speed torque ripple of the moteus controlle. I also built a dynamometer. I decided to use the dynamometer to quantify how much things had improved with the torque ripple, and to see how much room for improvement was left with any anti-cogging implementation.

Dynamometer script

Here, the test script is relatively simple. I have the “fixture” controller sweep at a very low velocity (0.01Hz) through a bit more than one full revolution using a relatively high I term in the PID controller to ensure that it really holds that position no matter what external torque is applied. Then, the “device under test” controller is just commanded either to be powered off, or in position mode with a pd gain of 0 and a feedforward torque. Then I can just measure the result from the torque transducer while this sweeps through a full revolution, and correlate the measured torque with the encoder position.

Results

For these plots, I subtracted out the DC offset to just concentrate on the ripple and not scaling factor errors. Here’s the plot from the pre-fixes controller:

In these plots, the higher torque values are displayed in lighter colors to make it easier to see the values at low torque. Also, the standard deviation and peak-to-peak values are rendered in the lower right hand corner. Before any fixes, when the controller was off (i.e. completely unpowered), there was about 0.026Nm of peak-to-peak ripple, however, when turning on the controller and commanding 0 torque, that jumped up to a 0.047 Nm peak-to-peak.

Now for the post-fix plot:

Post fixes, the torque ripple at all the tested torque levels is nearly indistinguishable from the torque of the completely unpowered motor, which is what we want to see!

STM32G4 ADC and low-torque operation

Recently dlickindorf pointed out in the mjbots discord that he was having problems with very low torques on his large PMSM hobby-grade motor. While moteus doesn’t have any anti-cogging support yet, it should still be capable of driving motors such that the unexpected torque isn’t much worse than the baseline cogging torque of the motor. However, he was seeing much worse behavior with controlling to 0 current, as much as a full percent of the maximum torque of the motor.

Needless to say, I wanted to try and understand the behavior and figure out how to make it better. I was able to reproduce the problem locally, so that was a good start. It was easiest to see when commanding a position with a low maxmum torque. Say on a 8108 motor, with 0.05 N*m maximum torque, the cogging-like torque was high enough that the position control could get stuck in a local minima far from the control point.

In other experiments with higher torque, the switching noise because audibly “squirrely” at certain electrical theta angles. One often occurred at a 0 theta pre-magnetic offset compensation, and another appeared when one phase current was near maximum and the other two phase currents were opposite sign but near equal magnitude.

Calibration smoothing

When the moteus controller is calibrated, it calculates an offset between the electrical commutation angle and the magnetic encoder not just as an average, but at 64 separate points in the revolution of the magnetic encoder. This allows the calibration to take out some of the effect of magnets that are not perfectly axis-aligned with the encoder.

However, when calculating the moving average of the offset value, I neglected to take into account the fact that the encoder wraps around between 0 and 2*pi, and those ends of the offset curve were smoothed independently. If the calibration was somewhat steep in that particular window, it resulted in a discontinuity in the offset curve, which resulted in high frequency noise when controlling near that position.

That problem was relatively easy to solve, by just filtering in a circular domain.

Current noise

The next issue was dealing where the phase current became obviously very noisy. Ultimately I tracked this down to a combination of mis-configuration of the STM32G4 ADC peripheral and coupling between the digital and analog domains.

The latter is the easiest to cover. In the core FOC loop, I use a debugging pin that goes high during the loop to be able to easily identify how long it takes on an oscilloscope. The problem was that I was starting the ADC conversions, then immediately switching that pin. That results in a large enough current transient either within the chip or on the PCB that the analog samples have significant noise introduced. Solving that was easy enough by just moving the debug pin assignment to after the ADC samples are completed.

The former was a result of bugs introduced when I ported the moteus code from the STM32F4 to the G4. The ADC peripherals are significantly different in the G4 (more like the F3 peripherals) and the configuration registers are almost entirely different. At one point several months ago I was trying to configure the sample time for the ADCs but not actually doing so at all. When I resolved that issue, I didn’t look at the resulting sampled waveforms very closely and didn’t notice that the current waveforms were still pretty bad. This was compounded by a further issue. The moteus has 3 current shunts, but it was only sampling two of them and inferring the 3rd by Kirchoff’s law.

Here’s a plot showing the 3 current values as the voltage phase was advanced through a few cycles:

The biggest problem here was that the ADC prescaler was too low for the system clock I was running. Once fixing the prescaler, and making a few additional changes, the current waveforms now look like:

So yes, there is now much less unusual discretization going on across all 3 current channels.

Final results

And now for a video showing the final result:

Initial dynamometer assembly

Earlier I showed off a torque transducer and the calibration fixture I used for it. I’ve now got enough assembled to make an entire dynamometer:

This has the torque transducer on one end, coupled to the “fixture” moteus controller through a bearing support. Then that is connected via a 3d printed coupler to the “device under test” moteus controller, which is hard mounted to the base plate. Any net torque between the two controllers will be coupled back to the transducer resulting in a measured torque.

I mounted it all to a nicely machined fixture plate I got from ebay. It’s flexible enough that I can build one for the qdd100 on it as well, although I might just get an entire second setup so that I can leave them both assembled all the time.

Torque transducer

I’ve been wanting to build a dynamometer for a while to better characterize the performance of the direct drive and geared versions of the moteus controller. I have now started down that path with a torque transducer, which I calibrated with the below fixture:

I got a what ended up being a low quality load cell amplifier to use with it from the same supplier, although discovered it was total garbage and am now using a SparkFun OpenScale board which seems to be working much better. Soon I’ll hopefully have something wired up that actually has a controller or two on it.

Up-rating the qdd100 beta thermal bounds

When I first posted the qdd100 beta on mjbots.com, I performed a simple “continuous torque” test where I measured the torque that could be applied indefinitely without thermal limiting in a lab environment. It has come to my attention that other servos rate their “continuous torque” for a much lower value of “continuous”, sometimes only 30s. To make the situation clearer, I measured the time to thermal limiting at a range of torques and updated the product page.

For this test, at each torque value I started with the qdd100 in thermal equilibrium with an ambient 20C lab environment, then applied the given torque and waited until thermal throttling set in. No forced airflow was present and no conductive or radiative cooling enhancements were used.

TorqueTime to Thermal Limit
12.5 Nm< 5 s
10 Nm30s
8 Nm120 s
6 Nm300 s
4 Nm800 s
2.5NmIndefinite

Dealing with stator magnetic saturation

In my previous experiments demonstrating torque feedback (full rate inverse dynamics, ground truth torque testing), I’ve glossed over the fact that as the stator approaches magnetic saturation, the linear relationship between torque and current breaks down. Now finally I’ll take at least one step towards allowing moteus to accurately work in the torque domain as motors reach saturation.

Background

The stator in a rotor consists of windings wrapped around usually an iron core. The iron in the core consists of lots of little sub-domains of magnetized material, that normally are randomly oriented resulting in a net zero magnetic field. As current is applied to the windings, those domains line up, greatly magnifying the resulting magnetic field. Eventually most of the sub-domains are aligned, at which point you don’t get any more magnifying effect from the iron core. In this region, the stator is said to be “saturated”. You can read about it in much more depth on wikipedia or with even more detail here. The end result is a curve of magnetic field versus applied current that looks something like this:

To date, moteus assumes that you are operating completely in the “Linear” region, where the torque and current are linearly related.

Operating in the Rotation Region

To operate in the “rotation” region I ended up using the following formula:

\tau = K_T * I_c + ts * log2(1 + (I - I_c) * is)

Where I is the input current, K_T is the motor torque constant, ts, I_c and is are three constants that I fit to measured torque data. With some approximations, this can be calculated relatively efficiently on the STM32G4 that drives the moteus controller, adding only a microsecond to the overall loop time to go in both directions.

I then ran a torque sweep with my load-cell fixture from before, and sure enough, the input and output torque match much better now across the entire range of operation, despite the fact that the phase current needs to start growing very rapidly near the top end:

Testing qdd100 stator windings

My initial design torque for the qdd100 was a little over 17 Nm. However, when I did my first ground truth torque testing, I found that some servos had a lower maximum torque than I had specified. While working to diagnose those, I built a qdd100 that used an alternate stator winding of 105Kv instead of the 135Kv that are in all the beta units. The Kv rating of a stator describes how fast the motor will spin for a given applied voltage. If you assume the same amount of copper mass of wiring, a lower Kv will mean that there are thinner wires that wrap around the stator more turns (or fewer wires in parallel). A higher Kv will have thicker wires with fewer overall turns.

On paper, if you assume a perfect controller, this shouldn’t make much of a difference. The same input power should be required for the same output torque. The only differences should come into play once you have a controller with either a limited maximum voltage or a limited maximum current. The higher Kv motor will be able to go faster given a fixed maximum voltage, and the lower Kv motor will have more torque for a given maximum current.

I wanted to verify that this was true as part of my evaluation to identify the cause of my decreased torque, so I used a slightly upgraded torque testing fixture:

For now, I rigged up the world’s cheapest load cell from amazon to a Nucleo configured to report the load in grams over the serial port. I also wired up my Chroma power supply over USB using the linux USBTMC driver. With those two things hooked up, I was able to run tests that sweeped across torque commands, while recording output torque, phase current, and input power.

At higher torques, the input power was pretty sensitive to the temperature of the windings — hotter windings increased the resistance, which increased the power required to achieve a given phase current, thus my plot isn’t perfect as it was grabbed over several different runs. For the highest power samples I couldn’t use my Chroma, as it is limited to around 600W. Thus those samples don’t record the input power.

Plotting the input power vs output torque on the same chart shows that indeed, modulo some measurement error, they are the same for the two stators:

So, this experiment reaffirmed my understanding of stator magnetics and confirmed that the stator winding was not the cause of my decreased torque.

Ground truth torque testing for qdd100

First, a limited number of qdd100 servos are available for sale to beta testers!  Check them out at mjbots.com.

After building up the first set of qdd100 servos, I wanted to empirically measure their performance parameters.  Some astute commenters uncovered in my terrible juggling video, that I didn’t actually have any ground truth measure of torque with these actuators.  Given that the ultimate torque is a pretty useful performance metric, it’s a good thing to have a solid understanding of.

To measure this, I built a simple test fixture (which is also the qdd100 beta development kit), consisting of two brackets.  The first lets the servo be bolted to a table, and the second mounts to the output and has set screws to hold a 1″ diameter pipe.  I used this to insert a 1 meter pipe which then can press against a digital scale.

dsc_0379
1m is pretty long for my workshop!

Then I created a simple C++ application which emitted torque commands in response to joystick input and reported back telemetry from the servo: qdd100_test

Using these I was able to generate a plot of actual torque vs motor phase current:

qdd100 torque vs phase current

There are a couple of interesting things here, one is that the torque constant at low phase currents is slightly lower than I had estimated based on the motor’s Kv rating.  Second, the torque constant drops off faster at higher currents than I had anticipated, and third, the motor Kv rating was lower than I had predicted.  Those things combined result in a peak torque of between 12.5 and 15Nm depending upon the servo.  That’s still enough torque to do some serious jumping, but exploring those discrepancies is now on my backlog.

Here’s a video showing how this testing (and max speed testing) was done: