Tag Archives: moteus

moteus firmware release 2021-09-19

This new release makes minor improvements to support for r4.8 moteus boards, notably it makes the Kv and winding resistance calculation more closely match that measured by r4.5 and decreases audible noise when controlling to 0 current or torque.

Get it from github: moteus 2021-09-19

Note, this does require a new version of moteus_tool to be able to flash over CAN, version 0.3.29. You can get it from pypi using any of the normal pip3 methods: https://pypi.org/project/moteus/

Compensating for FET turn-on time

A motor driver like moteus switches power to the phases of a brushless motor using a set of 6 (or possibly more), MOSFETs. The typical topology involves 3 high side N channel MOSFETs and 3 low side N channel MOSFETs arranged in 3 half bridges like this:

(example 3 half-bridge from DRV8353 reference manual)

Since the gates of these FETs need to be driven with potentially high voltages, and you never want the high side and low side to be on at the same time, typically a gate driver is used. For the moteus r4.5 and earlier controllers, the DRV8323 driver from Texas Instruments is what performs this function. This driver lets you configure the drive current for each of the gates for both operations, charging up the gate and discharging it. For high power drive systems, charging up or discharging the gate too fast can result in undesired transients like accidentally switching the other FET on due to capacitive coupling, or inductive ringing as the current starts moving through the FET instead of the body diode. If the gate charges too slowly, then the FET spends much of its time not fully on, which increases power dissipation in the FETs.

For the purposes of this write-up, this means that the FETs do not turn on or off instantly, and the turn-on time can differ from the turn-off time.

Control structure with PWM mapping shown

One of the lowest levels of control in moteus accepts a set of desired voltages on each of the 3 phases, and then selects a PWM duty cycle for the 3 phases which attempts to achieve those voltages. For most control purposes this mapping isn’t too critical, as usually it is driven by an outer current loop, which selects these values to try and achieve a desired phase current. Thus any non-linearities are mostly washed out, just reducing the control performance a bit. The times it is most important is during motor calibration when a fixed voltage waveform is applied for spinning the motor, and when the phase resistance and inductance of the motor are estimated.

To date, that function has used a relatively simple model that treats the 3 phases independently. For each phase, the voltage is mapped to a PWM using a piecewise linear approximation with two segments. This works reasonably well on the r4.5, and gets the resistance and inductive measurements into a usable territory.

Problems brewing

As a consequence of the global semiconductor apocalypse, I’m working on a new version of the moteus controller that uses a gate driver which it was possible to purchase with less than a year lead time. Unfortunately, it is more sensitive to failure induced by ringing than the DRV8323 was. Because of the abbreviated design timeframe, I left the power stage of the r4.5 alone when making this switch, and it had a fair amount of ringing when using the drive currents it is configured with by default. So, for the new board, it needs to be run with much slower gate drive waveforms than the r4.5 board could achieve.

Using the lower current results in a very distorted mapping between PWM and voltage on the phase terminals, such that calibration wouldn’t complete and measuring the phase resistance was not practical. You can get an idea of the problem by looking at the plot below of phase current during the motor calibration phase. The driving voltage is a sine wave, and the current is supposed to be a sine wave also. Because of the additional distortion, low voltage commands result in nearly no actual current production and there is a large undesired waveform when the three phases are active, but at different levels.

Thankfully current control mostly worked, although it likely suffered from degraded performance at small currents. Despite that, not being able to calibrate is a big deal, so I had to take another look at this control step to make it able to handle the larger non-linearity.

Quantifying the problem

I didn’t necessarily want to try and model the gate drive at a more detailed level to understand this, to tackled the quantification problem by brute force. I wrote a simple tool which commanded a fixed PWM on the A phase, and then did a 2D sweep over the B and C phases in a region where my power supply could provide sufficient current without undue heating. The plots of the B, and C currents as 3D surfaces are shown below (the A current can be found from those two currents).

B and C phase current vs PWM

I think numerically inverted that mapping, to determine the necessary B and C pwm values to achieve a given B and C phase current.

The C phase plot looked the same just mirrored. Notably, this has two distinct regions. There is a region which extends to infinity where the command B is related to the desired B 1 to 1 with a fixed offset. However, that region only seems to exist beyond a line that is related to the C command. On the other side of that line, the fixed offset is no longer required. I did a rough curve fit to this, which looks like:

In the above plot, the sampled data is now faded out, and the simple surface fit is fully saturated. It works plenty well, and is controlled by 2 parameters as before (since the dividing line between the two regimes seems to not be something that is likely to need to be configured).

Results

I reworked the mapping to always operate in terms of a B and C phase that are larger than the A phase, then shift things back to the correct phase and balance afterwards. That way this correction surface could be applied as is.

This new technique gives much better low-voltage performance, especially when more than one phase is active and when larger amounts of compensation are required. Here’s a plot showing the current waveform during a sinusoidal calibration sweep.

Comparison of PWM compensation methods

With the r4.5 board, you can see the low voltage performance improve a fair amount. With the newer r4.8 board and its higher required compensation, the improvement is dramatic.

moteus r4.8

I’m excited to announce the release of moteus r4.8!

Due to the ongoing semiconductor apocalypse, this minor release uses some alternate components which were easier to source. It remains compatible with the r4.5 and r4.3 both electrically, mechanically, and with firmware.

For now, the biggest win is that the board and the devkit are actually in stock!

A secondary win is that external primary encoders are now supported, via an unpopulated connector pad on the backside of the board. I’ll write up more about that in a later post.

Good luck building!

CAN prefixes for moteus

The moteus controller, communicates exclusively over CAN-FD for command, telemetry, and diagnostics. It will accept either standard or extended frames, and until now, the ID format in terms of bits looked like the following:

33333222222221111111100000000
43210765432107654321076543210
XXXXXXXXXXXXXQSSSSSSSDDDDDDDD

Where:

  • X: Don’t care
  • Q: 1 for query, 0 for no query
  • S: source ID
  • D: destination ID

If the lower 8 bits matched the configured ID, all the X bits would be completely ignored and moteus would accept the CAN message as if it were destined for itself. This may not be super desirable, as it consumes nearly all of the available CAN-FD addressing space.

Starting with firmware version 2021-08-20, moteus now uses the following ID format:

33333222222221111111100000000
43210765432107654321076543210
PPPPPPPPPPPPPQSSSSSSSDDDDDDDD

Where P is a 13 bit “CAN prefix” that can be configured and defaults to 0. moteus will only accept CAN frames where this prefix matches the configured value*, and all frames it sends will have the prefix set as configured. This allows you to reclaim large sections of the CAN ID space for other devices in the event that moteus controllers share a bus.

[*] Footnote: The bootloader will require that the CAN prefix be set correctly, but WILL NOT set the prefix on the messages it sends. The existing moteus client side tools will function, but other devices on the bus may be confused.

Gear testing fixtures

The qdd100 servo uses a planetary geartrain as the transmission reducer. This consists of an outer ring gear, an inner sun gear connected to the rotor as the input, and 3 planets connected to the output. The tolerances of these gears directly impacts the performance of the servo, namely the backlash and noise.

To date, I’ve been hand-binning these and testing each servo for noise at the end of production. To make that process a bit more deterministic, and with less fallout, I’ve built up a series of manual and semi-automated gear metrology fixtures to measure various properties of the gears.

Some of the simple ones are just tools to hold micrometers in convenient locations relative to gears or meshing gears, like this one to measure the OD of the ring gears at various points:

Or this one to measure the meshing of the sun gear with a rack gear:

Or this one to measure the meshing of a ring gear with a reference sun gear:

Semi-automated tools

As I went to use these techniques for production, manually measuring the gears both was tedious, and still not as useful as it could be. It wasn’t feasible to do more than record a minimum and maximum when measuring a gear by hand, and for some parameters, measuring it at many points around the circumference is helpful. Thus, I’ve started on some automated gear testing fixtures.

The first is one that tests sun gears against a reference planet:

This has a few pieces. The motion platform is a moteus devkit motor with a reference planet gear attached. This spins a “test” sun gear which rests on a linear rail. Then a dial indicator is positioned to record the position of the carriage. An arduino connects to the SPC data port on the dial indicator to programmatically read the position. I used a technique similar to this forum post, except that my iGaging dial indicator runs off about 3V, so I didn’t bother with a separate pull down transistor and just toggled the REQ pin between input and output low to initiate readouts. That meant I could just plug the 4 wires directly into the Arduino.

When this runs, the reference planet is spun through small increments and the micrometer reading is captured at each point. This measures the “double flank” mesh distance of the gear pair. Here, the indicator spring applies a pressure to the test gear, forcing it to mesh with the master gear.

To make this work, I characterized the reference planet gear by running a reference sun gear (which is a 20 tooth M0.5 gear), at all 20 different phases relative to the planet. Then I took the median of the distance across all the runs as the “reference curve” for this planet.

Then test gears are measured relative to that reference curve. That shows the delta between the center distance at each point and the reference distance, so should be relatively well calibrated for the fact that my master gear is not perfect, nor mounted perfectly concentric. Here is a plot from the same gear taken four times at different phases, shifted laterally to compensate for the phase difference and shows that it is relatively consistent and repeatable.

The process is unfortunately slow, primarily because the dial indicator SPC port only emits data at 2Hz, and it takes about 2 readings to settle after each motion. I was using 8 points per planet tooth for the above plot, which works out to 320 total samples per evaluation. At 1.5s per sample, that is around 7 minutes per gear! Fewer points still give reliable results, at a corresponding reduction in fine resolution.

Forgiving the slow speed, this does seem to give profiles that are repeatable to within about 10 microns, which is good enough for the binning I am doing now.

Filtering encoder values in moteus

TLDR: moteus can now filter the encoder, resulting in less audible noise. Use firmware version 2021-04-20 and ‘pip3 install moteus’ version 0.3.19, then re-calibrate to get the benefits.

Background

The moteus controller uses an absolute magnetic encoder to measure the position of the rotor. It uses this knowledge to accurately control the current through the three phases of a brushless motor so that the desired torque is produced, i.e. “field oriented control”. This works well, but has some downsides. One, is that magnetic encoders work by sensing the magnetic field produced by a “sensing magnet” that is somehow affixed to the rotor. This sensing process always introduces some noise, so that the sensed rotor position is never perfect.

Because of this, even if the rotor is perfectly stationary, moteus will constantly be tweaking the phase of the motor current to track the noise. This results in slightly increased power consumption, and more important to most, audible noise as the slight variations in control current can induce vibrations in the phase windings of the motor.

Fortunately, in most applications, the rotor is not actually capable of accelerating with the full bandwidth that the magnetic sensor is capable of sensing. Thus, we can filter it to remove high frequency noise without any loss of performance.

Approach

The filter method that moteus uses is an “all-digital phase locked loop“. Formulated in the traditional PLL terminology, this consists of three pieces: a numerically controlled oscillator, a phase detector, and a PI controller.

The “numerically controlled oscillator” is just a counter that tries to “guess” what the encoder is doing by propagating a value forward at an estimated velocity. For an ADPLL in this setup (where our encoder gives us an absolute phase measurement), the “phase detector” just subtracts the measured phase from the estimated phase. The PI controller determines how the estimated oscillator tracks disturbances in the actual encoder frequency.

In my post on automatic torque bandwidth selection for moteus, I derived the necessary equations for determining the torque bandwidth. Here, I’m just going to reference the excellent article by Neil Robertson, “Digital PLL’s” (part 1, and part 2), over at dsprelated.com. There, he derived the necessary proportional and derivative gains for a given bandwidth and damping ratio:

K_p = 2 \zeta \omega_{3db}

K_i = {\omega_{3db}}^ 2

Where \zeta is the “damping ratio“. For our purposes, we’ll use 1.0, which is known as “critically damped” and is often a good balance between stability and response time.

Experiments

To see this in action, I ran some experiments on a moteus devkit. I added back in a conditional ability to emit a few bytes of debugging information at the full control rate to the firmware, and used that to emit the encoder value as used by FOC at each control cycle. I made up a script, that can plot the power spectral density in the encoder measurements. This is basically the noise present at any given frequency. When run on an unmodified development kit with no encoder filtering, the result looks like:

Power spectral density of moteus AS5047P encoder in a devkit

This shows that there are peaks in the noise at around 700Hz and 2kHz and after that the noise drops off rather rapidly. Then if we enable filtering at a few different bandwidths, you can see how the plot changes:

Power spectral density of AS5047P with various filter bandwidths configured

The filter bandwidths here varied from 5000 rps (~800Hz) down to 100rps (~15Hz). The filtered noise profiles follow what one would expect for each of the filters.

Audible noise

To measure the combined effect of this and torque bandwidth on audible noise, I switched to a controller attached to an 8108 motor, as I’ve seen those tend to demonstrate more audible noise. The motor had a constant back and forth motion at 0.5Hz for 60s and the result was captured with a studio mic set about 1cm away from the motor. In each test, I ran moteus_tool --calibrate and selected only a torque bandwidth, letting it pick an appropriate encoder bandwidth. For the 100Hz torque bandwidth and above tests, the same position PID values were used, although they needed to be tweaked for stability at the lower bandwidths. I similarly plotted the power spectral density for several filtering values and for silence. The total signal strength measured in negative dB is noted in the label:

It is not shown here, but the unfiltered noise is about the same as the 400Hz one. Thus, the maximum improvement is around 6dB of audible noise. Filtering at 100Hz gives most of that benefit for this motor, with slight improvements beyond that. Most of the audible energy is in the spectrum below 1kHz and there are several frequency bands where the encoder does not appear to be the dominant source of audible noise, as all options are equivalent in those.

For comparison purposes, the ODrive firmware defaults to filtering both the torque and encoder at around 160Hz (1000rps).

moteus_tool integration

As of version 0.3.19, moteus_tool has support for configuring the encoder bandwidth during calibration. By default, it will select a value appropriate for the selected torque bandwidth, or you can specify it manually with --encoder-bw-hz.

moteus direction configuration

Since the first public release, moteus has always calibrated motors so that a positive command is equivalent to a fixed sequencing of the phase wires. That means that depending upon which order you solder the phase wires, a positive commanded velocity will result in the motor spinning either clockwise or counterclockwise.

As it turns out, since moteus has an absolute encoder that is immune to such vagarities, it is much more convenient to normalize the direction of rotation around the encoder rather than the phase wires. As of release 2021-04-26, and moteus_tool 0.3.22, that is exactly what moteus does.

Now by default, moteus_tool will attempt to calibrate the motor such that a positive command results in a positive encoder value (this will be clockwise rotation when looking at the front of the motor / back of the moteus board). If the firmware is too old, it may not be able to do this, in which case it will emit an error.

You can also, use the new ‘--cal-invert' option, which will have moteus calibrate the motor such that a positive command results in the encoder moving in the negative direction. For some existing deployed systems, you must use this option if you want the calibrated motor to have the same sense of direction as before (even with old firmware). As before, if this is not possible because the firmware is too old to support the necessary configuration, an error is emitted.

Auxiliary encoders for moteus

The moteus controller uses an absolute magnetic encoder to sense the position of the rotor in order to conduct field oriented control of the motor. In many applications, this sensing is also sufficient to measure the output as well, particularly in direct drive applications. However, if the controller is driving the output through a gear reduction, multiple turns of the input are necessary to make one turn on the output. At power on, this results in an ambiguity, where the controller doesn’t know where the output is.

There are a couple of possible solutions to this, one is to do like the quad A1 does, and have a “known turn on position”. Another would be to have a rigid end stop and use a homing procedure on startup. Yet another would be to have a non-backdrivable mechanism and remember in the host application how many revolutions had been taken.

Auxiliary encoders

What I’m going to cover here is yet another solution to this problem, an auxiliary encoder. In this approach, a second absolute encoder is used to measure the position at the output directly, thus directly resolving all ambiguity. All of the production moteus controllers have had a, to date unused, connector named ABS which has pins intended for I2C on it. As of revision 2021-04-09, moteus can now use these pins to read the position from an AS5048B absolute magnetic encoder.

After reading, it uses the values for two purposes. First, it reports the measured value out over both the diagnostic and register interface, so that host applications can use it. It also can be optionally used to initialize the value of “unwrapped_position” at startup.

Setting it up

Getting an auxiliary encoder working is pretty easy. First, you need to wire something up. If you don’t already have hardware, you can use these cables from amazon, and this breakout board from digikey. Here’s a photo of those connected up with with a .1″ connector in between.

The pinout on the moteus board is described in the reference manual:

  • Pin 1: 3.3V (closest to ABS label)
  • Pin 2: SCL
  • Pin 3: SDA
  • Pin 4: GND

Then you connect it to the moteus (while off) and install the breakout board facing a magnet. Here, I made a simple 3d printed belt reducer:

Now we can go into tview and configure things. First, we use the config abs_port.mode from the reference manual, and set it to the value for an AS5048B (1). Then we will configure an offset using abs_port.position_offset, and finally set the position to be set from this encoder on startup with servo.rezero_from_abs.

And that’s all that is necessary!

Using it

At this point, the current value of the encoder can be read at in tview at 'abs_port.position' or register 0x006 as documented in the reference manual!

Here’s a video showing a bit more detail:

New available limits in moteus firmware

Some of the new features in the moteus 2021-04-09 firmware release are new limits that can make the overall system more robust to faults or environmental conditions.

Velocity limiting

config: servo.max_velocity

Like the position limits, there now is a configurable velocity limit. If the motor is moving faster than this limit in either direction, then the applied torque will be limited, eventually to a value of 0. This can be used to reduce the likelihood of runaway behavior in systems where high speeds are not expected.

moteus development kits come with this value set to 10 revolutions per second. It can be easily changed in tview.

Power limiting

config: servo.max_power_W

This limit throttles the available PWM when the overall power applied to the motor exceeds this configured value. By default it is set to 450W, slightly less than the moteus’s rated power of 500W. This limit is intended to reduce the likelihood of damaging the controller through an over-power situation.