StepperSpline Arduino Sketch

This sketch smoothly controls four stepper motors, receiving control messages from an external source over a USB serial port. The path interpolator uses cubic Bezier splines.

The full code for the sketch spans several files; all files may be downloaded in a single archive file as StepperSpline.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 StepperSpline.ino.

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

Path Generator

The path generation is implemented by SplinePath objects. These are purely data operators, they do not directly interface to hardware.

Sources: SplinePath.h, SplinePath.cpp.

 1/// \file SplinePath.h
 2/// \brief Spline 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 __SPLINE_PATH_H_INCLUDED__
17#define __SPLINE_PATH_H_INCLUDED__
18
19#include <math.h>
20
21#define MAX_SPLINE_SEGMENTS 20
22
23// ================================================================
24class SplinePath {
25
26private:
27  float q;   	   ///< current model position in dimensionless units
28  float qd;   	   ///< current model velocity in units/sec
29  float origin;    ///< model position origin for offsetting knot values
30
31  float u;    	   ///< current spline position parameter, ranges over 0.0 to 1.0
32  float rate;      ///< spline path velocity, units are (1/sec)
33
34  float knots[3*MAX_SPLINE_SEGMENTS+1];  ///< current Bezier knot points in dimensionless units (e.g. step or encoder counts)
35  int pts;         ///< current number of valid knot points; always at least four
36
37  /// Internal method to recalculate model values at current path position.
38  void recalculate();
39
40public:
41
42  /// Main constructor.
43  SplinePath();
44
45  /// Set the spline 'tempo' in units of segments/minute.  The default is 60 or
46  /// one segment/second.
47  void setTempo(int spm) { rate = spm / 60.0; };
48
49  /// Set the spline segment duration in units of milliseconds per segment.
50  void setDuration(long msec_per_seg) { rate = 1000.0 / msec_per_seg; };
51
52  /// Path calculation polling function to be called as often as possible,
53  /// typically from the main event loop.  The interval argument is the duration
54  /// in microseconds since the last call.
55  void pollForInterval(unsigned long interval);
56
57  /// Set the absolute target position.   The units are dimensionless
58  /// 'steps'.  If using a microstepping driver, these may be less than a
59  /// physical motor step.
60  void setTarget(long position);
61
62  /// Add a signed offset to the target position.  The units are dimensionless
63  /// 'steps'.  If using a microstepping driver, these may be less than a
64  /// physical motor step.
65  void incrementTarget(long offset);
66
67  /// Reset the knot origin to the end of the current path.  Affects
68  /// interpretation of subsequent knots.
69  void setOrigin(void) { origin = knots[pts-1]; };
70
71  /// Append another knot to the spline buffer.  Each additional three knots
72  /// extends the previous spline by one segment.  Knots exceeding the buffer
73  /// length are silently dropped.
74  void addKnot(long position);
75
76  /// Return the current position in dimensionless units.
77  float currentPosition(void) { return q; }
78
79  /// Return the current velocity in units/second.
80  float currentVelocity(void) { return qd; }
81};
82
83#endif //__SPLINE_PATH_H_INCLUDED__
  1/// \file SplinePath.cpp
  2/// \brief Step and path generator for a single motor.
  3///
  4/// \copyright Written over 2014-2023 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 "SplinePath.h"
 16
 17//================================================================
 18SplinePath::SplinePath()
 19{
 20  q    = 0.0;
 21  qd   = 0.0;
 22  rate = 1.0;
 23  memset(knots, 0, sizeof(knots));
 24  origin = 0.0;
 25
 26  // invariant: always leave one segment in buffer
 27  pts  = 4;
 28  u    = 1.0;
 29}
 30
 31//================================================================
 32/// Path calculation polling function to be called as often as possible,
 33/// typically from the main event loop.  The interval argument is the duration
 34/// in microseconds since the last call.
 35void SplinePath::pollForInterval(unsigned long interval)
 36{
 37  // calculate the current number of spline segments
 38  int segs = (pts-1)/3;
 39
 40  // integrate the path position one time step
 41  float dt = 1e-6 * interval;
 42  u += rate*dt;
 43
 44  // Determine whether to roll over to the next segment or not.  This will
 45  // always leave one segment remaining.
 46  if (segs > 1) {
 47    if (u >= 1.0) {
 48      // u has advanced to next segment, drop the first segment by dropping the first three knots
 49      pts -= 3;
 50      for (int i = 0; i < pts; i++) knots[i] = knots[i+3];
 51      u -= 1.0;
 52    }
 53  }
 54  // always limit u to the first active segment
 55  u = constrain(u, 0.0, 1.0);
 56
 57  // update q and qd
 58  this->recalculate();
 59}
 60
 61//================================================================
 62/// Apply the De Casteljau algorithm to calculate the position and velocity of
 63/// the spline at the current path point.
 64void SplinePath::recalculate()
 65{
 66  // unroll the De Casteljau iteration and save intermediate points
 67  float beta[3];
 68  for (int k = 0; k < 3; k++)  beta[k] = knots[k] * (1 - u) + knots[k+1] * u;
 69  for (int k = 0; k < 2; k++)  beta[k] =  beta[k] * (1 - u) +  beta[k+1] * u;
 70  qd = 3 * (beta[1] - beta[0]);          // s'(u)
 71  q  = beta[0] * (1 - u) + beta[1] * u;   // s(u)
 72}
 73
 74//================================================================
 75/// Set the absolute target position in dimensionless units.
 76void SplinePath::setTarget(long position)
 77{
 78  // reset the spline knots to move to the target
 79  knots[0] = q;  // start at the current position and velocity
 80  knots[1] = knots[0] + (qd * (1.0/3.0));
 81
 82  // set the endpoint to the target position
 83  knots[3] = (float) position;
 84
 85  // set a zero velocity boundary condition
 86  knots[2] = knots[3];
 87
 88  // reset the origin for safety
 89  origin = knots[3];
 90
 91  // reset the path position to start the new segment
 92  u = 0.0;
 93
 94  // reset the spline length to one segment
 95  pts = 4;
 96
 97  // recalculate current values
 98  this->recalculate();
 99}
100
101//================================================================
102/// Add a signed offset to the target position.  The units are dimensionless
103/// 'steps'.  If using a microstepping driver, these may be less than a
104/// physical motor step.
105void SplinePath::incrementTarget(long offset)
106{
107  // reset the spline knots to move to the relative target
108  knots[0] = q;  // start at the current position and velocity
109  knots[1] = knots[0] + (qd * (1.0/3.0));
110
111  // set the endpoint to the target position
112  knots[3] += (float) offset;
113
114  // set a zero velocity boundary condition
115  knots[2] = knots[3];
116
117  // reset the origin for safety
118  origin = knots[3];
119
120  // reset the spline length to one segment
121  pts = 4;
122
123  // reset the path position to start the new segment
124  u = 0.0;
125
126  // recalculate current values
127  this->recalculate();
128}
129
130//================================================================
131/// Append another knot to the spline buffer.  Each additional three knots
132/// extends the previous spline by one segment.  Knots exceeding the buffer
133/// length are silently dropped.
134void SplinePath::addKnot(long position)
135{
136  if (pts < (3*MAX_SPLINE_SEGMENTS+1)) {
137    knots[pts] = (float) position + origin;
138    pts++;
139  }
140}
141//================================================================

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 value) { target = value; }
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
79      // limit the maximum speed to a step on every interrupt
80      if (step_interval == 0) step_interval = 1;
81    }
82  }
83
84};
85
86#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
49      // finish the step pulse
50      digitalWrite(step_pin, LOW);
51    }
52  }
53}
54//================================================================