7.12. StepperSweep Arduino Sketch

This sketch is used by Exercise: A4988 Stepper Motor Driver.

7.12.1. Full Source Code

The full code is all in one file StepperSweep.ino.

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
// StepperSweep - move a stepper motor at different rates
//
// Copyright (c) 2016, Garth Zeglin.  All rights reserved. Licensed under the
// terms of the BSD 3-clause license as included in LICENSE.
//
// This program assumes that:
//
//  1. A A4988 stepper motor driver is connected to pins 2 and 3.
//  2. A control potentiometer can vary the voltage on A0.
//  3. The serial console on the Arduino IDE is set to 9600 baud communications speed.

// ================================================================================
// Define constant values and global variables.

// Define the pin numbers on which the outputs are generated.
#define DIR_PIN 2     // The direction pin controls the direction of stepper motor rotation.
#define STEP_PIN 3    // Each pulse on the STEP pin moves the stepper motor one angular unit.
#define ENABLE_PIN 4  // Optional control of the driver power.

// Alternate definitions for the Protoneer CNC Shield board X axis.
// #define DIR_PIN 5
// #define STEP_PIN 2
// #define ENABLE_PIN 8

// ================================================================================
// Configure the hardware once after booting up.  This runs once after pressing
// reset or powering up the board.
void setup(void)
{
  // Initialize the stepper driver control pins to output drive mode.
  pinMode(DIR_PIN, OUTPUT); 
  pinMode(STEP_PIN, OUTPUT);
  pinMode(ENABLE_PIN, OUTPUT);

  // Drive the /ENABLE pin low to keep the motor always energized.
  digitalWrite(ENABLE_PIN, LOW);
  
  // Initialize the serial UART at 9600 bits per second.
  Serial.begin(9600);
} 
/****************************************************************/
/// Rotate the stepper motor a specified distance at constant speed.  It does
/// not return until the motion is complete, e.g. it 'blocks' for the duration.
///
/// \param steps angular distance to move; the sign determines the direction,
///		 but the precise angle depends upon the driver microstepping
///		 configuration and type of motor.
///
/// \param speed speed in steps/second

void rotate_stepper(int steps, float speed)
{
  // Configure the direction pin on the stepper motor driver based on the sign
  // of the displacement.
  int dir = (steps > 0)? HIGH:LOW;
  digitalWrite(DIR_PIN, dir); 

  // Find the positive number of steps pulses to emit.
  int pulses = abs(steps);

  // Compute a delay time in microseconds controlling the duration of each half
  // of the step cycle.
  //  microseconds/half-step = (1000000 microseconds/second) * (1 step/2 half-steps) / (steps/second)
  unsigned long wait_time = 500000/speed;

  // The delayMicroseconds() function cannot wait more than 16.383ms, so the
  // total delay is separated into millisecond and microsecond components.  This
  // increases the range of speeds this function can handle.
  unsigned int msec = wait_time / 1000;
  unsigned int usec = wait_time - (1000*msec);

  // Print a status message to the console.
  Serial.print("Beginning rotation of ");
  Serial.print(steps);
  Serial.print(" steps with delay interval of ");
  Serial.print(msec);
  Serial.print(" milliseconds, ");
  Serial.print(usec);
  Serial.print(" microseconds.\n");
  
  // Loop for the given number of step cycles.  The driver will change outputs
  // on the rising edge of the step signal so short pulses would work fine, but
  // this produces a square wave for easier visualization on a scope.
  for(int i = 0; i < pulses; i++) {
    digitalWrite(STEP_PIN, HIGH);
    if (msec > 0) delay(msec);
    if (usec > 0) delayMicroseconds(usec);

    digitalWrite(STEP_PIN, LOW); 
    if (msec > 0) delay(msec);
    if (usec > 0) delayMicroseconds(usec);
  }
}
// ================================================================================
// Run one iteration of the main event loop.  The Arduino system will call this
// function over and over forever.
void loop(void)
{
  // Begin the motion sequence with a few back-and-forth movements at faster and faster speeds.
  rotate_stepper(  10,   10.0);
  rotate_stepper( -10,   10.0);
  rotate_stepper(  20,   20.0);
  rotate_stepper( -20,   20.0);
  rotate_stepper(  50,   50.0);
  rotate_stepper( -50,   50.0);
  rotate_stepper( 100,  100.0);
  rotate_stepper(-100,  100.0);
  rotate_stepper( 100,  200.0);
  rotate_stepper(-100,  200.0);
  rotate_stepper( 100,  400.0);
  rotate_stepper(-100,  400.0);

  // Now demonstrate that the stepper can freely rotate.
  rotate_stepper(1000, 250.0);
  rotate_stepper(-1000, 250.0);

  // Now begin a simple back and forth motion with speed controlled by the analog input.
  while (1) {
    // Read the current value of the potentiometer input from analog input 0.
    int an0 = analogRead(0);

    // Map the input to a useful speed range.
    int speed = map(an0, 0, 1023, 100, 400);

    // Sweep back and forth one cycle.
    rotate_stepper( 100, speed);
    rotate_stepper(-100, speed);
  }
}

/****************************************************************/

Table Of Contents

Previous topic

7.11. WheelDrive Arduino Sketch

Next topic

7.13. EventLoopDemo Arduino Sketch