StepperWinch Arduino Sketch

This sketch smoothly controls four stepper motors, receiving control messages from an external source over a USB serial port. The protocol is event-driven with local filtering and motion smoothing, much like a MIDI instrument driven by note events.

The full code for the sketch spans several files; all files may be downloaded in a single archive file as StepperWinch.zip, browsed in raw form in the source folder, or browsed below.

Compiling the sketch requires installing the optional TimerOne library in the Arduino IDE for supporting timer interrupt processing.

Top-Level Functions

void setup(void)

Standard Arduino initialization function to configure the system.

void loop(void)

Standard Arduino polling function to handle all I/O and periodic processing. This loop should never be allowed to stall or block so that all tasks can be constantly serviced.

void path_poll(unsigned long interval)

Polling function called from the main event loop to update the path model and update the step generators.

void serial_input_poll(void)

Polling function to process messages arriving over the serial port. Each iteration through this polling function processes at most one character. It records the input message line into a buffer while simultaneously dividing it into ‘tokens’ delimited by whitespace. Each token is a string of non-whitespace characters, and might represent either a symbol or an integer. Once a message is complete, parse_input_message() is called.

void parse_input_message(int argc, char *argv[])

Process an input message. Unrecognized commands are silently ignored. The input is provided an array argv of argc pointers to strings, one per token.

Main

The main entry points and event loop are in file StepperWinch.ino.

  1/// \file StepperWinch.ino
  2/// \brief Driver for four-channel stepper-motor capstan winch system.
  3///
  4/// \copyright Written over 2014-2018 by Garth Zeglin <garthz@cmu.edu>.  To the
  5/// extent possible under law, the author has dedicated all copyright and
  6/// related and neighboring rights to this software to the public domain
  7/// worldwide.  This software is distributed without any warranty.  You should
  8/// have received a copy of the CC0 Public Domain Dedication along with this
  9/// software.  If not, see <http://creativecommons.org/publicdomain/zero/1.0/>.
 10///
 11/// \details This sketch is designed to support the expressive gestural motion
 12/// of a kinetic fabric sculpture rather than perform precision trajectory
 13/// tracking as would be typical for CNC applications.  The communicates over
 14/// the serial port to receive motion commands and report status.  The protocol
 15/// is event-driven and implements parameterized gestural motions; it is
 16/// patterned after MIDI or OSC conventions.  This sketch assumes the following:
 17///
 18/// 1. The TimerOne library is installed in the Arduino IDE.
 19/// 2. Four A4988 stepper motor drivers are connected following the CNC Shield pin conventions.
 20/// 3. If using a CNC Shield board, A-axis jumpers are installed to connect A-DIR to D13 (also SpinDir) and A-STEP to D12 (also SpinEnable)..
 21/// 4. The serial communication baud rate is 115200 bps.
 22///
 23/// Typically, for 200 step/rev (1.8 deg) stepper motors the drivers are
 24/// configured for 1/4 step microstepping (MS2 pulled high).  However, the
 25/// protocol commands use integer step units so the code does not depend on
 26/// this.
 27
 28// ================================================================
 29// Import the TimerOne library to support timer interrupt processing.
 30#include "TimerOne.h"
 31
 32// Include the other modules from this sketch.
 33#include "cnc_shield.h"
 34#include "Stepper.h"
 35#include "Path.h"
 36
 37// ================================================================
 38// Communication protocol.
 39
 40// The message protocol is based on plain-text commands sent as keywords and
 41// values in a line of text.  One line is one message.  All the input message
 42// formats begin with a string naming a specific command or destination followed
 43// by one or two arguments.  The output formats are similar but include more
 44// general debugging output with a variable number of tokens.
 45
 46// ----------------------------------------------------------------
 47// The following global messages are not channel-specific.
 48
 49// Command	Arguments		Meaning
 50// ping                                 query whether the server is running
 51// version				query the identity of the sketch
 52// srate        <value>                 set the status reporting interval in milliseconds
 53// enable       <value>                 enable or disable all driver outputs, value is 0 or non-zero
 54
 55// ----------------------------------------------------------------
 56// The following messages include a token representing the flag set specifying
 57// the affected axes.  The flag set should include one or more single-letter
 58// channel specifiers (regex form: "[xyza]+").  Note that the flag set cannot be
 59// empty.
 60
 61// --------------------------------
 62
 63// Absolute move. There should be an integer target value corresponding to each
 64// included channel; each controller target is set to the specified position.
 65// The motion is not coordinated; different channels may finish at different
 66// times.  Note that this command will enable all drivers.
 67
 68//   a <flags> <offset>+
 69//
 70// Examples:
 71//   a xyza 100 120 -200 -50	move the axes to the specified locations
 72//   a x 50			move the X axis to +50
 73
 74// --------------------------------
 75
 76// Relative move. There should be an offset value corresponding to each included
 77// channel; each controller target is incremented by the specified amount.  The
 78// motion is not coordinated; different channels may finish at different times.
 79// Note that this command will enable all drivers.
 80//
 81//   d <flags> <offset>+
 82//
 83// Examples:
 84//   d xyza 10 10 -10 -10	move all axes ten steps (two forward, two backward)
 85//   d x 50			move the X axis fifty steps forward
 86
 87// --------------------------------
 88
 89// Reference move. There should be an offset value corresponding to each
 90// included channel; each controller reference value is incremented by the
 91// specified amount, which has the effect of applying an impulse.  Note that
 92// this command will enable all drivers.
 93//
 94//   r <flags> <offset>+
 95//
 96// Examples:
 97//   r xyza 10 10 -10 -10	move all axes reference positions ten steps (two forward, two backward)
 98//   r x 50			move the X axis reference position fifty steps forward
 99
100// --------------------------------
101
102// Set velocity. There should be an integer velocity value corresponding to each
103// included channel; each controller target velocity is set to the amount
104// specified in units/sec.  Note that this command will enable all drivers.
105//
106//   v <flags> <value>+
107//
108// Examples:
109//   v xyza 10 10 -10 -10	set all axes to drift 10 steps per second (two forward, two backward)
110//   v x 500			set the X axis to constantly move forward at roughly half speed
111
112// --------------------------------
113// Set speed. There should be an integer speed value corresponding to each
114// included channel; each controller target speed is set to the amount
115// specified in units/sec.  Note that this command will enable all drivers.
116//
117//   s <flags> <value>+
118//
119// Examples:
120//   s xyza 10 10 10 10		set all axes to ramp at 10 steps per second toward the target
121//   s x 500			set the X axis to ramp at 500 steps/second
122
123// --------------------------------
124// Set second-order gains.  The same dynamic parameters are applied to all included channels.
125//   g <flags> <frequency (Hz)> <damping-ratio>
126//
127// Examples:
128//   g xyza 2.0 1.0		set all channels to 1 Hz natural frequency with critical damping
129//   g xyza 0.1 0.5		set all channels to 0.1 Hz natural frequency and underdamping
130
131// --------------------------------
132// Set velocity and acceleration limits.  The same dynamic parameters are applied to all included channels.
133//   l <flags> <maximum velocity (steps/sec)> <maximum acceleration (steps/sec/sec)>
134//
135// Examples:
136//   l xyza 4000 40000		set all channels to 4000 steps/sec and 40000 steps/sec/sec
137
138// ----------------------------------------------------------------
139// This program generates the following messages:
140
141// Command	Arguments		Meaning
142// awake                                initialization has completed or ping was received
143// txyza        <usec> <x> <y> <z> <a>  Arduino clock time in microseconds, followed by absolute step position
144// dbg		<value-or-token>+	debugging message to print for user
145// id		<tokens>+		tokens identifying the specific sketch
146
147// ================================================================
148// Global variables and constants.
149
150// The baud rate is the number of bits per second transmitted over the serial port.
151#define BAUD_RATE 115200
152
153// Interval in microseconds between status messages.
154static unsigned long status_poll_interval = 200000; // 5 Hz message rate to start
155
156/// Control objects for the stepper channels.  The declaration statically
157/// initializes the global state objects for the channels.  Note that this does
158/// not initialize the hardware; that is performed in setup().
159static Stepper x_axis(X_AXIS_STEP_PIN, X_AXIS_DIR_PIN);
160static Stepper y_axis(Y_AXIS_STEP_PIN, Y_AXIS_DIR_PIN);
161static Stepper z_axis(Z_AXIS_STEP_PIN, Z_AXIS_DIR_PIN);
162static Stepper a_axis(A_AXIS_STEP_PIN, A_AXIS_DIR_PIN);
163
164/// Path generator object for each channel.
165static Path x_path, y_path, z_path, a_path;
166
167/// The timestamp in microseconds for the last polling cycle, used to compute
168/// the exact interval between stepper motor updates.
169static unsigned long last_interrupt_clock = 0;
170
171/// Identification string.
172static const char version_string[] = "id StepperWinch " __DATE__;
173
174// ================================================================
175/// Enable or disable the stepper motor drivers.  The output is active-low,
176/// so this inverts the sense.
177static inline void set_driver_enable(int value)
178{
179  digitalWrite(STEPPER_ENABLE_PIN, (value != 0) ? LOW : HIGH);
180}
181
182// ================================================================
183/// Interrupt handler to update all the stepper motor channels.  Note that this
184/// is called from a timer interrupt context, so it should take as little time as
185/// feasible and cannot use serial I/O (i.e. no debugging messages).
186void stepper_output_interrupt(void)
187{
188  // read the clock
189  unsigned long now = micros();
190
191  // Compute the time elapsed since the last poll.  This will correctly handle wrapround of
192  // the 32-bit long time value given the properties of twos-complement arithmetic.
193  unsigned long interval = now - last_interrupt_clock;
194  last_interrupt_clock = now;
195
196  // Update all the stepper channels. This may emit step signals or simply
197  // update the timing and state variables.
198  x_axis.pollForInterval(interval);
199  y_axis.pollForInterval(interval);
200  z_axis.pollForInterval(interval);
201  a_axis.pollForInterval(interval);
202}
203
204// ================================================================
205/// Polling function called from the main event loop to update the path model
206/// and update the step generators.
207void path_poll(unsigned long interval)
208{
209  x_path.pollForInterval(interval);
210  y_path.pollForInterval(interval);
211  z_path.pollForInterval(interval);
212  a_path.pollForInterval(interval);
213
214  // update the step generator for new targets
215  x_axis.setTarget(x_path.currentPosition());
216  x_axis.setSpeed(abs(x_path.currentVelocity()));
217
218  y_axis.setTarget(y_path.currentPosition());
219  y_axis.setSpeed(abs(y_path.currentVelocity()));
220
221  z_axis.setTarget(z_path.currentPosition());
222  z_axis.setSpeed(abs(z_path.currentVelocity()));
223
224  a_axis.setTarget(a_path.currentPosition());
225  a_axis.setSpeed(abs(a_path.currentVelocity()));
226}
227// ================================================================
228/// Return a Path object or NULL for each flag in the flag token.  As a side effect, updates
229/// the source pointer, leaving it at the terminating null.
230static Path *path_flag_iterator(char **tokenptr)
231{
232  char flag = **tokenptr;
233  if (flag == 0) return NULL;
234  else {
235    (*tokenptr) += 1;
236    switch (flag) {
237    case 'x': return &x_path;
238    case 'y': return &y_path;
239    case 'z': return &z_path;
240    case 'a': return &a_path;
241    default: return NULL;
242    }
243  }
244}
245
246// ================================================================
247/// Process an input message.  Unrecognized commands are silently ignored.
248///
249/// @param argc		number of argument tokens
250/// @param argv		array of pointers to strings, one per token
251void parse_input_message(int argc, char *argv[])
252{
253  if (argc == 0) return;
254
255  // Interpret the first token as a command symbol.
256  char *command = argv[0];
257
258  if (string_equal(command, "enable")) {
259    if (argc > 1) set_driver_enable(atoi(argv[1]));
260
261  } else if (string_equal(command, "a")) {
262    if (argc > 2) {
263      set_driver_enable(1);
264      char *flags = argv[1];
265      int channel = 0;
266      while (*flags) {
267	Path *p = path_flag_iterator(&flags);
268	if (p) {
269	  if (argc > (channel+2)) {
270	    p->setTarget(atol(argv[channel+2]));
271	    channel++;
272	  }
273	}
274      }
275    }
276  } else if (string_equal(command, "d")) {
277    if (argc > 2) {
278      set_driver_enable(1);
279      char *flags = argv[1];
280      int channel = 0;
281      while (*flags) {
282	Path *p = path_flag_iterator(&flags);
283	if (p) {
284	  if (argc > (channel+2)) {
285	    p->incrementTarget(atol(argv[channel+2]));
286	    channel++;
287	  }
288	}
289      }
290    }
291  } else if (string_equal(command, "r")) {
292    if (argc > 2) {
293      set_driver_enable(1);
294      char *flags = argv[1];
295      int channel = 0;
296      while (*flags) {
297	Path *p = path_flag_iterator(&flags);
298	if (p) {
299	  if (argc > (channel+2)) {
300	    p->incrementReference(atol(argv[channel+2]));
301	    channel++;
302	  }
303	}
304      }
305    }
306  } else if (string_equal(command, "v")) {
307    if (argc > 2) {
308      set_driver_enable(1);
309      char *flags = argv[1];
310      int channel = 0;
311      while (*flags) {
312	Path *p = path_flag_iterator(&flags);
313	if (p) {
314	  if (argc > (channel+2)) {
315	    p->setVelocity(atol(argv[channel+2]));
316	    channel++;
317	  }
318	}
319      }
320    }
321  } else if (string_equal(command, "s")) {
322    if (argc > 2) {
323      set_driver_enable(1);
324      char *flags = argv[1];
325      int channel = 0;
326      while (*flags) {
327	Path *p = path_flag_iterator(&flags);
328	if (p) {
329	  if (argc > (channel+2)) {
330	    p->setSpeed(atol(argv[channel+2]));
331	    channel++;
332	  }
333	}
334      }
335    }
336  } else if (string_equal(command, "g")) {
337    if (argc > 3) {
338      char *flags = argv[1];
339      float frequency = atof(argv[2]);
340      float damping_ratio = atof(argv[3]);
341      while (*flags) {
342	Path *p = path_flag_iterator(&flags);
343	if (p) p->setFreqDamping(frequency, damping_ratio);
344      }
345    }
346  } else if (string_equal(command, "l")) {
347    if (argc > 3) {
348      char *flags = argv[1];
349      float qdmax = atof(argv[2]);
350      float qddmax = atof(argv[3]);
351      while (*flags) {
352	Path *p = path_flag_iterator(&flags);
353	if (p) p->setLimits(qdmax, qddmax);
354      }
355    }
356  } else if (string_equal(command, "version")) {
357    send_message(version_string);
358
359  } else if (string_equal(command, "ping")) {
360    send_message("awake");
361
362  } else if (string_equal(command, "srate")) {
363    if (argc > 1) {
364      long value = atol(argv[1]);
365      // set the reporting interval (milliseconds -> microseconds)
366      if (value > 0)  status_poll_interval = 1000*value;
367      else send_debug_message("invalid srate value");
368    }
369  }
370}
371
372/****************************************************************/
373/// Polling function to send status reports at periodic intervals.
374static void status_poll(unsigned long interval)
375{
376  static long timer = 0;
377  timer -= interval;
378
379  if (timer < 0) {
380    timer += status_poll_interval;
381
382    // send a time and position reading
383    long clock = micros();
384    long x = x_axis.currentPosition();
385    long y = y_axis.currentPosition();
386    long z = z_axis.currentPosition();
387    long a = a_axis.currentPosition();
388    send_message("txyza", clock, x, y, z, a);
389  }
390}
391
392/****************************************************************/
393/**** Standard entry points for Arduino system ******************/
394/****************************************************************/
395
396/// Standard Arduino initialization function to configure the system.
397void setup(void)
398{
399  // set up the CNC Shield I/O
400  digitalWrite(STEPPER_ENABLE_PIN, HIGH); // initialize drivers in disabled state
401  pinMode(STEPPER_ENABLE_PIN, OUTPUT);
402
403  pinMode(X_AXIS_STEP_PIN, OUTPUT);
404  pinMode(Y_AXIS_STEP_PIN, OUTPUT);
405  pinMode(Z_AXIS_STEP_PIN, OUTPUT);
406  pinMode(A_AXIS_STEP_PIN, OUTPUT);
407
408  pinMode(X_AXIS_DIR_PIN, OUTPUT);
409  pinMode(Y_AXIS_DIR_PIN, OUTPUT);
410  pinMode(Z_AXIS_DIR_PIN, OUTPUT);
411  pinMode(A_AXIS_DIR_PIN, OUTPUT);
412
413#ifdef LED_BUILTIN
414  pinMode(LED_BUILTIN, OUTPUT);
415#endif
416
417  // initialize the Serial port
418  Serial.begin(BAUD_RATE);
419
420  // set up the timer1 interrupt and attach it to the stepper motor controls
421  last_interrupt_clock = micros();
422  Timer1.initialize(100); // 100 microsecond intervals, e.g. 10kHz
423  Timer1.attachInterrupt(stepper_output_interrupt);
424
425  // send a wakeup message
426  send_message("awake");
427}
428
429/****************************************************************/
430/// Standard Arduino polling function to handle all I/O and periodic processing.
431/// This loop should never be allowed to stall or block so that all tasks can be
432/// constantly serviced.
433void loop(void)
434{
435  static unsigned long last_event_loop = 0;
436
437  // read the clock
438  unsigned long now = micros();
439
440  // Compute the time elapsed since the last polling cycle.  This will correctly handle wrapround of
441  // the 32-bit long time value given the properties of twos-complement arithmetic.
442  unsigned long interval = now - last_event_loop;
443  last_event_loop = now;
444
445  serial_input_poll();
446  status_poll(interval);
447  path_poll(interval);
448
449  // other polled tasks can go here
450}
451
452/****************************************************************/
453/****************************************************************/

Path Generator

The input filtering and path generation are implemented by Path objects. These are purely data operators, they do not directly interface to hardware.

Sources: Path.h, Path.cpp.

 1/// \file Path.h
 2/// \brief Path generator for a single motor.
 3///
 4/// \copyright Written 2018 by Garth Zeglin <garthz@cmu.edu>.  To the extent
 5/// possible under law, the author has dedicated all copyright and related and
 6/// neighboring rights to this software to the public domain worldwide.  This
 7/// software is distributed without any warranty.  You should have received a
 8/// copy of the CC0 Public Domain Dedication along with this software.  If not,
 9/// see <http://creativecommons.org/publicdomain/zero/1.0/>.
10///
11/// \details This class implements several smooth path generators intended for
12/// generating gestural motions on a single motor channel.  It assumes a
13/// separate controller manages the step generator of closed-loop control of the
14/// physical hardware.
15
16#ifndef __PATH_H_INCLUDED__
17#define __PATH_H_INCLUDED__
18
19#include <math.h>
20
21// ================================================================
22class Path {
23
24private:
25  float q;    	   ///< current model position, in dimensionless units (e.g. step or encoder counts)
26  float qd;   	   ///< current model velocity in units/sec
27  float qdd;  	   ///< current model acceleration, in units/sec/sec
28  float q_d;  	   ///< current model reference position in dimensionless units
29  float qd_d;  	   ///< current model reference velocity in dimensionless units/sec
30
31  float q_d_d; 	   ///< user-specified target position in dimensionless units
32  float speed;     ///< user-specified target speed in dimensionless units/sec
33
34  float t;    	   ///< elapsed model time, in seconds
35  float k;    	   ///< proportional feedback gain, in (units/sec/sec)/(units), which is (1/sec^2)
36  float b;    	   ///< derivative feedback gain, in (units/sec/sec)/(units/sec), which is (1/sec)
37  float qd_max;    ///< maximum allowable speed in units/sec
38  float qdd_max;   ///< maximum allowable acceleration in units/sec/sec
39
40public:
41
42  /// Main constructor.
43  Path();
44
45  /// Path-integration polling function to be called as often as possible,
46  /// typically from the main event loop.  The interval argument is the duration
47  /// in microseconds since the last call.
48  void pollForInterval(unsigned long interval);
49
50  /// Add a signed offset to the target position.  The units are dimensionless
51  /// 'steps'.  If using a microstepping driver, these may be less than a
52  /// physical motor step.
53  void incrementTarget(long offset) { q_d_d += offset; }
54
55  /// Add a signed offset to the reference position.  This can have  the
56  /// effect of applying a triangular impulse; the reference trajectory will
57  /// make a step, then ramp back to the target position.
58  void incrementReference(long offset) { q_d += offset; }
59
60  /// Set the absolute target position in dimensionless units.
61  void setTarget(long position) { q_d_d = position; }
62
63  /// Set the ramp speed in dimensionless units/second.  If less than or equal to zero,
64  /// it is treated as unlimited, and the
65  /// reference position will move in steps instead of ramps.
66  void setSpeed(long newspeed) { speed = (newspeed <= 0) ? INFINITY : newspeed; }
67
68  /// Set the ramp velocity in dimensionless units/second, either positive or negative.
69  /// The ramp target position is set to reflect the sign of the change.
70  void setVelocity(long newspeed) {
71    speed = abs(newspeed);
72    if (newspeed >= 0)  q_d_d = INFINITY;
73    else                q_d_d = -INFINITY;
74  }
75
76  /// Return the current position in dimensionless units.
77  long currentPosition(void) { return (long) q; }
78
79  /// Return the current velocity in units/second.
80  long currentVelocity(void) { return (long) qd; }
81
82  /// Configure the second-order model gains.
83  void setPDgains(float k_new, float b_new) { k = k_new; b = b_new; }
84
85  /// Convenience function to set second order model gains in terms of natural frequency and damping ratio.
86  /// The frequency is in Hz, the damping ratio is 1.0 at critical damping.
87  void setFreqDamping(float freq, float damping) {
88    // freq = (1/2*pi) * sqrt(k/m); k = (freq*2*pi)^2      
89    k = freq * freq * 4 * M_PI * M_PI;
90    b = 2 * sqrtf(k) * damping;
91  }
92
93  /// Configure the velocity and acceleration limits.
94  void setLimits(float qdmax, float qddmax) { qd_max = qdmax; qdd_max = qddmax; }
95};
96
97#endif //__PATH_H_INCLUDED__
 1/// \file Path.cpp
 2/// \brief Step and path generator for a single path motor
 3///
 4/// \copyright Written over 2014-2018 by Garth Zeglin <garthz@cmu.edu>.  To the
 5/// extent possible under law, the author has dedicated all copyright and
 6/// related and neighboring rights to this software to the public domain
 7/// worldwide.  This software is distributed without any warranty.  You should
 8/// have received a copy of the CC0 Public Domain Dedication along with this
 9/// software.  If not, see <http://creativecommons.org/publicdomain/zero/1.0/>.
10
11#include <Arduino.h>
12#include <math.h>
13#include <stdint.h>
14
15#include "Path.h"
16
17//================================================================
18Path::Path()
19{
20  q    = 0.0;
21  qd   = 0.0;
22  qdd  = 0.0;
23  q_d  = 0.0;
24  qd_d = 0.0;
25
26  q_d_d = 0.0;
27  speed = INFINITY;
28
29  t = 0;
30  
31  // Initialize the second-order model response to 2 Hz natural frequency, with
32  // a damping ratio of 1.0 for critical damping.
33  setFreqDamping(2.0, 1.0);
34  
35  qd_max  = 2400.0;     // typical physical limit for 4x microstepping
36  qdd_max = 24000.0;
37}
38
39//================================================================
40// Path integration running from main event loop.
41void Path::pollForInterval(unsigned long interval)
42{
43  float dt = 1e-6 * interval;
44
45  // calculate the derivatives
46  float qdd = k * (q_d - q) + b * (qd_d - qd);
47
48  // clamp the acceleration within range for safety
49  qdd = constrain(qdd, -qdd_max, qdd_max);
50
51  // integrate one time step
52  q  += qd  * dt;
53  qd += qdd * dt;
54  t += dt;
55
56  // clamp the model velocity within range for safety
57  qd = constrain(qd, -qd_max, qd_max);
58
59  // Update the reference trajectory using linear interpolation.  This can
60  // create steps or ramps.  This calculates the maximum desired step, bounds it
61  // to the speed, then applies the sign to move in the correct direction.
62  float q_d_err = q_d_d - q_d;  // maximum error step
63
64  if (q_d_err == 0.0) {
65    qd_d = 0.0;  // make sure reference velocity is zero, leave reference position unchanged
66
67  } else {
68    if (isinf(speed)) {
69      q_d = q_d_d;      // infinite speed, always adjust reference in one step
70      qd_d = 0.0;       // then assume zero velocity
71    } else {            // else calculate a ramp step
72      float d_q_d_max = speed * dt; // maximum linear step, possibly infinite
73      if (q_d_err > 0.0) {
74	float d_q_d = min(d_q_d_max, q_d_err); // reference position step
75	q_d += d_q_d;
76	qd_d = speed; // reference velocity
77      } else {
78	float d_q_d = min(d_q_d_max, -q_d_err); // absolute value of reference position step
79	q_d -= d_q_d;
80	qd_d = -speed; // reference velocity
81      }
82    }
83  }
84}
85//================================================================

Step Generator

The hardware drivers are operated by the step generator running on a fast timer interrupt. The step targets are updated from the path generator outputs in the main event loop.

Sources: Stepper.h, Stepper.cpp.

 1/// \file Stepper.h
 2/// \brief Step generator for a single stepper motor.
 3///
 4/// \copyright Written over 2014-2018 by Garth Zeglin <garthz@cmu.edu>.  To the
 5/// extent possible under law, the author has dedicated all copyright and
 6/// related and neighboring rights to this software to the public domain
 7/// worldwide.  This software is distributed without any warranty.  You should
 8/// have received a copy of the CC0 Public Domain Dedication along with this
 9/// software.  If not, see <http://creativecommons.org/publicdomain/zero/1.0/>.
10///
11/// \details This class implements fast constant-velocity stepping.  It is
12/// possible to use this directly, but the overall sketch pairs this with a
13/// interpolating path generator which frequently updates the position and
14/// velocity setpoints.
15
16#ifndef __STEPPER_H_INCLUDED__
17#define __STEPPER_H_INCLUDED__
18
19#include <stdint.h>
20
21/// An instance of this class manages generation of step and direction signals
22/// for one stepper motor.
23class Stepper {
24
25private:
26  /****************************************************************/
27  // The following instance variables may only be modified from a non-interrupt
28  // context, i.e., not within poll().
29
30  /// the I/O pins for this channel designated using the Arduino convention
31  uint8_t step_pin, dir_pin;
32
33  /// the target position in dimensionless step counts
34  long target;
35
36  /// the interval in microseconds between steps
37  unsigned long step_interval;
38
39  /****************************************************************/
40  // The following instance variables may be modified within poll() from an interrupt context.
41
42  /// the current position in dimensionless step counts
43  long position;
44
45  /// the time elapsed in microseconds since the last step occurred
46  unsigned long elapsed;
47
48  /****************************************************************/
49public:
50
51  /// Main constructor.  The arguments are the pin numbers for the step and
52  /// direction outputs. Note: this does not initialize the underlying hardware.
53  Stepper(uint8_t step_pin, uint8_t dir_pin);
54
55  /// Step-generator polling function to be called as often as possible.  This
56  /// is typically called from a timer interrupt.  The interval argument is the
57  /// duration in microseconds since the last call.
58  void pollForInterval(unsigned long interval);
59
60  /// Add a signed offset to the target position.  The units are dimensionless
61  /// 'steps'.  If using a microstepping driver, these may be less than a
62  /// physical motor step.
63  void incrementTarget(long offset) { target += offset; }
64
65  /// Set the absolute target position.
66  void setTarget(long position) { target = position; }
67
68  /// Return the current position in dimensionless 'steps'.
69  long currentPosition(void) { return position; }
70
71  /// Set a constant speed in steps/second.  Note that the value must be
72  /// non-zero and positive.  The maximum rate available is a function of the
73  /// polling rate.
74  void setSpeed(int speed) {
75    // (1000000 microseconds/second) / (steps/second) = (microseconds/step)
76    if (speed > 0) {
77      step_interval = 1000000 / speed;
78      if (step_interval == 0) step_interval = 1;
79    }
80  }
81
82};
83
84#endif //__STEPPER_H_INCLUDED__
 1/// \file Stepper.cpp
 2/// \brief Step and path generator for a single stepper motor
 3///
 4/// \copyright Written over 2014-2018 by Garth Zeglin <garthz@cmu.edu>.  To the
 5/// extent possible under law, the author has dedicated all copyright and
 6/// related and neighboring rights to this software to the public domain
 7/// worldwide.  This software is distributed without any warranty.  You should
 8/// have received a copy of the CC0 Public Domain Dedication along with this
 9/// software.  If not, see <http://creativecommons.org/publicdomain/zero/1.0/>.
10
11#include "Stepper.h"
12#include <Arduino.h>
13
14Stepper::Stepper(uint8_t _step_pin, uint8_t _dir_pin)
15{
16  step_pin = _step_pin;
17  dir_pin  = _dir_pin;
18  position = 0;
19  target   = 0;
20  elapsed  = 0;
21
22  step_interval = 200;  // 200 microseconds = 5000 steps/sec
23}
24//================================================================
25// Step generator running on fast timer interrupt.
26void Stepper::pollForInterval(unsigned long interval)
27{
28  // Accumulated the time elapsed since the step.
29  elapsed += interval;
30
31  if (elapsed >= step_interval) {
32    // reset the timer according to the target interval to produce a correct an
33    // average rate even if extra time has passed
34    elapsed -= step_interval;
35
36    // check whether to emit a step
37    if (position != target) {
38
39      // always set the direction to match the sign of motion
40      digitalWrite(dir_pin, (position < target) ? HIGH : LOW);
41
42      // emit a step
43      digitalWrite(step_pin, HIGH);
44
45      // update the position count
46      if (position < target) position++;
47      else position--;
48      digitalWrite(step_pin, LOW);
49    }
50  }
51}
52//================================================================