High Level Real-Time Control of Stepping Motors

Part z of Stepping Motors by Douglas W. Jones

Under Development

Introduction

The key question to be answered by the high-level control system for a stepping motor is, when should the next step be taken? While this almost always depends on the application, the similarities between different applicatons are sufficient to justify the development of fairly complex general purpose stepping motor controllers.

Stepping motor control may be based on open loop or closed loop models. We are primarily interested in open loop models, because this is where stepping motors excel, but we will treat closed loop models briefly because they are somewhat simpler. Figure z.1 illustrates an extreme example:

Figure z.1 
     ________
    |        |    _______
    |        |___| Shaft |___
    | Motor  |___|Encoder|___ ... Load
    |        |   |_______|
    |________|      | |
      _||||_        | |
     |Motor |-/-----  |
     |Driver|-\-------
     |______|


In Figure z.1, a quadrature shaft encoder is attached to the drive shaft of a permanent magnet or hybrid stepping motor, and the two phase output of this encoder is used to directly generate the control vector for the motor driver. Rotary shaft encoders are typically rated in output pulses per channel per revolution; for this example to be useful, for a motor with n steps per revolution, the shaft encoder output must gives n/2 pulses per channel per revolution. If this is the case, the behavior of this system will depend on how the shaft encoder is rotated around the motor shaft relative to the motor.

If the shaft encoder is rotated into a position where the output of the shaft encoder translates to a control vector that holds the motor shaft in its initial position, the motor shaft will not rotate of itself, and if the motor shaft is rotated by force, it will stay wherever it is left. We will refer to this position of the shaft encoder relative to the motor as the neutral position.

If the shaft encoder is rotated one step clockwise (or counterclockwise) from the neutral position, the control vector output by the shaft encoder will pull the rotor clockwise (or counterclockwise). As the rotor turns, the shaft encoder will change the control vector so that the rotor is always trying to maintain a position one step clockwise (or counterclockwise) from where it is at the moment. The torque produced by this method will fall off with rotor speed, but this control system will always produce the maximum torque the motor is able to deliver at any speed.

In effect, with this one-step displacement, we have constructed a brushless DC motor from a stepping motor and a collection of off-the-shelf parts. In practice, this is rarely done, but there are numerous applications of stepping motors in closed-loop control systems that are based on this model, usually with a microprocessor included in the feedback loop between the shaft encoder and the motor controller.

In an open-loop control system, this feedback loop is broken, but at a high level, the basic principle remains quite similar, as illustrated in Figure z.2:

Figure z.2 
     ________
    |        |
    |        |_______________
    | Motor  |_______________ ... Load
    |        |           __________
    |________|   -----\-| Model of |
      _||||_    |  ---/-|  Motor   |
     |Motor |-/-  |     | and Load |
     |Driver|-\-  |     |__________|
     |______|   | |          | |
                |  ----/-----  |
                 ------\-------

In Figure z.2, we replace the shaft encoder from Figure z.1 with a simulation model of the response of the motor and load to the control vector. At any instant, the actual positon of the rotor is unknown! Nonetheless, we can use the simulation model to predict, based on an assumed rotor position and velocity, how the motor will respond to the control vector, and we can construct this model so that its output is the control vector generated by a simulated shaft encoder.

So long as the model is sufficiently accurate, the behavior of the motor controlled by this model will be the same as the behavior of the motor controlled by a closed loop system!

Model Variables

In the example given in Figure z.1, the only control variable offered is the angle of the shaft encoder relative to the motor. In effect, this controls the extent to which the equilibrium point of the motor's torque versus shaft angle curve leads or follows the current rotor position. In theory, any desired motor behavior can be elicited by adjusting this angle, but it is far more convenient to speak in terms of other variables:

Theta -- The predicted shaft position (radians)
Thetatarget -- The target shaft position determined by the application
V = dTheta/dt -- The predicted velocity (radians per second)
Vtarget -- The target velocity determined by the application
A = dV/dt -- The predicted acceleration (radians per second squared)
Atarget -- The target acceleration, may be determined by the application
As in the section on Stepping Motor Physics, we will define the basic motor characteristics:
S -- step or microstep angle, in radians
µ -- moment of inertia of rotor and load
h -- the holding torque of the motor
Note that here, the step angle S is not the physical step angle of the motor, but rather, the step angle offered by the mid-level motor interface; this may be a full step, a half step, or a microstep of some size!

Models

The simplest model that will do the job is almost always the best. For some applications, this means the model is so simple that it is hard to identify it as a model! For example, consider the case where the application demands a constant motor velocity:

Atarget = 0
Vtarget = Constant
In this case,
tstep = S / Vtarget
where
tstep -- time per step
This barely looks like a model; in part, this is because we have omitted the statement that, every tstep seconds, we advance the control vector one step:
repeat the following cycle forever:

wait tstep seconds and then
Theta = Theta + S
step( 1 )

A more interesting model is required if we want to maintain a constant acceleration. Obviously, we can't do this forever, but we'll use this model as a component in more complex models that require changes of velocity or position. In this case,

Atarget = Constant
where
Atarget < h / µ
In developing a model, we begin with the observation that, for constant acceleration A and assuming a standing start at time 0,
Theta = 1/2 A t2
More generally, if the motor starts at position Theta and velocity V, after time t the new position Theta' and velocity V' will be:
Theta' = 1/2 A t2 + V t Theta V' = A t + V
Setting Theta=0 and Theta'=S, we solve first for t, the time taken to move one step, as a function of V and A:
1/2 A t2 + V t - S = 0
t = ( -V ± ( V2 + 2 A S )0.5 ) / A
Here, we have applied the quadratic formula, and for our situation, this gives two real roots! The additive root is the root we are concerned with; for this, we can use the resulting time to compute the velocity at the end of one step:
tstep = ( -V + ( V2 + 2 A S )0.5 ) / A
V' = ( V2 + 2 A S )0.5

We can combine this model for acceleration with the model for constant speed running to make a motor controller that will seek Vtarget, assuming that an outside agent may change Vtarget at any time:

repeat the following cycle forever:
if V = Vtarget do the following:
wait S/Vtarget seconds and then
Theta = Theta + S
step( 1 )

otherwise, if V < Vtarget, accelerate as follows:
wait ( -V + (V2 + 2 AaccelS)0.5 ) / Aaccel seconds and then
Theta = Theta + S
V = (V2 + 2 AaccelS)0.5
step( 1 )

otherwise, V > Vtarget, decelerate as follows:
wait ( -V + (V2 + 2 AdecelS)0.5 ) / Adecel seconds and then
Theta = Theta + S
V = (V2 + 2 AdecelS)0.5
step( 1 )
This control system is not fully satisfactory for a number of reasons! First, it only allows the motor to operate in one direction and it fails utterly when V reaches zero; at that point, if a divide by zero operation is allowed to produce an infinite result, the program will wait infinitely and never again respond to change in the control input.

The second shortcoming of this program is simpler to correct: As written, there is an infinitesimal probability of the motor speed reaching the desired speed and staying there with Vtarget equal to V. Far more likely, what will happen is that V will oscillate around Vtarget, taking alternate accelerating and decelerating steps and never settling down at the desired running speed.

A quick and dirty solution to this latter problem is to add code to recognize when V passes Vtarget during acceleration or deceleration; when this occurs, V can be set to Vtarget. Formally, this is incorrect, but if the acceleration and deceleration rates are not too high and if there is sufficient damping in the system, this will work quite well.

In a frictionless system using sine-cosine microstepping at speeds below the cutoff speed for the motor, the available torque is effectively constant and we can use the full torque to accelerate or decelerate the motor, so the above control algorithm will work with

Aaccel = Adecel = h / µ
If there is significant static friction, we can take this into account as follows:
Aaccel = ( h - f ) / µ
Adecel = ( h + f ) / µ
where
f -- frictional torque
If the motor is run using the maximum available acceleration and decleration, any unexpected increase in the load will cause the motor rotor to fall behind its predicted position, and the result will be a failure of the control system. As a result, open-loop stepping motor control systems are never run at the accelerations give above! In the case of full or half-stepping, where there is no sine-cosine torque compensation, the available torque varies over a range of a factor of 20.5, so we typically adjust the accelerations given above by this amount:
Aaccel = ( ( h / 1.414 ) - f ) / µ
Adecel = ( ( h / 1.414 ) + f ) / µ
If we operate consistantly near the edge of the performance envelope, and if we never request a velocity Vtarget near the resonant speed of the motor, we can safely accelerate through resonances without relying on damping. If, on the other hand, we select acceleration values that are significantly below the maximum that is possible, electrical or mechanical damping may be needed to avoid problems with resonance.

Note that it is not difficult to extend the above control model to account, at least approximately, for viscous friction and for the dropoff of torque as a function of speed. To do this, we merely modify the above formulas for Aaccel and Adecel so that h and f are functions of V. Thus, instead of treating these as constants of the control algorithm, we must recompute the available acceleration at each step.

If our goal is to turn the motor smoothly from one set postion to another, we must first accelerate it, then perhaps coast at fixed speed for a while, then decelerate. The decision governing when to begin decelerating rests on a knowledg of the stopping distance from any particular velocity. Assuming that the available acceleration is constant over the relevant range of speeds, we can compute this from:

V = Adecel t
Theta = 1/2 Adecel t2
First we solve for the stopping time,
t = V / Adecel
and then we solve for the stopping angle
Theta = 1/2 Adecel ( V / Adecel )2 = V2 / ( 2 Adecel )
Given this, we can outline a procedure for moving the motor from its current estimated position to a step just beyone some target position:
moveto( Thetatarget )
-- a function of one argument Theta
-- no value is returned
while V < Vtarget
and while Theta < Thetatarget - V2 / ( 2 Adecel ) repeat the following to accelerate
step( 1 )
wait ( -V + (V2 + 2 AaccelS)0.5 ) / Aaccel seconds and then
Theta = Theta + S
V = (V2 + 2 AaccelS)0.5

V = Vtarget

while Theta < Thetatarget - V2 / ( 2 Adecel ) repeat the following to coast
step( 1 )
wait S/Vtarget seconds and then
Theta = Theta + S

while Theta < Thetatarget repeat the following to decelerate
step( 1 )
wait ( -V + ( V2 + 2 AdecelS )0.5 ) / Aaccel seconds and then
Theta = Theta + S
V = ( V2 + 2 AaccelS )0.5
V = 0
done, Theta and Thetatarget are within a step of each other!

The control model only moves the motor one direction, it fails to plan in terms of the quantization of available stopping positions, and it doesn't account for the cyclic nature of Theta. Nonetheless, it is a useful illustration. Note that we have used Vtarget as a limiting velocity in this code, but that this will only be relevant during long moves; for short moves, the motor will never reach this speed.

With the above, code, so long as the acceleration and deceleration rates are high enough to avoid dwelling for too long at resonant speeds, and so long as Vtarget is not too close to a resonant speed, a plot of rotor position versus time will show fairly clean moves, as illustrated in Figure z.3:

Figure z.3 
          |
          |                       --
          |                     /
          |              --
 position |            /       /
          |     --    
          |   /       /       /
          |--      --      --
        --|-------------------------
          |          time

If the motor is to be accelerated at the maximum possible rate, the control model used above is not sufficient. In that case, during acceleration, the equilibrium position must be maintained between 0.5 and 1.5 steps ahead of the rotor position as the rotor moves, and during deceleration, the equilibrium position must be maintained the same distance behind the rotor position. This requires careful logic at the turnaround point, when the change is made from accelerating to decelerating modes. The above control model omits any such considerations, but it is adequate at accelerations sufficiently below the maximum available!

Hardware Solutions

Today, it is rare to find high-level stepping motor control done purely in hardware, and when it is done, it is usually only in the very simplest of applications. For example, consider the problem of starting and stopping a stepping motor under load. Direct generation of the quadratic functions necessary to achieve smooth acceleration is quite difficult in hardware, but it is easy to generate exponentials that are adequate approximations of these. The circuit outlined in Figure z.4 illustrates how this can be done:

Figure z.4 
                                      ________
                                     |        |
                                     |        |___
                      _____          | Motor  |___
 run/stop            |     |         |        |
     o---/\/\/---o---| VCO |--       |________|
           R    _|_  |_____|  |     ____||||____
              C ___           |    |   motor    |
                _|_            ----| controller |
                ///          step  |____________|

Here, the resistor R and capacitor C form a low pass filter on the control input of the voltage controlled oscillator VCO. When the input level is at run, the VCO output oscillates at its maximum rate. When the input level is at stop, the VCO output ceases to oscillate. The RC time constant of the low pass filter determines the rate of acceleration applied to the motor.

With such a design, the time constant RC is usually determined empirically by setting up the system and then adjusting R and C until the system operates properly.

Practical Examples

The NE555 timer can be used as a voltage controlled oscillator, but I first saw this done with discrete components on a controller for a paper-tape reader designed around 1970.

Software Solutions

The basic control models outlined at the start of this section can be directly incorporated into the software for controlling a stepping motor, and this must be done if, for example, the motor is driving a load with a variable moment of intertia or driving a load against variable frictional loadings. Most open-loop stepping motor applications are not that complicated, however! So long as the inertia and frictional loadings are constant, the control software can be greatly simplified, replacing complex model computations with a table of precomputed delays.

Consider the problem of accelerating the motor from a standing start. No matter where the motor starts, so long as the torque, moment of inertia and frictional loadings remain the same, the time sequence of steps will be the same. Therefore, we need only pre-compute this time sequence of steps and save it in an array. We can use this array as follows to accelerate the motor:

array AV, the acceleration vector, holds time intervals
i is the index into AV

i = 0
repeat the following cycle to accelerate forever:

wait AV[i] seconds and then
step( 1 )
i = i + 1
We may use i, the counter in the above code, as a stand-in for the motor velocity, since stepping the motor every AV[i] seconds will move the motor at a speed of S/AV[i].

It is a straightforward exercise in elementary physics to compute the entries in the array A. If the motor is accelerating at Atarget,

Thetai = 1/2 Atarget ti2
where
Thetai -- the shaft angle at each successive step
Solving for time as a function of position, we get:
ti = (2Thetai / Atarget) 0.5
If we define
Theta0 = 0
so that
Thetai = Si
and
t0 = 0
we can conclude that
ti = k i0.5
where
k = (2S/Atarget)0.5
The acceleration vector entries are then:
A[0] = (2S/Atarget)0.5
and
A[i] = (i0.5 - (i - 1)0.5)A[0]
The following table gives the ratios of the first 20 entries in A[i] to A[0]:
0 1.000 10 0.154
1 0.414 11 0.147
2 0.318 12 0.141
3 0.268 13 0.136
4 0.236 14 0.131
5 0.213 15 0.127
6 0.196 16 0.123
7 0.183 17 0.120
8 0.172 18 0.116
9 0.162 19 0.113

In general, we aren't interested in indefinite accelearation, but rather, we are interested in accelerating until some speed or position restriction is satisfied, and then the control system should change, for example, from acceleration to deceleration or constant speed operation. So long as friction can be ignored, so the same rates can be used for acceleration and deceleration, we can make a clean move to a target position as follows:

array AV is the acceleration vector
i is the index into AV

i = 0
D = Thetatarget - Theta
while D nonzero do the following
if D > 0 -- spin one way
step( 1 )
D = D - 1
else -- spin the other way
step( -1 )
D = D + 1
endif
wait AV[i] seconds and then
if (i < |D|) and (S/AV[i] < Vtarget) -- accelerate
i = i + 1
else if i > |D| -- decelerate
i = i - 1
endif
endloop
Given an appropriate acceleration vector, the above code will cleanly accelerate a motor up to a speed near the target velocity, hold that speed, and then decelerate cleanly to a stop at the target position.

The above code does not take advantage of the higher rates of deceleration allowed when there is friction. In general, this should not cause any problems, but if the fastest possible moves are desired, a separate deceleration table should be maintained. Here is one idea:

array AV holds acceleration intervals
array C holds coasting intervals
array T holds transition information
array D holds deceleration intervals

i = 0
repeat the following until the desired speed is reached

wait A[i] seconds and then
step( 1 )
i = i + 1

repeat the following to maintain the speed

wait C[i] seconds and then
step( 1 )

repeat the following to maintain the speed

i = i - T[i]
repeat the following until i = 0
i = i - 1
step( 1 )
In the above, the arrays A and D are constructed identically, except that one has intervals used for acceleration, at a rate limited by friction, while the other has intervals used for deceleration, at a rate assisted by friction. Note that, after accelerating for i steps from a standing start, the motor will reach a velocity from which it can decelerate to a halt in i-T[i] steps. This relationship determines the values pre-computed in the array T.

Simple Practical Examples

An Object Oriented Design

1