IAP 2017: servo control of stepper motors

Sam Calisch

This IAP I want to work on a closed loop stepper motor driver. There is a natural hierarchy of methods for closed loop stepper control:

This last option is what I'd like to do. The advantages of this technique are ~50% higher torque at low RPMs, higher positioning resolution than open-loop microstepping, higher max RPM than open loop, cooler running motors, and the ability to run in position-, velocity-, or torque-control modes.

This is all born out of a real frustration with the choice between stepper motors and dc gearmotors when building machines. We always want a lot of torque in a small package and force feedback is especially nice for dynamic processes, so dc gearmotors seem like the way to go. Unless you break the bank, however, the backlash in a cheap gearbox can really be a major hindrance. At one point I went down a rabbit hole in making DIY low-backlash gearboxes on the wire-EDM, but this would never be cheap or scalable. Conventional stepper drives, on the other hand, can be just as frustrating. Lost steps can do a lot of damage, and even simpler closed loop control can be fussy business. Besides this, steppers are bulky for their torque rating and can dissipate quite a bit of heat under normal operating conditions.

So, in short, my goals is to implement a cheap, scalable version of servo control for stepper motors. I've got lots of projects I want to use this for, most immediately my diy sewing machine, where it will do a better job synchronizing the three degrees of freedom than the gearmotors I'm using now, while also slimming down the profile nicely:

Or, as Tomer put it, a cheap, open-source alternative to the impressive Clearpath servos:

It turns out, however, position feedback we can treat a stepper motor just like a generic brushless dc motor. The high pole count gives us a lot of torque (we're never too far from a pole), but we need significantly higher resolution and lower latency in the position feedback to commutate correctly.

Comparing brushless stepper and servo motors.

As I think about it, there are several options to do this, falling broadly into sensored and sensorless categories. We outline them below, starting with sensored approaches:

Magnetic Shaft Encoder

Miniaturized hall effect encoders provide non-contact position measurement with surprisingly high resolution.

Hall effect encoder

In fact, there is already a kicstarter project using the AS5047D (a 14-bit, latency-compensated magnetic encoder from Austrian Microsystems) to do servo control of stepper motors: Mechaduino

Mechaduino PCB

I see a few things I'd like to change in this design (higher current H-bridge, tighter firmware timing), but it's good to see just how good the results can be.

Magnetic Wheel Encoder

Same as above, but using a multi-pole wheel to reduce resolution/latency requirements on encoder IC. AMS's offerings here aren't great, the 5311 is probably the best IC for this, but it's latency is ~100 us. Too high.

Austrian microsystems 5311 linear / off-axis shaft encoder.

Could also do a discrete array of hall effect sensors with a magnet wheel...

Sense winding

A really cool product called Mosolver boasts 32,000 counts per revolution using only a small sense coil inside the motor. This is super neat, but requires a circumferential slot in the stator that common hybrid stepper motors don't have.

Mosolver
Mosolver video

Capacitive Encoder

As long as we're talking about encoders, we have to mention capacitive methods. One of my favorite encoders (the AMT10X from CUI) is capacitive and has resolution up to 2048 counts per revolution. This isn't high enough for our application, but we could might use these methods. I started reading a patent from Mitutoyo (maker of fine measuring equipment) to understand the capacitive technology in their calipers.

Capacitive calipers

The techniques are a beautiful extension of this earlier patent to create a coarse, medium, and fine measurement from a single electrode array, allowing fast, high-resolution measurements to be made. I can imagine a rotary implementation of this on a milled codewheel for a nice fabbable encoder.

Sensorless: Back EMF Only

A company called Nanotec made a silly but cool video:

Nanotec's sensorless drive video

Digging around, there are quite a few papers on these techniques. They use the fact that back EMF and torque both depend on angle and angular frequency to do some state estimation, usually with a Kalman filter. Following Field Oriented Sensorless Position Control of a Hybrid Stepper Motor with Extended Kalman Filter, we can estimate state parameters $\theta$ (angular position), $\dot{\theta}$ (angular velocity), and $T_L$ (load torque) using equations of inductance for each phase, and a torque balance equation: $$ \frac{\partial i_a}{\partial t} = \frac{v_a - R i_a + K_m \dot{\theta} \sin {N_r \theta}}{L} $$ $$ \frac{\partial i_b}{\partial t} = \frac{v_b - R i_b + K_m \dot{\theta} \cos {N_r \theta}}{L} $$ $$ \frac{\partial \dot{\theta}}{\partial t} = \frac{ K_m i_b \cos{N_r \theta} - K_m i_a \sin{N_r \theta} - T_L - B \dot{\theta} }{J} $$ where $i_a$ (resp. $i_b$) is the current in phase A (resp. phase B), $v_a$ (resp. $v_b$) is the voltage across phase A (resp. phase B), $B$ is viscous friction, $J$ is motor inertia, $K_m$ is the motor torque constant, $R$ is phase resistance, $L$ is the phase inductance, and $N_r$ is the number of teeth per phase. With this state estimate, we can then implement field oriented control.

Critically, the position error they measure is less than .0004 radians, or about 16000 error bands per revolution. This is the positioning resolution range we're looking for. It's important to note that this test appears to have been in an unloaded condition, and a variable shaft load will likely reduce this effective resolution.

The paper Position Control of a Sensorless Stepper Motor, extends this by including phase resistance in the state parameters (as it is temparature dependent, and hence can vary over time). They also experiment with the system's response to a changing shaft load. They don't include an measure of the estimation accuracy, but they directly implement feedback controller and measure the total system's response.

Variable Reluctance

When I started thinking about the sensorless methods above, I couldn't believe that inductance was independent of position. In fact I thought it should vary a great deal between each step as the teeth of the rotor and stator came in and out of alignment. If this was true, I thought I could use this to get a good estimate of rotor position. 100 levels of discernable inductance over 100 rotor teeth is 10000 counts per revolution -- equivalent to a very nice encoder. I thought I would use the XMega's comparator to build a chopper drive for current control. The chopping delay is a function of R/L and is easy to measure with the event system and an onboard timer counter. The comparator has a 6 bit DAC (64 levels) for current set points. Alternatively, we could use the built in DAC (12 bit), but even though is has two channels, it only has one conversion block (1 MSPS) that alternately converts the CH0 and CH1 registers.

Before designing a board to do this, I made a simple test jig to see how inductance depends on sub-step position. I use a long lever clamped to the stepper shaft to turn it in very small increments. A fine-adjustment screw (1/4-80 thread) moves it such that each screw rotation is 1/10th of a step. A spring biases the lever arm against the screw. It's designed to be machined in two operations, but I printed one on the 3DWox for a fast test.

Jig for measuring inductance at varying rotor positions.
Scope traces at 1Hz (~DC) and 1kHz (frequency for Inductance spec)

To my surprise, the measured phase angle (~50 degrees) was remarkably constant with respect to rotor position. After thinking about this for a while, I realized this makes sense, as inductance only depends on time varying magnetic flux, not on the static flux from the permanent magnets. Therefore, the inductance is really more a function of the amount of magnetic material on the rotor close to magnetic material on the stator. The images below show this remains relatively constant, despite the constant flux pointing in different directions on different stator discs.


Hybrid stepper motor rotor teeth passing a stator tooth.

Sensorless servo-stepper driver PCB Design

I started designing a board to test these sensorless methods. I'm planning to use a pair of A4950 H-bridge ICs from Allegro to drive the phases of the stepper motor. This package has a convenient footprint, delivers 3.5A continuously, and accepts PH/EN inputs. For current monitoring, ideally we'd use a "flying" sense resistor directly in series with the motor or do a dual sense trick on each leg of the H bridge . Both of these require a differential amp in order to handle the high common mode voltages. The latter isn't possible with the A4950 because the legs of the H-bridge are internal to the IC, so we can't measure them individually. We could still use a flying sense resistor, but the PWM drive signals will produce high frequency oscillations at the motor driving voltage. Dealing with this would require a nicer op amp than I'm planning to use for this cheap circuit.

Flying sense resistor and dual configuration (from Linear's Design Note 407).

Given this, I think I will use a simple low side current measurement shown below, which is compatible with the A4950. Further, since the sense voltages won't shift to the motor driving voltage at the PWM frequency, I don't need a nice current sense amp with perfect CMM (I think...). Importantly, however, in "slow decay mode" the internal recirculation current will not be measureable with the low side resistor (shown below, and in TI's SLVA321, which gives a good description of H-bridge decay modes and their uses). Question: why don't people use dual low side measurement?

H bridge decay modes (from TI's DRV8833C Datasheet).

This inability to measure recirculation currents is a key disadvantage of the low side measurement, but if we don't use slow decay maybe this is ok. Importantly, if we only use fast decay, our PWM resolution is cut in half because at 50% duty cycle is zero current flowing (assuming PWM frequency is fast compared to L/R ~= 1e-3).

Assuming this is ok, we still have a bipolar voltage measurement with respect to ground, so we can use a resistor network to shift it into the ADC's range (paying a small price in signal amplitude). This network and the current balance equation is shown below.

Current balance equation for resistor network.

With such a resistor network on an ADC input, we need to be conscious of the total impedance, as raising it too much will decrease our maximum sampling frequency. From the datasheet, I made the first graph below, including the overall bounds on the XMega ADCs. Looking at this, it seems an impedance below about 5 kOhms would be nice. Further, we can provide a stable reference from the Xmega bandgap out on a pin using the internal DAC for the top side voltage reference for our resistor network. The minimum resistance the DAC can drive is 1 kOhm, so the network must present a higher load than this to be safe. These two considerations put us in the gray box in the right graph below.

Sizing resistor network for sampling rate and hardware constraints.

To size the rest of the resistor network, we need to consider the size of the sense resistor voltage signal. It's possible to get inexpensive sense resistors up to about 1W power rating. At the max 3.5 amps continuous from the H-bridge, that gives a maximum of 80 mOhms. To be safe, let's make is 50 mOhms. This means the voltage signal will fluctuate over +- 175 mV. Let's map +-200 mV into the ADC range. The equation above means that with $V_{ref}=1 V$, we need $R3/R1 = .2$. Picking 2 kOhms on the graph above for R3, this means R1 and R2 must be 10 kOhms. These values are cheap to obtain with .1% accuracy specs. Below is LTSpice simulation confirming that we do map the bipolar signal onto the interval 0 - 280 mV. This is perfect to use the Xmega 4x gain stage with the bandgap reference.

Spice confirmation of the resistor network's behavior.

I got a first version of the board routed (see below). I put the encoder on the back (so as not to redo much work when I potentially take it off the board). I also routed the sense lines on the back -- I may figure out how to keep them on top later, but for now it was easier this way.

After some debate, I moved away from using Allegro's packaged H-bridges, and used a bare H-bridge with 2 N-channel and 2 P-channel MOSFETS. This was partially for ease of routing and component cost (about one third the price), but mostly to avoid the A495x's internal current control logic with a sense resistor. With one as small as mine, it likely wouldn't have tripped (keeping VREF at 3.3V), but I didn't want to risk it (and I didn't want to pay for something I wasn't using). Plus, it gives me a chance to use the XMega's built in dead-time insertion logic and advanced waveform generation capabilities. Depending on the results of this board, I may switch back to the Allegro parts, but I thought I'd give this a chance.

PCB Layout v1.

After some pain routing everything, I milled the board, using 1/64" end mill on the front side, and a .010" on the back (which is due to the encoder which won't be there on a final sensorless board if all goes well). I used threaded rod and standoffs to replace the stepper bolts so that I could mount my board securely to the back of the motor. There were a few mistakes, but nothing that couldn't be corrected with solder rework.

My first programming task was to get Xmega's advanced waveform extension module (AWEX) working. This allows you to map the 4 compare channels from a timer counter to 8 pins (4 complementary pairs). This is useful for driving H-bridges because we can divide the FETs into pairs that should never be open at the same time. This way, we can drive both H-bridge by simply setting the 4 compare values and generating the signals from a single timer/counter.

Further, the AWEX module allows dead-time insertion -- that is a short period of time around the transition (when one member of a pair goes high and the other goes low) where both pins are guaranteed to be low. With finite slew rates of mosfets and their gate drivers, this is important to prevent any current from shooting through one side of the bridge (thus bypassing the motor and destroying the fets). This module was really nice and easy to set up (code in progress is here).


logic analyzer output showing deadtime insertion of 2 and 4 clock cycles at 32 MHz. Note my logic analyzer's sampling frequency (50 MHz) isn't fast enough to accurately time these transitions (they should be 62.5 and 125 ns).

The figure above shows testing the dead time insertion (DTI) with my saleae logic analyzer (I wasn't near a scope at the time). The logic analyzer's frequency isn't fast enough to accurately time the dead time (it should be 62.5 and 125 ns for 2 and 4 clock cycles inserted, respectively), it convinved me I've got things hooked up correctly.

Next up, I've got to verify I can talk to the encoder over SPI and set up the ADC for current measurement. One nice advantage of using a single timer counter for the PWM generation is that I can use the timer overflow to trigger an ADC conversion. That way, I can measure at a consistent place (or multiple places, as in this project) in the RL charging curve. With these tasks finished, I can then implement the Kalman filter and start testing against the onboard encoder.

Looking forward, I've been thinking about what are some good tests to demonstrate this system. One common test is pointing a laser across the room to demonstrate step size. I don't yet know how effective the sensorless back-emf techniques will be at this task, because there is very little angular velocity. One idea for static pointing is to use the saturation nonlinearity of the core to use inductance for inter-step position estimates at zero speed.

Another task is to recover from a stall condition. The stepper could be tracking a trajectory, we grab the shaft to halt it, when we release the obstruction, it flies forward to catch back up with the trajectory.

Another task could demonstrate force control over a range of disturbances.

OK, I've now got the SPI communication with the encoder working. Current code is here. I was stuck for a minute, before realizing the XMega SPI shift register supports 8 bit frames, while I needed 16 bit frames for communication with the AS5047D. I wrote a function to transcieve two 8 bits frames, and verified this worked. For now this is blocking while the transmission occurs (around 1 us), but in the future I'd like to move this completely out of the loop, with XMega's DMA moving the bytes between variables and the SPI.DATA register. I also experimented with overclocking the SCK frequency to 16 MHz (using the 4 times divider with the 2x multiplier from the 32 MHz system clock). The AS5047D is only rated to 10MHz, but it tolerated the faster communication just fine in testing. Screenshot below, where we read the register for the magnetic field strength.


logic analyzer output for SPI communication