├── .gitignore ├── LICENSE ├── README.md ├── examples ├── AFMotor_ConstantSpeed │ └── AFMotor_ConstantSpeed.pde ├── AFMotor_MultiStepper │ └── AFMotor_MultiStepper.pde ├── Blocking │ └── Blocking.pde ├── Bounce │ └── Bounce.pde ├── ConstantSpeed │ └── ConstantSpeed.pde ├── DualMotorShield │ └── DualMotorShield.pde ├── MotorShield │ └── MotorShield.pde ├── MultiStepper │ └── MultiStepper.pde ├── MultipleSteppers │ └── MultipleSteppers.pde ├── Overshoot │ └── Overshoot.pde ├── ProportionalControl │ └── ProportionalControl.pde ├── Quickstop │ └── Quickstop.pde └── Random │ └── Random.pde ├── extras └── doc │ ├── AccelStepper_8h-source.html │ ├── annotated.html │ ├── classAccelStepper-members.html │ ├── classAccelStepper.html │ ├── doxygen.css │ ├── doxygen.png │ ├── files.html │ ├── functions.html │ ├── functions_func.html │ ├── index.html │ ├── tab_b.gif │ ├── tab_l.gif │ ├── tab_r.gif │ └── tabs.css ├── keywords.txt ├── library.properties └── src ├── AccelStepper.cpp ├── AccelStepper.h ├── MultiStepper.cpp └── MultiStepper.h /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | *.obj 6 | 7 | # Precompiled Headers 8 | *.gch 9 | *.pch 10 | 11 | # Compiled Dynamic libraries 12 | *.so 13 | *.dylib 14 | *.dll 15 | 16 | # Fortran module files 17 | *.mod 18 | *.smod 19 | 20 | # Compiled Static libraries 21 | *.lai 22 | *.la 23 | *.a 24 | *.lib 25 | 26 | # Executables 27 | *.exe 28 | *.out 29 | *.app 30 | 31 | \.DS_Store 32 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | This software is Copyright (C) Mike McCauley. Use is subject to license 2 | conditions. The main licensing options available are GPL V3 or Commercial: 3 | 4 | Open Source Licensing GPL V3 5 | 6 | This is the appropriate option if you want to share the source code of your 7 | application with everyone you distribute it to, and you also want to give them 8 | the right to share who uses it. If you wish to use this software under Open 9 | Source Licensing, you must contribute all your source code to the open source 10 | community in accordance with the GPL Version 3 when your application is 11 | distributed. See http://www.gnu.org/copyleft/gpl.html 12 | 13 | Commercial Licensing 14 | 15 | This is the appropriate option if you are creating proprietary applications 16 | and you are not prepared to distribute and share the source code of your 17 | application. Contact info@airspayce for details. 18 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | This fork follows the [upstream version](http://www.airspayce.com/mikem/arduino/AccelStepper/). Files are slightly reorganized to follow Arduino library conventions to allow for inclusion into the Arduino IDE library manager. 2 | 3 | Please direct questions and discussion to http://groups.google.com/group/accelstepper 4 | 5 | --- 6 | 7 | This is the Arduino AccelStepper library. It provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers. 8 | 9 | The standard Arduino IDE includes the Stepper library (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is perfectly adequate for simple, single motor applications. 10 | 11 | AccelStepper significantly improves on the standard Arduino Stepper library in several ways: 12 | 13 | - Supports acceleration and deceleration 14 | - Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper 15 | - API functions never delay() or block 16 | - Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers. 17 | - Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library) 18 | - Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip) 19 | - Very slow speeds are supported 20 | - Extensive API 21 | - Subclass support 22 | 23 | -------------------------------------------------------------------------------- /examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde: -------------------------------------------------------------------------------- 1 | // AFMotor_ConstantSpeed.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to run AccelStepper in the simplest, 5 | // fixed speed mode with no accelerations 6 | // Requires the AFMotor library 7 | // (https://github.com/adafruit/Adafruit-Motor-Shield-library) 8 | // Caution, does not work with Adafruit Motor Shield V2 9 | // See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library 10 | // for examples that work with Adafruit Motor Shield V2. 11 | 12 | #include 13 | #include 14 | 15 | AF_Stepper motor1(200, 1); 16 | 17 | 18 | // you can change these to DOUBLE or INTERLEAVE or MICROSTEP! 19 | void forwardstep() { 20 | motor1.onestep(FORWARD, SINGLE); 21 | } 22 | void backwardstep() { 23 | motor1.onestep(BACKWARD, SINGLE); 24 | } 25 | 26 | AccelStepper stepper(forwardstep, backwardstep); // use functions to step 27 | 28 | void setup() 29 | { 30 | Serial.begin(9600); // set up Serial library at 9600 bps 31 | Serial.println("Stepper test!"); 32 | 33 | stepper.setMaxSpeed(50); 34 | stepper.setSpeed(50); 35 | } 36 | 37 | void loop() 38 | { 39 | stepper.runSpeed(); 40 | } 41 | -------------------------------------------------------------------------------- /examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde: -------------------------------------------------------------------------------- 1 | // AFMotor_MultiStepper.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Control both Stepper motors at the same time with different speeds 5 | // and accelerations. 6 | // Requires the AFMotor library (https://github.com/adafruit/Adafruit-Motor-Shield-library) 7 | // Caution, does not work with Adafruit Motor Shield V2 8 | // See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library 9 | // for examples that work with Adafruit Motor Shield V2. 10 | 11 | #include 12 | #include 13 | 14 | // two stepper motors one on each port 15 | AF_Stepper motor1(200, 1); 16 | AF_Stepper motor2(200, 2); 17 | 18 | // you can change these to DOUBLE or INTERLEAVE or MICROSTEP! 19 | // wrappers for the first motor! 20 | void forwardstep1() { 21 | motor1.onestep(FORWARD, SINGLE); 22 | } 23 | void backwardstep1() { 24 | motor1.onestep(BACKWARD, SINGLE); 25 | } 26 | // wrappers for the second motor! 27 | void forwardstep2() { 28 | motor2.onestep(FORWARD, SINGLE); 29 | } 30 | void backwardstep2() { 31 | motor2.onestep(BACKWARD, SINGLE); 32 | } 33 | 34 | // Motor shield has two motor ports, now we'll wrap them in an AccelStepper object 35 | AccelStepper stepper1(forwardstep1, backwardstep1); 36 | AccelStepper stepper2(forwardstep2, backwardstep2); 37 | 38 | void setup() 39 | { 40 | stepper1.setMaxSpeed(200.0); 41 | stepper1.setAcceleration(100.0); 42 | stepper1.moveTo(24); 43 | 44 | stepper2.setMaxSpeed(300.0); 45 | stepper2.setAcceleration(100.0); 46 | stepper2.moveTo(1000000); 47 | 48 | } 49 | 50 | void loop() 51 | { 52 | // Change direction at the limits 53 | if (stepper1.distanceToGo() == 0) 54 | stepper1.moveTo(-stepper1.currentPosition()); 55 | stepper1.run(); 56 | stepper2.run(); 57 | } 58 | -------------------------------------------------------------------------------- /examples/Blocking/Blocking.pde: -------------------------------------------------------------------------------- 1 | // Blocking.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to use the blocking call runToNewPosition 5 | // Which sets a new target position and then waits until the stepper has 6 | // achieved it. 7 | // 8 | // Copyright (C) 2009 Mike McCauley 9 | // $Id: Blocking.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 10 | 11 | #include 12 | 13 | // Define a stepper and the pins it will use 14 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 15 | 16 | void setup() 17 | { 18 | stepper.setMaxSpeed(200.0); 19 | stepper.setAcceleration(100.0); 20 | } 21 | 22 | void loop() 23 | { 24 | stepper.runToNewPosition(0); 25 | stepper.runToNewPosition(500); 26 | stepper.runToNewPosition(100); 27 | stepper.runToNewPosition(120); 28 | } 29 | -------------------------------------------------------------------------------- /examples/Bounce/Bounce.pde: -------------------------------------------------------------------------------- 1 | // Bounce.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Make a single stepper bounce from one limit to another 5 | // 6 | // Copyright (C) 2012 Mike McCauley 7 | // $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 8 | 9 | #include 10 | 11 | // Define a stepper and the pins it will use 12 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 13 | 14 | void setup() 15 | { 16 | // Change these to suit your stepper if you want 17 | stepper.setMaxSpeed(100); 18 | stepper.setAcceleration(20); 19 | stepper.moveTo(500); 20 | } 21 | 22 | void loop() 23 | { 24 | // If at the end of travel go to the other end 25 | if (stepper.distanceToGo() == 0) 26 | stepper.moveTo(-stepper.currentPosition()); 27 | 28 | stepper.run(); 29 | } 30 | -------------------------------------------------------------------------------- /examples/ConstantSpeed/ConstantSpeed.pde: -------------------------------------------------------------------------------- 1 | // ConstantSpeed.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to run AccelStepper in the simplest, 5 | // fixed speed mode with no accelerations 6 | /// \author Mike McCauley (mikem@airspayce.com) 7 | // Copyright (C) 2009 Mike McCauley 8 | // $Id: ConstantSpeed.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 9 | 10 | #include 11 | 12 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 13 | 14 | void setup() 15 | { 16 | stepper.setMaxSpeed(1000); 17 | stepper.setSpeed(50); 18 | } 19 | 20 | void loop() 21 | { 22 | stepper.runSpeed(); 23 | } 24 | -------------------------------------------------------------------------------- /examples/DualMotorShield/DualMotorShield.pde: -------------------------------------------------------------------------------- 1 | // DualMotorShield.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to run 2 simultaneous steppers 5 | // using the Itead Studio Arduino Dual Stepper Motor Driver Shield 6 | // model IM120417015 7 | // This shield is capable of driving 2 steppers at 8 | // currents of up to 750mA 9 | // and voltages up to 30V 10 | // Runs both steppers forwards and backwards, accelerating and decelerating 11 | // at the limits. 12 | // 13 | // Copyright (C) 2014 Mike McCauley 14 | // $Id: $ 15 | 16 | #include 17 | 18 | // The X Stepper pins 19 | #define STEPPER1_DIR_PIN 3 20 | #define STEPPER1_STEP_PIN 2 21 | // The Y stepper pins 22 | #define STEPPER2_DIR_PIN 7 23 | #define STEPPER2_STEP_PIN 6 24 | 25 | // Define some steppers and the pins the will use 26 | AccelStepper stepper1(AccelStepper::DRIVER, STEPPER1_STEP_PIN, STEPPER1_DIR_PIN); 27 | AccelStepper stepper2(AccelStepper::DRIVER, STEPPER2_STEP_PIN, STEPPER2_DIR_PIN); 28 | 29 | void setup() 30 | { 31 | stepper1.setMaxSpeed(200.0); 32 | stepper1.setAcceleration(200.0); 33 | stepper1.moveTo(100); 34 | 35 | stepper2.setMaxSpeed(100.0); 36 | stepper2.setAcceleration(100.0); 37 | stepper2.moveTo(100); 38 | } 39 | 40 | void loop() 41 | { 42 | // Change direction at the limits 43 | if (stepper1.distanceToGo() == 0) 44 | stepper1.moveTo(-stepper1.currentPosition()); 45 | if (stepper2.distanceToGo() == 0) 46 | stepper2.moveTo(-stepper2.currentPosition()); 47 | stepper1.run(); 48 | stepper2.run(); 49 | } 50 | -------------------------------------------------------------------------------- /examples/MotorShield/MotorShield.pde: -------------------------------------------------------------------------------- 1 | // AFMotor_ConstantSpeed.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor 5 | // using the Adafruit Motor Shield 6 | // http://www.ladyada.net/make/mshield/index.html. 7 | // Create a subclass of AccelStepper which controls the motor pins via the 8 | // Motor Shield serial-to-parallel interface 9 | 10 | #include 11 | 12 | // Arduino pin names for interface to 74HCT595 latch 13 | // on Adafruit Motor Shield 14 | #define MOTORLATCH 12 15 | #define MOTORCLK 4 16 | #define MOTORENABLE 7 17 | #define MOTORDATA 8 18 | 19 | // PWM pins, also used to enable motor outputs 20 | #define PWM0A 5 21 | #define PWM0B 6 22 | #define PWM1A 9 23 | #define PWM1B 10 24 | #define PWM2A 11 25 | #define PWM2B 3 26 | 27 | 28 | // The main purpose of this class is to override setOutputPins to work with Adafruit Motor Shield 29 | class AFMotorShield : public AccelStepper 30 | { 31 | public: 32 | AFMotorShield(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5); 33 | 34 | virtual void setOutputPins(uint8_t mask); 35 | }; 36 | 37 | 38 | AFMotorShield::AFMotorShield(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4) 39 | : AccelStepper(interface, pin1, pin2, pin3, pin4) 40 | { 41 | // Enable motor control serial to parallel latch 42 | pinMode(MOTORLATCH, OUTPUT); 43 | pinMode(MOTORENABLE, OUTPUT); 44 | pinMode(MOTORDATA, OUTPUT); 45 | pinMode(MOTORCLK, OUTPUT); 46 | digitalWrite(MOTORENABLE, LOW); 47 | 48 | // enable both H bridges on motor 1 49 | pinMode(PWM2A, OUTPUT); 50 | pinMode(PWM2B, OUTPUT); 51 | pinMode(PWM0A, OUTPUT); 52 | pinMode(PWM0B, OUTPUT); 53 | digitalWrite(PWM2A, HIGH); 54 | digitalWrite(PWM2B, HIGH); 55 | digitalWrite(PWM0A, HIGH); 56 | digitalWrite(PWM0B, HIGH); 57 | 58 | setOutputPins(0); // Reset 59 | }; 60 | 61 | // Use the AF Motor Shield serial-to-parallel to set the state of the motor pins 62 | // Caution: the mapping of AccelStepper pins to AF motor outputs is not 63 | // obvious: 64 | // AccelStepper Motor Shield output 65 | // pin1 M4A 66 | // pin2 M1A 67 | // pin3 M2A 68 | // pin4 M3A 69 | // Caution this is pretty slow and limits the max speed of the motor to about 500/3 rpm 70 | void AFMotorShield::setOutputPins(uint8_t mask) 71 | { 72 | uint8_t i; 73 | 74 | digitalWrite(MOTORLATCH, LOW); 75 | digitalWrite(MOTORDATA, LOW); 76 | 77 | for (i=0; i<8; i++) 78 | { 79 | digitalWrite(MOTORCLK, LOW); 80 | 81 | if (mask & _BV(7-i)) 82 | digitalWrite(MOTORDATA, HIGH); 83 | else 84 | digitalWrite(MOTORDATA, LOW); 85 | 86 | digitalWrite(MOTORCLK, HIGH); 87 | } 88 | digitalWrite(MOTORLATCH, HIGH); 89 | } 90 | 91 | AFMotorShield stepper(AccelStepper::HALF3WIRE, 0, 0, 0, 0); // 3 phase HDD spindle drive 92 | 93 | void setup() 94 | { 95 | stepper.setMaxSpeed(500); // divide by 3 to get rpm 96 | stepper.setAcceleration(80); 97 | stepper.moveTo(10000000); 98 | } 99 | 100 | void loop() 101 | { 102 | stepper.run(); 103 | } 104 | -------------------------------------------------------------------------------- /examples/MultiStepper/MultiStepper.pde: -------------------------------------------------------------------------------- 1 | // MultiStepper.pde 2 | // -*- mode: C++ -*- 3 | // Use MultiStepper class to manage multiple steppers and make them all move to 4 | // the same position at the same time for linear 2d (or 3d) motion. 5 | 6 | #include 7 | #include 8 | 9 | // EG X-Y position bed driven by 2 steppers 10 | // Alas its not possible to build an array of these with different pins for each :-( 11 | AccelStepper stepper1(AccelStepper::FULL4WIRE, 2, 3, 4, 5); 12 | AccelStepper stepper2(AccelStepper::FULL4WIRE, 8, 9, 10, 11); 13 | 14 | // Up to 10 steppers can be handled as a group by MultiStepper 15 | MultiStepper steppers; 16 | 17 | void setup() { 18 | Serial.begin(9600); 19 | 20 | // Configure each stepper 21 | stepper1.setMaxSpeed(100); 22 | stepper2.setMaxSpeed(100); 23 | 24 | // Then give them to MultiStepper to manage 25 | steppers.addStepper(stepper1); 26 | steppers.addStepper(stepper2); 27 | } 28 | 29 | void loop() { 30 | long positions[2]; // Array of desired stepper positions 31 | 32 | positions[0] = 1000; 33 | positions[1] = 50; 34 | steppers.moveTo(positions); 35 | steppers.runSpeedToPosition(); // Blocks until all are in position 36 | delay(1000); 37 | 38 | // Move to a different coordinate 39 | positions[0] = -100; 40 | positions[1] = 100; 41 | steppers.moveTo(positions); 42 | steppers.runSpeedToPosition(); // Blocks until all are in position 43 | delay(1000); 44 | } 45 | -------------------------------------------------------------------------------- /examples/MultipleSteppers/MultipleSteppers.pde: -------------------------------------------------------------------------------- 1 | // MultiStepper.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Shows how to multiple simultaneous steppers 5 | // Runs one stepper forwards and backwards, accelerating and decelerating 6 | // at the limits. Runs other steppers at the same time 7 | // 8 | // Copyright (C) 2009 Mike McCauley 9 | // $Id: MultiStepper.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 10 | 11 | #include 12 | 13 | // Define some steppers and the pins the will use 14 | AccelStepper stepper1; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 15 | AccelStepper stepper2(AccelStepper::FULL4WIRE, 6, 7, 8, 9); 16 | AccelStepper stepper3(AccelStepper::FULL2WIRE, 10, 11); 17 | 18 | void setup() 19 | { 20 | stepper1.setMaxSpeed(200.0); 21 | stepper1.setAcceleration(100.0); 22 | stepper1.moveTo(24); 23 | 24 | stepper2.setMaxSpeed(300.0); 25 | stepper2.setAcceleration(100.0); 26 | stepper2.moveTo(1000000); 27 | 28 | stepper3.setMaxSpeed(300.0); 29 | stepper3.setAcceleration(100.0); 30 | stepper3.moveTo(1000000); 31 | } 32 | 33 | void loop() 34 | { 35 | // Change direction at the limits 36 | if (stepper1.distanceToGo() == 0) 37 | stepper1.moveTo(-stepper1.currentPosition()); 38 | stepper1.run(); 39 | stepper2.run(); 40 | stepper3.run(); 41 | } 42 | -------------------------------------------------------------------------------- /examples/Overshoot/Overshoot.pde: -------------------------------------------------------------------------------- 1 | // Overshoot.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Check overshoot handling 5 | // which sets a new target position and then waits until the stepper has 6 | // achieved it. This is used for testing the handling of overshoots 7 | // 8 | // Copyright (C) 2009 Mike McCauley 9 | // $Id: Overshoot.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 10 | 11 | #include 12 | 13 | // Define a stepper and the pins it will use 14 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 15 | 16 | void setup() 17 | { 18 | stepper.setMaxSpeed(150); 19 | stepper.setAcceleration(100); 20 | } 21 | 22 | void loop() 23 | { 24 | stepper.moveTo(500); 25 | while (stepper.currentPosition() != 300) // Full speed up to 300 26 | stepper.run(); 27 | stepper.runToNewPosition(0); // Cause an overshoot then back to 0 28 | } 29 | -------------------------------------------------------------------------------- /examples/ProportionalControl/ProportionalControl.pde: -------------------------------------------------------------------------------- 1 | // ProportionalControl.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Make a single stepper follow the analog value read from a pot or whatever 5 | // The stepper will move at a constant speed to each newly set posiiton, 6 | // depending on the value of the pot. 7 | // 8 | // Copyright (C) 2012 Mike McCauley 9 | // $Id: ProportionalControl.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 10 | 11 | #include 12 | 13 | // Define a stepper and the pins it will use 14 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 15 | 16 | // This defines the analog input pin for reading the control voltage 17 | // Tested with a 10k linear pot between 5v and GND 18 | #define ANALOG_IN A0 19 | 20 | void setup() 21 | { 22 | stepper.setMaxSpeed(1000); 23 | } 24 | 25 | void loop() 26 | { 27 | // Read new position 28 | int analog_in = analogRead(ANALOG_IN); 29 | stepper.moveTo(analog_in); 30 | stepper.setSpeed(100); 31 | stepper.runSpeedToPosition(); 32 | } 33 | -------------------------------------------------------------------------------- /examples/Quickstop/Quickstop.pde: -------------------------------------------------------------------------------- 1 | // Quickstop.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Check stop handling. 5 | // Calls stop() while the stepper is travelling at full speed, causing 6 | // the stepper to stop as quickly as possible, within the constraints of the 7 | // current acceleration. 8 | // 9 | // Copyright (C) 2012 Mike McCauley 10 | // $Id: $ 11 | 12 | #include 13 | 14 | // Define a stepper and the pins it will use 15 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 16 | 17 | void setup() 18 | { 19 | stepper.setMaxSpeed(150); 20 | stepper.setAcceleration(100); 21 | } 22 | 23 | void loop() 24 | { 25 | stepper.moveTo(500); 26 | while (stepper.currentPosition() != 300) // Full speed up to 300 27 | stepper.run(); 28 | stepper.stop(); // Stop as fast as possible: sets new target 29 | stepper.runToPosition(); 30 | // Now stopped after quickstop 31 | 32 | // Now go backwards 33 | stepper.moveTo(-500); 34 | while (stepper.currentPosition() != 0) // Full speed basck to 0 35 | stepper.run(); 36 | stepper.stop(); // Stop as fast as possible: sets new target 37 | stepper.runToPosition(); 38 | // Now stopped after quickstop 39 | 40 | } 41 | -------------------------------------------------------------------------------- /examples/Random/Random.pde: -------------------------------------------------------------------------------- 1 | // Random.pde 2 | // -*- mode: C++ -*- 3 | // 4 | // Make a single stepper perform random changes in speed, position and acceleration 5 | // 6 | // Copyright (C) 2009 Mike McCauley 7 | // $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $ 8 | 9 | #include 10 | 11 | // Define a stepper and the pins it will use 12 | AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5 13 | 14 | void setup() 15 | { 16 | } 17 | 18 | void loop() 19 | { 20 | if (stepper.distanceToGo() == 0) 21 | { 22 | // Random change to speed, position and acceleration 23 | // Make sure we dont get 0 speed or accelerations 24 | delay(1000); 25 | stepper.moveTo(rand() % 200); 26 | stepper.setMaxSpeed((rand() % 200) + 1); 27 | stepper.setAcceleration((rand() % 200) + 1); 28 | } 29 | stepper.run(); 30 | } 31 | -------------------------------------------------------------------------------- /extras/doc/annotated.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: Class List 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |
42 |
Class List
43 |
44 |
45 |
Here are the classes, structs, unions and interfaces with brief descriptions:
46 | 47 | 48 | 49 |
 CAccelStepperSupport for stepper motors with acceleration etc
 CMultiStepperOperate multiple AccelSteppers in a co-ordinated fashion
50 |
51 |
52 | 53 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /extras/doc/classAccelStepper-members.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: Member List 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |
42 |
AccelStepper Member List
43 |
44 |
45 | 46 |

This is the complete list of members for AccelStepper, including all inherited members.

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 |
_directionAccelStepperprotected
_stepIntervalAccelStepperprotected
acceleration()AccelStepper
AccelStepper(uint8_t interface=AccelStepper::FULL4WIRE, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5, bool enable=true)AccelStepper
AccelStepper(void(*forward)(), void(*backward)())AccelStepper
computeNewSpeed()AccelStepperprotectedvirtual
currentPosition()AccelStepper
Direction enum nameAccelStepperprotected
DIRECTION_CCW enum valueAccelStepperprotected
DIRECTION_CW enum valueAccelStepperprotected
disableOutputs()AccelSteppervirtual
distanceToGo()AccelStepper
DRIVER enum valueAccelStepper
enableOutputs()AccelSteppervirtual
FULL2WIRE enum valueAccelStepper
FULL3WIRE enum valueAccelStepper
FULL4WIRE enum valueAccelStepper
FUNCTION enum valueAccelStepper
HALF3WIRE enum valueAccelStepper
HALF4WIRE enum valueAccelStepper
isRunning()AccelStepper
maxSpeed()AccelStepper
MotorInterfaceType enum nameAccelStepper
move(long relative)AccelStepper
moveTo(long absolute)AccelStepper
run()AccelStepper
runSpeed()AccelStepper
runSpeedToPosition()AccelStepper
runToNewPosition(long position)AccelStepper
runToPosition()AccelStepper
setAcceleration(float acceleration)AccelStepper
setCurrentPosition(long position)AccelStepper
setEnablePin(uint8_t enablePin=0xff)AccelStepper
setMaxSpeed(float speed)AccelStepper
setMinPulseWidth(unsigned int minWidth)AccelStepper
setOutputPins(uint8_t mask)AccelStepperprotectedvirtual
setPinsInverted(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)AccelStepper
setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)AccelStepper
setSpeed(float speed)AccelStepper
speed()AccelStepper
step(long step)AccelStepperprotectedvirtual
step0(long step)AccelStepperprotectedvirtual
step1(long step)AccelStepperprotectedvirtual
step2(long step)AccelStepperprotectedvirtual
step3(long step)AccelStepperprotectedvirtual
step4(long step)AccelStepperprotectedvirtual
step6(long step)AccelStepperprotectedvirtual
step8(long step)AccelStepperprotectedvirtual
stepBackward()AccelStepperprotected
stepForward()AccelStepperprotected
stop()AccelStepper
targetPosition()AccelStepper
~AccelStepper()AccelStepperinlinevirtual
102 | 103 | 106 | 107 | 108 | -------------------------------------------------------------------------------- /extras/doc/doxygen.css: -------------------------------------------------------------------------------- 1 | /* The standard CSS for doxygen 1.9.1 */ 2 | 3 | body, table, div, p, dl { 4 | font: 400 14px/22px Roboto,sans-serif; 5 | } 6 | 7 | p.reference, p.definition { 8 | font: 400 14px/22px Roboto,sans-serif; 9 | } 10 | 11 | /* @group Heading Levels */ 12 | 13 | h1.groupheader { 14 | font-size: 150%; 15 | } 16 | 17 | .title { 18 | font: 400 14px/28px Roboto,sans-serif; 19 | font-size: 150%; 20 | font-weight: bold; 21 | margin: 10px 2px; 22 | } 23 | 24 | h2.groupheader { 25 | border-bottom: 1px solid #879ECB; 26 | color: #354C7B; 27 | font-size: 150%; 28 | font-weight: normal; 29 | margin-top: 1.75em; 30 | padding-top: 8px; 31 | padding-bottom: 4px; 32 | width: 100%; 33 | } 34 | 35 | h3.groupheader { 36 | font-size: 100%; 37 | } 38 | 39 | h1, h2, h3, h4, h5, h6 { 40 | -webkit-transition: text-shadow 0.5s linear; 41 | -moz-transition: text-shadow 0.5s linear; 42 | -ms-transition: text-shadow 0.5s linear; 43 | -o-transition: text-shadow 0.5s linear; 44 | transition: text-shadow 0.5s linear; 45 | margin-right: 15px; 46 | } 47 | 48 | h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { 49 | text-shadow: 0 0 15px cyan; 50 | } 51 | 52 | dt { 53 | font-weight: bold; 54 | } 55 | 56 | ul.multicol { 57 | -moz-column-gap: 1em; 58 | -webkit-column-gap: 1em; 59 | column-gap: 1em; 60 | -moz-column-count: 3; 61 | -webkit-column-count: 3; 62 | column-count: 3; 63 | } 64 | 65 | p.startli, p.startdd { 66 | margin-top: 2px; 67 | } 68 | 69 | th p.starttd, th p.intertd, th p.endtd { 70 | font-size: 100%; 71 | font-weight: 700; 72 | } 73 | 74 | p.starttd { 75 | margin-top: 0px; 76 | } 77 | 78 | p.endli { 79 | margin-bottom: 0px; 80 | } 81 | 82 | p.enddd { 83 | margin-bottom: 4px; 84 | } 85 | 86 | p.endtd { 87 | margin-bottom: 2px; 88 | } 89 | 90 | p.interli { 91 | } 92 | 93 | p.interdd { 94 | } 95 | 96 | p.intertd { 97 | } 98 | 99 | /* @end */ 100 | 101 | caption { 102 | font-weight: bold; 103 | } 104 | 105 | span.legend { 106 | font-size: 70%; 107 | text-align: center; 108 | } 109 | 110 | h3.version { 111 | font-size: 90%; 112 | text-align: center; 113 | } 114 | 115 | div.navtab { 116 | border-right: 1px solid #A3B4D7; 117 | padding-right: 15px; 118 | text-align: right; 119 | line-height: 110%; 120 | } 121 | 122 | div.navtab table { 123 | border-spacing: 0; 124 | } 125 | 126 | td.navtab { 127 | padding-right: 6px; 128 | padding-left: 6px; 129 | } 130 | td.navtabHL { 131 | background-image: url('tab_a.png'); 132 | background-repeat:repeat-x; 133 | padding-right: 6px; 134 | padding-left: 6px; 135 | } 136 | 137 | td.navtabHL a, td.navtabHL a:visited { 138 | color: #fff; 139 | text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); 140 | } 141 | 142 | a.navtab { 143 | font-weight: bold; 144 | } 145 | 146 | div.qindex{ 147 | text-align: center; 148 | width: 100%; 149 | line-height: 140%; 150 | font-size: 130%; 151 | color: #A0A0A0; 152 | } 153 | 154 | dt.alphachar{ 155 | font-size: 180%; 156 | font-weight: bold; 157 | } 158 | 159 | .alphachar a{ 160 | color: black; 161 | } 162 | 163 | .alphachar a:hover, .alphachar a:visited{ 164 | text-decoration: none; 165 | } 166 | 167 | .classindex dl { 168 | padding: 25px; 169 | column-count:1 170 | } 171 | 172 | .classindex dd { 173 | display:inline-block; 174 | margin-left: 50px; 175 | width: 90%; 176 | line-height: 1.15em; 177 | } 178 | 179 | .classindex dl.odd { 180 | background-color: #F8F9FC; 181 | } 182 | 183 | @media(min-width: 1120px) { 184 | .classindex dl { 185 | column-count:2 186 | } 187 | } 188 | 189 | @media(min-width: 1320px) { 190 | .classindex dl { 191 | column-count:3 192 | } 193 | } 194 | 195 | 196 | /* @group Link Styling */ 197 | 198 | a { 199 | color: #3D578C; 200 | font-weight: normal; 201 | text-decoration: none; 202 | } 203 | 204 | .contents a:visited { 205 | color: #4665A2; 206 | } 207 | 208 | a:hover { 209 | text-decoration: underline; 210 | } 211 | 212 | .contents a.qindexHL:visited { 213 | color: #FFFFFF; 214 | } 215 | 216 | a.el { 217 | font-weight: bold; 218 | } 219 | 220 | a.elRef { 221 | } 222 | 223 | a.code, a.code:visited, a.line, a.line:visited { 224 | color: #4665A2; 225 | } 226 | 227 | a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { 228 | color: #4665A2; 229 | } 230 | 231 | /* @end */ 232 | 233 | dl.el { 234 | margin-left: -1cm; 235 | } 236 | 237 | ul { 238 | overflow: hidden; /*Fixed: list item bullets overlap floating elements*/ 239 | } 240 | 241 | #side-nav ul { 242 | overflow: visible; /* reset ul rule for scroll bar in GENERATE_TREEVIEW window */ 243 | } 244 | 245 | #main-nav ul { 246 | overflow: visible; /* reset ul rule for the navigation bar drop down lists */ 247 | } 248 | 249 | .fragment { 250 | text-align: left; 251 | direction: ltr; 252 | overflow-x: auto; /*Fixed: fragment lines overlap floating elements*/ 253 | overflow-y: hidden; 254 | } 255 | 256 | pre.fragment { 257 | border: 1px solid #C4CFE5; 258 | background-color: #FBFCFD; 259 | padding: 4px 6px; 260 | margin: 4px 8px 4px 2px; 261 | overflow: auto; 262 | word-wrap: break-word; 263 | font-size: 9pt; 264 | line-height: 125%; 265 | font-family: monospace, fixed; 266 | font-size: 105%; 267 | } 268 | 269 | div.fragment { 270 | padding: 0 0 1px 0; /*Fixed: last line underline overlap border*/ 271 | margin: 4px 8px 4px 2px; 272 | background-color: #FBFCFD; 273 | border: 1px solid #C4CFE5; 274 | } 275 | 276 | div.line { 277 | font-family: monospace, fixed; 278 | font-size: 13px; 279 | min-height: 13px; 280 | line-height: 1.0; 281 | text-wrap: unrestricted; 282 | white-space: -moz-pre-wrap; /* Moz */ 283 | white-space: -pre-wrap; /* Opera 4-6 */ 284 | white-space: -o-pre-wrap; /* Opera 7 */ 285 | white-space: pre-wrap; /* CSS3 */ 286 | word-wrap: break-word; /* IE 5.5+ */ 287 | text-indent: -53px; 288 | padding-left: 53px; 289 | padding-bottom: 0px; 290 | margin: 0px; 291 | -webkit-transition-property: background-color, box-shadow; 292 | -webkit-transition-duration: 0.5s; 293 | -moz-transition-property: background-color, box-shadow; 294 | -moz-transition-duration: 0.5s; 295 | -ms-transition-property: background-color, box-shadow; 296 | -ms-transition-duration: 0.5s; 297 | -o-transition-property: background-color, box-shadow; 298 | -o-transition-duration: 0.5s; 299 | transition-property: background-color, box-shadow; 300 | transition-duration: 0.5s; 301 | } 302 | 303 | div.line:after { 304 | content:"\000A"; 305 | white-space: pre; 306 | } 307 | 308 | div.line.glow { 309 | background-color: cyan; 310 | box-shadow: 0 0 10px cyan; 311 | } 312 | 313 | 314 | span.lineno { 315 | padding-right: 4px; 316 | text-align: right; 317 | border-right: 2px solid #0F0; 318 | background-color: #E8E8E8; 319 | white-space: pre; 320 | } 321 | span.lineno a { 322 | background-color: #D8D8D8; 323 | } 324 | 325 | span.lineno a:hover { 326 | background-color: #C8C8C8; 327 | } 328 | 329 | .lineno { 330 | -webkit-touch-callout: none; 331 | -webkit-user-select: none; 332 | -khtml-user-select: none; 333 | -moz-user-select: none; 334 | -ms-user-select: none; 335 | user-select: none; 336 | } 337 | 338 | div.ah, span.ah { 339 | background-color: black; 340 | font-weight: bold; 341 | color: #FFFFFF; 342 | margin-bottom: 3px; 343 | margin-top: 3px; 344 | padding: 0.2em; 345 | border: solid thin #333; 346 | border-radius: 0.5em; 347 | -webkit-border-radius: .5em; 348 | -moz-border-radius: .5em; 349 | box-shadow: 2px 2px 3px #999; 350 | -webkit-box-shadow: 2px 2px 3px #999; 351 | -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; 352 | background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); 353 | background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000 110%); 354 | } 355 | 356 | div.classindex ul { 357 | list-style: none; 358 | padding-left: 0; 359 | } 360 | 361 | div.classindex span.ai { 362 | display: inline-block; 363 | } 364 | 365 | div.groupHeader { 366 | margin-left: 16px; 367 | margin-top: 12px; 368 | font-weight: bold; 369 | } 370 | 371 | div.groupText { 372 | margin-left: 16px; 373 | font-style: italic; 374 | } 375 | 376 | body { 377 | background-color: white; 378 | color: black; 379 | margin: 0; 380 | } 381 | 382 | div.contents { 383 | margin-top: 10px; 384 | margin-left: 12px; 385 | margin-right: 8px; 386 | } 387 | 388 | td.indexkey { 389 | background-color: #EBEFF6; 390 | font-weight: bold; 391 | border: 1px solid #C4CFE5; 392 | margin: 2px 0px 2px 0; 393 | padding: 2px 10px; 394 | white-space: nowrap; 395 | vertical-align: top; 396 | } 397 | 398 | td.indexvalue { 399 | background-color: #EBEFF6; 400 | border: 1px solid #C4CFE5; 401 | padding: 2px 10px; 402 | margin: 2px 0px; 403 | } 404 | 405 | tr.memlist { 406 | background-color: #EEF1F7; 407 | } 408 | 409 | p.formulaDsp { 410 | text-align: center; 411 | } 412 | 413 | img.formulaDsp { 414 | 415 | } 416 | 417 | img.formulaInl, img.inline { 418 | vertical-align: middle; 419 | } 420 | 421 | div.center { 422 | text-align: center; 423 | margin-top: 0px; 424 | margin-bottom: 0px; 425 | padding: 0px; 426 | } 427 | 428 | div.center img { 429 | border: 0px; 430 | } 431 | 432 | address.footer { 433 | text-align: right; 434 | padding-right: 12px; 435 | } 436 | 437 | img.footer { 438 | border: 0px; 439 | vertical-align: middle; 440 | } 441 | 442 | /* @group Code Colorization */ 443 | 444 | span.keyword { 445 | color: #008000 446 | } 447 | 448 | span.keywordtype { 449 | color: #604020 450 | } 451 | 452 | span.keywordflow { 453 | color: #e08000 454 | } 455 | 456 | span.comment { 457 | color: #800000 458 | } 459 | 460 | span.preprocessor { 461 | color: #806020 462 | } 463 | 464 | span.stringliteral { 465 | color: #002080 466 | } 467 | 468 | span.charliteral { 469 | color: #008080 470 | } 471 | 472 | span.vhdldigit { 473 | color: #ff00ff 474 | } 475 | 476 | span.vhdlchar { 477 | color: #000000 478 | } 479 | 480 | span.vhdlkeyword { 481 | color: #700070 482 | } 483 | 484 | span.vhdllogic { 485 | color: #ff0000 486 | } 487 | 488 | blockquote { 489 | background-color: #F7F8FB; 490 | border-left: 2px solid #9CAFD4; 491 | margin: 0 24px 0 4px; 492 | padding: 0 12px 0 16px; 493 | } 494 | 495 | blockquote.DocNodeRTL { 496 | border-left: 0; 497 | border-right: 2px solid #9CAFD4; 498 | margin: 0 4px 0 24px; 499 | padding: 0 16px 0 12px; 500 | } 501 | 502 | /* @end */ 503 | 504 | /* 505 | .search { 506 | color: #003399; 507 | font-weight: bold; 508 | } 509 | 510 | form.search { 511 | margin-bottom: 0px; 512 | margin-top: 0px; 513 | } 514 | 515 | input.search { 516 | font-size: 75%; 517 | color: #000080; 518 | font-weight: normal; 519 | background-color: #e8eef2; 520 | } 521 | */ 522 | 523 | td.tiny { 524 | font-size: 75%; 525 | } 526 | 527 | .dirtab { 528 | padding: 4px; 529 | border-collapse: collapse; 530 | border: 1px solid #A3B4D7; 531 | } 532 | 533 | th.dirtab { 534 | background: #EBEFF6; 535 | font-weight: bold; 536 | } 537 | 538 | hr { 539 | height: 0px; 540 | border: none; 541 | border-top: 1px solid #4A6AAA; 542 | } 543 | 544 | hr.footer { 545 | height: 1px; 546 | } 547 | 548 | /* @group Member Descriptions */ 549 | 550 | table.memberdecls { 551 | border-spacing: 0px; 552 | padding: 0px; 553 | } 554 | 555 | .memberdecls td, .fieldtable tr { 556 | -webkit-transition-property: background-color, box-shadow; 557 | -webkit-transition-duration: 0.5s; 558 | -moz-transition-property: background-color, box-shadow; 559 | -moz-transition-duration: 0.5s; 560 | -ms-transition-property: background-color, box-shadow; 561 | -ms-transition-duration: 0.5s; 562 | -o-transition-property: background-color, box-shadow; 563 | -o-transition-duration: 0.5s; 564 | transition-property: background-color, box-shadow; 565 | transition-duration: 0.5s; 566 | } 567 | 568 | .memberdecls td.glow, .fieldtable tr.glow { 569 | background-color: cyan; 570 | box-shadow: 0 0 15px cyan; 571 | } 572 | 573 | .mdescLeft, .mdescRight, 574 | .memItemLeft, .memItemRight, 575 | .memTemplItemLeft, .memTemplItemRight, .memTemplParams { 576 | background-color: #F9FAFC; 577 | border: none; 578 | margin: 4px; 579 | padding: 1px 0 0 8px; 580 | } 581 | 582 | .mdescLeft, .mdescRight { 583 | padding: 0px 8px 4px 8px; 584 | color: #555; 585 | } 586 | 587 | .memSeparator { 588 | border-bottom: 1px solid #DEE4F0; 589 | line-height: 1px; 590 | margin: 0px; 591 | padding: 0px; 592 | } 593 | 594 | .memItemLeft, .memTemplItemLeft { 595 | white-space: nowrap; 596 | } 597 | 598 | .memItemRight, .memTemplItemRight { 599 | width: 100%; 600 | } 601 | 602 | .memTemplParams { 603 | color: #4665A2; 604 | white-space: nowrap; 605 | font-size: 80%; 606 | } 607 | 608 | /* @end */ 609 | 610 | /* @group Member Details */ 611 | 612 | /* Styles for detailed member documentation */ 613 | 614 | .memtitle { 615 | padding: 8px; 616 | border-top: 1px solid #A8B8D9; 617 | border-left: 1px solid #A8B8D9; 618 | border-right: 1px solid #A8B8D9; 619 | border-top-right-radius: 4px; 620 | border-top-left-radius: 4px; 621 | margin-bottom: -1px; 622 | background-image: url('nav_f.png'); 623 | background-repeat: repeat-x; 624 | background-color: #E2E8F2; 625 | line-height: 1.25; 626 | font-weight: 300; 627 | float:left; 628 | } 629 | 630 | .permalink 631 | { 632 | font-size: 65%; 633 | display: inline-block; 634 | vertical-align: middle; 635 | } 636 | 637 | .memtemplate { 638 | font-size: 80%; 639 | color: #4665A2; 640 | font-weight: normal; 641 | margin-left: 9px; 642 | } 643 | 644 | .memnav { 645 | background-color: #EBEFF6; 646 | border: 1px solid #A3B4D7; 647 | text-align: center; 648 | margin: 2px; 649 | margin-right: 15px; 650 | padding: 2px; 651 | } 652 | 653 | .mempage { 654 | width: 100%; 655 | } 656 | 657 | .memitem { 658 | padding: 0; 659 | margin-bottom: 10px; 660 | margin-right: 5px; 661 | -webkit-transition: box-shadow 0.5s linear; 662 | -moz-transition: box-shadow 0.5s linear; 663 | -ms-transition: box-shadow 0.5s linear; 664 | -o-transition: box-shadow 0.5s linear; 665 | transition: box-shadow 0.5s linear; 666 | display: table !important; 667 | width: 100%; 668 | } 669 | 670 | .memitem.glow { 671 | box-shadow: 0 0 15px cyan; 672 | } 673 | 674 | .memname { 675 | font-weight: 400; 676 | margin-left: 6px; 677 | } 678 | 679 | .memname td { 680 | vertical-align: bottom; 681 | } 682 | 683 | .memproto, dl.reflist dt { 684 | border-top: 1px solid #A8B8D9; 685 | border-left: 1px solid #A8B8D9; 686 | border-right: 1px solid #A8B8D9; 687 | padding: 6px 0px 6px 0px; 688 | color: #253555; 689 | font-weight: bold; 690 | text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); 691 | background-color: #DFE5F1; 692 | /* opera specific markup */ 693 | box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); 694 | border-top-right-radius: 4px; 695 | /* firefox specific markup */ 696 | -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; 697 | -moz-border-radius-topright: 4px; 698 | /* webkit specific markup */ 699 | -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); 700 | -webkit-border-top-right-radius: 4px; 701 | 702 | } 703 | 704 | .overload { 705 | font-family: "courier new",courier,monospace; 706 | font-size: 65%; 707 | } 708 | 709 | .memdoc, dl.reflist dd { 710 | border-bottom: 1px solid #A8B8D9; 711 | border-left: 1px solid #A8B8D9; 712 | border-right: 1px solid #A8B8D9; 713 | padding: 6px 10px 2px 10px; 714 | background-color: #FBFCFD; 715 | border-top-width: 0; 716 | background-image:url('nav_g.png'); 717 | background-repeat:repeat-x; 718 | background-color: #FFFFFF; 719 | /* opera specific markup */ 720 | border-bottom-left-radius: 4px; 721 | border-bottom-right-radius: 4px; 722 | box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); 723 | /* firefox specific markup */ 724 | -moz-border-radius-bottomleft: 4px; 725 | -moz-border-radius-bottomright: 4px; 726 | -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; 727 | /* webkit specific markup */ 728 | -webkit-border-bottom-left-radius: 4px; 729 | -webkit-border-bottom-right-radius: 4px; 730 | -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); 731 | } 732 | 733 | dl.reflist dt { 734 | padding: 5px; 735 | } 736 | 737 | dl.reflist dd { 738 | margin: 0px 0px 10px 0px; 739 | padding: 5px; 740 | } 741 | 742 | .paramkey { 743 | text-align: right; 744 | } 745 | 746 | .paramtype { 747 | white-space: nowrap; 748 | } 749 | 750 | .paramname { 751 | color: #602020; 752 | white-space: nowrap; 753 | } 754 | .paramname em { 755 | font-style: normal; 756 | } 757 | .paramname code { 758 | line-height: 14px; 759 | } 760 | 761 | .params, .retval, .exception, .tparams { 762 | margin-left: 0px; 763 | padding-left: 0px; 764 | } 765 | 766 | .params .paramname, .retval .paramname, .tparams .paramname, .exception .paramname { 767 | font-weight: bold; 768 | vertical-align: top; 769 | } 770 | 771 | .params .paramtype, .tparams .paramtype { 772 | font-style: italic; 773 | vertical-align: top; 774 | } 775 | 776 | .params .paramdir, .tparams .paramdir { 777 | font-family: "courier new",courier,monospace; 778 | vertical-align: top; 779 | } 780 | 781 | table.mlabels { 782 | border-spacing: 0px; 783 | } 784 | 785 | td.mlabels-left { 786 | width: 100%; 787 | padding: 0px; 788 | } 789 | 790 | td.mlabels-right { 791 | vertical-align: bottom; 792 | padding: 0px; 793 | white-space: nowrap; 794 | } 795 | 796 | span.mlabels { 797 | margin-left: 8px; 798 | } 799 | 800 | span.mlabel { 801 | background-color: #728DC1; 802 | border-top:1px solid #5373B4; 803 | border-left:1px solid #5373B4; 804 | border-right:1px solid #C4CFE5; 805 | border-bottom:1px solid #C4CFE5; 806 | text-shadow: none; 807 | color: white; 808 | margin-right: 4px; 809 | padding: 2px 3px; 810 | border-radius: 3px; 811 | font-size: 7pt; 812 | white-space: nowrap; 813 | vertical-align: middle; 814 | } 815 | 816 | 817 | 818 | /* @end */ 819 | 820 | /* these are for tree view inside a (index) page */ 821 | 822 | div.directory { 823 | margin: 10px 0px; 824 | border-top: 1px solid #9CAFD4; 825 | border-bottom: 1px solid #9CAFD4; 826 | width: 100%; 827 | } 828 | 829 | .directory table { 830 | border-collapse:collapse; 831 | } 832 | 833 | .directory td { 834 | margin: 0px; 835 | padding: 0px; 836 | vertical-align: top; 837 | } 838 | 839 | .directory td.entry { 840 | white-space: nowrap; 841 | padding-right: 6px; 842 | padding-top: 3px; 843 | } 844 | 845 | .directory td.entry a { 846 | outline:none; 847 | } 848 | 849 | .directory td.entry a img { 850 | border: none; 851 | } 852 | 853 | .directory td.desc { 854 | width: 100%; 855 | padding-left: 6px; 856 | padding-right: 6px; 857 | padding-top: 3px; 858 | border-left: 1px solid rgba(0,0,0,0.05); 859 | } 860 | 861 | .directory tr.even { 862 | padding-left: 6px; 863 | background-color: #F7F8FB; 864 | } 865 | 866 | .directory img { 867 | vertical-align: -30%; 868 | } 869 | 870 | .directory .levels { 871 | white-space: nowrap; 872 | width: 100%; 873 | text-align: right; 874 | font-size: 9pt; 875 | } 876 | 877 | .directory .levels span { 878 | cursor: pointer; 879 | padding-left: 2px; 880 | padding-right: 2px; 881 | color: #3D578C; 882 | } 883 | 884 | .arrow { 885 | color: #9CAFD4; 886 | -webkit-user-select: none; 887 | -khtml-user-select: none; 888 | -moz-user-select: none; 889 | -ms-user-select: none; 890 | user-select: none; 891 | cursor: pointer; 892 | font-size: 80%; 893 | display: inline-block; 894 | width: 16px; 895 | height: 22px; 896 | } 897 | 898 | .icon { 899 | font-family: Arial, Helvetica; 900 | font-weight: bold; 901 | font-size: 12px; 902 | height: 14px; 903 | width: 16px; 904 | display: inline-block; 905 | background-color: #728DC1; 906 | color: white; 907 | text-align: center; 908 | border-radius: 4px; 909 | margin-left: 2px; 910 | margin-right: 2px; 911 | } 912 | 913 | .icona { 914 | width: 24px; 915 | height: 22px; 916 | display: inline-block; 917 | } 918 | 919 | .iconfopen { 920 | width: 24px; 921 | height: 18px; 922 | margin-bottom: 4px; 923 | background-image:url('folderopen.png'); 924 | background-position: 0px -4px; 925 | background-repeat: repeat-y; 926 | vertical-align:top; 927 | display: inline-block; 928 | } 929 | 930 | .iconfclosed { 931 | width: 24px; 932 | height: 18px; 933 | margin-bottom: 4px; 934 | background-image:url('folderclosed.png'); 935 | background-position: 0px -4px; 936 | background-repeat: repeat-y; 937 | vertical-align:top; 938 | display: inline-block; 939 | } 940 | 941 | .icondoc { 942 | width: 24px; 943 | height: 18px; 944 | margin-bottom: 4px; 945 | background-image:url('doc.png'); 946 | background-position: 0px -4px; 947 | background-repeat: repeat-y; 948 | vertical-align:top; 949 | display: inline-block; 950 | } 951 | 952 | table.directory { 953 | font: 400 14px Roboto,sans-serif; 954 | } 955 | 956 | /* @end */ 957 | 958 | div.dynheader { 959 | margin-top: 8px; 960 | -webkit-touch-callout: none; 961 | -webkit-user-select: none; 962 | -khtml-user-select: none; 963 | -moz-user-select: none; 964 | -ms-user-select: none; 965 | user-select: none; 966 | } 967 | 968 | address { 969 | font-style: normal; 970 | color: #2A3D61; 971 | } 972 | 973 | table.doxtable caption { 974 | caption-side: top; 975 | } 976 | 977 | table.doxtable { 978 | border-collapse:collapse; 979 | margin-top: 4px; 980 | margin-bottom: 4px; 981 | } 982 | 983 | table.doxtable td, table.doxtable th { 984 | border: 1px solid #2D4068; 985 | padding: 3px 7px 2px; 986 | } 987 | 988 | table.doxtable th { 989 | background-color: #374F7F; 990 | color: #FFFFFF; 991 | font-size: 110%; 992 | padding-bottom: 4px; 993 | padding-top: 5px; 994 | } 995 | 996 | table.fieldtable { 997 | /*width: 100%;*/ 998 | margin-bottom: 10px; 999 | border: 1px solid #A8B8D9; 1000 | border-spacing: 0px; 1001 | -moz-border-radius: 4px; 1002 | -webkit-border-radius: 4px; 1003 | border-radius: 4px; 1004 | -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; 1005 | -webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); 1006 | box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); 1007 | } 1008 | 1009 | .fieldtable td, .fieldtable th { 1010 | padding: 3px 7px 2px; 1011 | } 1012 | 1013 | .fieldtable td.fieldtype, .fieldtable td.fieldname { 1014 | white-space: nowrap; 1015 | border-right: 1px solid #A8B8D9; 1016 | border-bottom: 1px solid #A8B8D9; 1017 | vertical-align: top; 1018 | } 1019 | 1020 | .fieldtable td.fieldname { 1021 | padding-top: 3px; 1022 | } 1023 | 1024 | .fieldtable td.fielddoc { 1025 | border-bottom: 1px solid #A8B8D9; 1026 | /*width: 100%;*/ 1027 | } 1028 | 1029 | .fieldtable td.fielddoc p:first-child { 1030 | margin-top: 0px; 1031 | } 1032 | 1033 | .fieldtable td.fielddoc p:last-child { 1034 | margin-bottom: 2px; 1035 | } 1036 | 1037 | .fieldtable tr:last-child td { 1038 | border-bottom: none; 1039 | } 1040 | 1041 | .fieldtable th { 1042 | background-image:url('nav_f.png'); 1043 | background-repeat:repeat-x; 1044 | background-color: #E2E8F2; 1045 | font-size: 90%; 1046 | color: #253555; 1047 | padding-bottom: 4px; 1048 | padding-top: 5px; 1049 | text-align:left; 1050 | font-weight: 400; 1051 | -moz-border-radius-topleft: 4px; 1052 | -moz-border-radius-topright: 4px; 1053 | -webkit-border-top-left-radius: 4px; 1054 | -webkit-border-top-right-radius: 4px; 1055 | border-top-left-radius: 4px; 1056 | border-top-right-radius: 4px; 1057 | border-bottom: 1px solid #A8B8D9; 1058 | } 1059 | 1060 | 1061 | .tabsearch { 1062 | top: 0px; 1063 | left: 10px; 1064 | height: 36px; 1065 | background-image: url('tab_b.png'); 1066 | z-index: 101; 1067 | overflow: hidden; 1068 | font-size: 13px; 1069 | } 1070 | 1071 | .navpath ul 1072 | { 1073 | font-size: 11px; 1074 | background-image:url('tab_b.png'); 1075 | background-repeat:repeat-x; 1076 | background-position: 0 -5px; 1077 | height:30px; 1078 | line-height:30px; 1079 | color:#8AA0CC; 1080 | border:solid 1px #C2CDE4; 1081 | overflow:hidden; 1082 | margin:0px; 1083 | padding:0px; 1084 | } 1085 | 1086 | .navpath li 1087 | { 1088 | list-style-type:none; 1089 | float:left; 1090 | padding-left:10px; 1091 | padding-right:15px; 1092 | background-image:url('bc_s.png'); 1093 | background-repeat:no-repeat; 1094 | background-position:right; 1095 | color:#364D7C; 1096 | } 1097 | 1098 | .navpath li.navelem a 1099 | { 1100 | height:32px; 1101 | display:block; 1102 | text-decoration: none; 1103 | outline: none; 1104 | color: #283A5D; 1105 | font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; 1106 | text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); 1107 | text-decoration: none; 1108 | } 1109 | 1110 | .navpath li.navelem a:hover 1111 | { 1112 | color:#6884BD; 1113 | } 1114 | 1115 | .navpath li.footer 1116 | { 1117 | list-style-type:none; 1118 | float:right; 1119 | padding-left:10px; 1120 | padding-right:15px; 1121 | background-image:none; 1122 | background-repeat:no-repeat; 1123 | background-position:right; 1124 | color:#364D7C; 1125 | font-size: 8pt; 1126 | } 1127 | 1128 | 1129 | div.summary 1130 | { 1131 | float: right; 1132 | font-size: 8pt; 1133 | padding-right: 5px; 1134 | width: 50%; 1135 | text-align: right; 1136 | } 1137 | 1138 | div.summary a 1139 | { 1140 | white-space: nowrap; 1141 | } 1142 | 1143 | table.classindex 1144 | { 1145 | margin: 10px; 1146 | white-space: nowrap; 1147 | margin-left: 3%; 1148 | margin-right: 3%; 1149 | width: 94%; 1150 | border: 0; 1151 | border-spacing: 0; 1152 | padding: 0; 1153 | } 1154 | 1155 | div.ingroups 1156 | { 1157 | font-size: 8pt; 1158 | width: 50%; 1159 | text-align: left; 1160 | } 1161 | 1162 | div.ingroups a 1163 | { 1164 | white-space: nowrap; 1165 | } 1166 | 1167 | div.header 1168 | { 1169 | background-image:url('nav_h.png'); 1170 | background-repeat:repeat-x; 1171 | background-color: #F9FAFC; 1172 | margin: 0px; 1173 | border-bottom: 1px solid #C4CFE5; 1174 | } 1175 | 1176 | div.headertitle 1177 | { 1178 | padding: 5px 5px 5px 10px; 1179 | } 1180 | 1181 | .PageDocRTL-title div.headertitle { 1182 | text-align: right; 1183 | direction: rtl; 1184 | } 1185 | 1186 | dl { 1187 | padding: 0 0 0 0; 1188 | } 1189 | 1190 | /* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug, dl.examples */ 1191 | dl.section { 1192 | margin-left: 0px; 1193 | padding-left: 0px; 1194 | } 1195 | 1196 | dl.section.DocNodeRTL { 1197 | margin-right: 0px; 1198 | padding-right: 0px; 1199 | } 1200 | 1201 | dl.note { 1202 | margin-left: -7px; 1203 | padding-left: 3px; 1204 | border-left: 4px solid; 1205 | border-color: #D0C000; 1206 | } 1207 | 1208 | dl.note.DocNodeRTL { 1209 | margin-left: 0; 1210 | padding-left: 0; 1211 | border-left: 0; 1212 | margin-right: -7px; 1213 | padding-right: 3px; 1214 | border-right: 4px solid; 1215 | border-color: #D0C000; 1216 | } 1217 | 1218 | dl.warning, dl.attention { 1219 | margin-left: -7px; 1220 | padding-left: 3px; 1221 | border-left: 4px solid; 1222 | border-color: #FF0000; 1223 | } 1224 | 1225 | dl.warning.DocNodeRTL, dl.attention.DocNodeRTL { 1226 | margin-left: 0; 1227 | padding-left: 0; 1228 | border-left: 0; 1229 | margin-right: -7px; 1230 | padding-right: 3px; 1231 | border-right: 4px solid; 1232 | border-color: #FF0000; 1233 | } 1234 | 1235 | dl.pre, dl.post, dl.invariant { 1236 | margin-left: -7px; 1237 | padding-left: 3px; 1238 | border-left: 4px solid; 1239 | border-color: #00D000; 1240 | } 1241 | 1242 | dl.pre.DocNodeRTL, dl.post.DocNodeRTL, dl.invariant.DocNodeRTL { 1243 | margin-left: 0; 1244 | padding-left: 0; 1245 | border-left: 0; 1246 | margin-right: -7px; 1247 | padding-right: 3px; 1248 | border-right: 4px solid; 1249 | border-color: #00D000; 1250 | } 1251 | 1252 | dl.deprecated { 1253 | margin-left: -7px; 1254 | padding-left: 3px; 1255 | border-left: 4px solid; 1256 | border-color: #505050; 1257 | } 1258 | 1259 | dl.deprecated.DocNodeRTL { 1260 | margin-left: 0; 1261 | padding-left: 0; 1262 | border-left: 0; 1263 | margin-right: -7px; 1264 | padding-right: 3px; 1265 | border-right: 4px solid; 1266 | border-color: #505050; 1267 | } 1268 | 1269 | dl.todo { 1270 | margin-left: -7px; 1271 | padding-left: 3px; 1272 | border-left: 4px solid; 1273 | border-color: #00C0E0; 1274 | } 1275 | 1276 | dl.todo.DocNodeRTL { 1277 | margin-left: 0; 1278 | padding-left: 0; 1279 | border-left: 0; 1280 | margin-right: -7px; 1281 | padding-right: 3px; 1282 | border-right: 4px solid; 1283 | border-color: #00C0E0; 1284 | } 1285 | 1286 | dl.test { 1287 | margin-left: -7px; 1288 | padding-left: 3px; 1289 | border-left: 4px solid; 1290 | border-color: #3030E0; 1291 | } 1292 | 1293 | dl.test.DocNodeRTL { 1294 | margin-left: 0; 1295 | padding-left: 0; 1296 | border-left: 0; 1297 | margin-right: -7px; 1298 | padding-right: 3px; 1299 | border-right: 4px solid; 1300 | border-color: #3030E0; 1301 | } 1302 | 1303 | dl.bug { 1304 | margin-left: -7px; 1305 | padding-left: 3px; 1306 | border-left: 4px solid; 1307 | border-color: #C08050; 1308 | } 1309 | 1310 | dl.bug.DocNodeRTL { 1311 | margin-left: 0; 1312 | padding-left: 0; 1313 | border-left: 0; 1314 | margin-right: -7px; 1315 | padding-right: 3px; 1316 | border-right: 4px solid; 1317 | border-color: #C08050; 1318 | } 1319 | 1320 | dl.section dd { 1321 | margin-bottom: 6px; 1322 | } 1323 | 1324 | 1325 | #projectlogo 1326 | { 1327 | text-align: center; 1328 | vertical-align: bottom; 1329 | border-collapse: separate; 1330 | } 1331 | 1332 | #projectlogo img 1333 | { 1334 | border: 0px none; 1335 | } 1336 | 1337 | #projectalign 1338 | { 1339 | vertical-align: middle; 1340 | } 1341 | 1342 | #projectname 1343 | { 1344 | font: 300% Tahoma, Arial,sans-serif; 1345 | margin: 0px; 1346 | padding: 2px 0px; 1347 | } 1348 | 1349 | #projectbrief 1350 | { 1351 | font: 120% Tahoma, Arial,sans-serif; 1352 | margin: 0px; 1353 | padding: 0px; 1354 | } 1355 | 1356 | #projectnumber 1357 | { 1358 | font: 50% Tahoma, Arial,sans-serif; 1359 | margin: 0px; 1360 | padding: 0px; 1361 | } 1362 | 1363 | #titlearea 1364 | { 1365 | padding: 0px; 1366 | margin: 0px; 1367 | width: 100%; 1368 | border-bottom: 1px solid #5373B4; 1369 | } 1370 | 1371 | .image 1372 | { 1373 | text-align: center; 1374 | } 1375 | 1376 | .dotgraph 1377 | { 1378 | text-align: center; 1379 | } 1380 | 1381 | .mscgraph 1382 | { 1383 | text-align: center; 1384 | } 1385 | 1386 | .plantumlgraph 1387 | { 1388 | text-align: center; 1389 | } 1390 | 1391 | .diagraph 1392 | { 1393 | text-align: center; 1394 | } 1395 | 1396 | .caption 1397 | { 1398 | font-weight: bold; 1399 | } 1400 | 1401 | div.zoom 1402 | { 1403 | border: 1px solid #90A5CE; 1404 | } 1405 | 1406 | dl.citelist { 1407 | margin-bottom:50px; 1408 | } 1409 | 1410 | dl.citelist dt { 1411 | color:#334975; 1412 | float:left; 1413 | font-weight:bold; 1414 | margin-right:10px; 1415 | padding:5px; 1416 | text-align:right; 1417 | width:52px; 1418 | } 1419 | 1420 | dl.citelist dd { 1421 | margin:2px 0 2px 72px; 1422 | padding:5px 0; 1423 | } 1424 | 1425 | div.toc { 1426 | padding: 14px 25px; 1427 | background-color: #F4F6FA; 1428 | border: 1px solid #D8DFEE; 1429 | border-radius: 7px 7px 7px 7px; 1430 | float: right; 1431 | height: auto; 1432 | margin: 0 8px 10px 10px; 1433 | width: 200px; 1434 | } 1435 | 1436 | .PageDocRTL-title div.toc { 1437 | float: left !important; 1438 | text-align: right; 1439 | } 1440 | 1441 | div.toc li { 1442 | background: url("bdwn.png") no-repeat scroll 0 5px transparent; 1443 | font: 10px/1.2 Verdana,DejaVu Sans,Geneva,sans-serif; 1444 | margin-top: 5px; 1445 | padding-left: 10px; 1446 | padding-top: 2px; 1447 | } 1448 | 1449 | .PageDocRTL-title div.toc li { 1450 | background-position-x: right !important; 1451 | padding-left: 0 !important; 1452 | padding-right: 10px; 1453 | } 1454 | 1455 | div.toc h3 { 1456 | font: bold 12px/1.2 Arial,FreeSans,sans-serif; 1457 | color: #4665A2; 1458 | border-bottom: 0 none; 1459 | margin: 0; 1460 | } 1461 | 1462 | div.toc ul { 1463 | list-style: none outside none; 1464 | border: medium none; 1465 | padding: 0px; 1466 | } 1467 | 1468 | div.toc li.level1 { 1469 | margin-left: 0px; 1470 | } 1471 | 1472 | div.toc li.level2 { 1473 | margin-left: 15px; 1474 | } 1475 | 1476 | div.toc li.level3 { 1477 | margin-left: 30px; 1478 | } 1479 | 1480 | div.toc li.level4 { 1481 | margin-left: 45px; 1482 | } 1483 | 1484 | span.emoji { 1485 | /* font family used at the site: https://unicode.org/emoji/charts/full-emoji-list.html 1486 | * font-family: "Noto Color Emoji", "Apple Color Emoji", "Segoe UI Emoji", Times, Symbola, Aegyptus, Code2000, Code2001, Code2002, Musica, serif, LastResort; 1487 | */ 1488 | } 1489 | 1490 | .PageDocRTL-title div.toc li.level1 { 1491 | margin-left: 0 !important; 1492 | margin-right: 0; 1493 | } 1494 | 1495 | .PageDocRTL-title div.toc li.level2 { 1496 | margin-left: 0 !important; 1497 | margin-right: 15px; 1498 | } 1499 | 1500 | .PageDocRTL-title div.toc li.level3 { 1501 | margin-left: 0 !important; 1502 | margin-right: 30px; 1503 | } 1504 | 1505 | .PageDocRTL-title div.toc li.level4 { 1506 | margin-left: 0 !important; 1507 | margin-right: 45px; 1508 | } 1509 | 1510 | .inherit_header { 1511 | font-weight: bold; 1512 | color: gray; 1513 | cursor: pointer; 1514 | -webkit-touch-callout: none; 1515 | -webkit-user-select: none; 1516 | -khtml-user-select: none; 1517 | -moz-user-select: none; 1518 | -ms-user-select: none; 1519 | user-select: none; 1520 | } 1521 | 1522 | .inherit_header td { 1523 | padding: 6px 0px 2px 5px; 1524 | } 1525 | 1526 | .inherit { 1527 | display: none; 1528 | } 1529 | 1530 | tr.heading h2 { 1531 | margin-top: 12px; 1532 | margin-bottom: 4px; 1533 | } 1534 | 1535 | /* tooltip related style info */ 1536 | 1537 | .ttc { 1538 | position: absolute; 1539 | display: none; 1540 | } 1541 | 1542 | #powerTip { 1543 | cursor: default; 1544 | white-space: nowrap; 1545 | background-color: white; 1546 | border: 1px solid gray; 1547 | border-radius: 4px 4px 4px 4px; 1548 | box-shadow: 1px 1px 7px gray; 1549 | display: none; 1550 | font-size: smaller; 1551 | max-width: 80%; 1552 | opacity: 0.9; 1553 | padding: 1ex 1em 1em; 1554 | position: absolute; 1555 | z-index: 2147483647; 1556 | } 1557 | 1558 | #powerTip div.ttdoc { 1559 | color: grey; 1560 | font-style: italic; 1561 | } 1562 | 1563 | #powerTip div.ttname a { 1564 | font-weight: bold; 1565 | } 1566 | 1567 | #powerTip div.ttname { 1568 | font-weight: bold; 1569 | } 1570 | 1571 | #powerTip div.ttdeci { 1572 | color: #006318; 1573 | } 1574 | 1575 | #powerTip div { 1576 | margin: 0px; 1577 | padding: 0px; 1578 | font: 12px/16px Roboto,sans-serif; 1579 | } 1580 | 1581 | #powerTip:before, #powerTip:after { 1582 | content: ""; 1583 | position: absolute; 1584 | margin: 0px; 1585 | } 1586 | 1587 | #powerTip.n:after, #powerTip.n:before, 1588 | #powerTip.s:after, #powerTip.s:before, 1589 | #powerTip.w:after, #powerTip.w:before, 1590 | #powerTip.e:after, #powerTip.e:before, 1591 | #powerTip.ne:after, #powerTip.ne:before, 1592 | #powerTip.se:after, #powerTip.se:before, 1593 | #powerTip.nw:after, #powerTip.nw:before, 1594 | #powerTip.sw:after, #powerTip.sw:before { 1595 | border: solid transparent; 1596 | content: " "; 1597 | height: 0; 1598 | width: 0; 1599 | position: absolute; 1600 | } 1601 | 1602 | #powerTip.n:after, #powerTip.s:after, 1603 | #powerTip.w:after, #powerTip.e:after, 1604 | #powerTip.nw:after, #powerTip.ne:after, 1605 | #powerTip.sw:after, #powerTip.se:after { 1606 | border-color: rgba(255, 255, 255, 0); 1607 | } 1608 | 1609 | #powerTip.n:before, #powerTip.s:before, 1610 | #powerTip.w:before, #powerTip.e:before, 1611 | #powerTip.nw:before, #powerTip.ne:before, 1612 | #powerTip.sw:before, #powerTip.se:before { 1613 | border-color: rgba(128, 128, 128, 0); 1614 | } 1615 | 1616 | #powerTip.n:after, #powerTip.n:before, 1617 | #powerTip.ne:after, #powerTip.ne:before, 1618 | #powerTip.nw:after, #powerTip.nw:before { 1619 | top: 100%; 1620 | } 1621 | 1622 | #powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { 1623 | border-top-color: #FFFFFF; 1624 | border-width: 10px; 1625 | margin: 0px -10px; 1626 | } 1627 | #powerTip.n:before { 1628 | border-top-color: #808080; 1629 | border-width: 11px; 1630 | margin: 0px -11px; 1631 | } 1632 | #powerTip.n:after, #powerTip.n:before { 1633 | left: 50%; 1634 | } 1635 | 1636 | #powerTip.nw:after, #powerTip.nw:before { 1637 | right: 14px; 1638 | } 1639 | 1640 | #powerTip.ne:after, #powerTip.ne:before { 1641 | left: 14px; 1642 | } 1643 | 1644 | #powerTip.s:after, #powerTip.s:before, 1645 | #powerTip.se:after, #powerTip.se:before, 1646 | #powerTip.sw:after, #powerTip.sw:before { 1647 | bottom: 100%; 1648 | } 1649 | 1650 | #powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { 1651 | border-bottom-color: #FFFFFF; 1652 | border-width: 10px; 1653 | margin: 0px -10px; 1654 | } 1655 | 1656 | #powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { 1657 | border-bottom-color: #808080; 1658 | border-width: 11px; 1659 | margin: 0px -11px; 1660 | } 1661 | 1662 | #powerTip.s:after, #powerTip.s:before { 1663 | left: 50%; 1664 | } 1665 | 1666 | #powerTip.sw:after, #powerTip.sw:before { 1667 | right: 14px; 1668 | } 1669 | 1670 | #powerTip.se:after, #powerTip.se:before { 1671 | left: 14px; 1672 | } 1673 | 1674 | #powerTip.e:after, #powerTip.e:before { 1675 | left: 100%; 1676 | } 1677 | #powerTip.e:after { 1678 | border-left-color: #FFFFFF; 1679 | border-width: 10px; 1680 | top: 50%; 1681 | margin-top: -10px; 1682 | } 1683 | #powerTip.e:before { 1684 | border-left-color: #808080; 1685 | border-width: 11px; 1686 | top: 50%; 1687 | margin-top: -11px; 1688 | } 1689 | 1690 | #powerTip.w:after, #powerTip.w:before { 1691 | right: 100%; 1692 | } 1693 | #powerTip.w:after { 1694 | border-right-color: #FFFFFF; 1695 | border-width: 10px; 1696 | top: 50%; 1697 | margin-top: -10px; 1698 | } 1699 | #powerTip.w:before { 1700 | border-right-color: #808080; 1701 | border-width: 11px; 1702 | top: 50%; 1703 | margin-top: -11px; 1704 | } 1705 | 1706 | @media print 1707 | { 1708 | #top { display: none; } 1709 | #side-nav { display: none; } 1710 | #nav-path { display: none; } 1711 | body { overflow:visible; } 1712 | h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } 1713 | .summary { display: none; } 1714 | .memitem { page-break-inside: avoid; } 1715 | #doc-content 1716 | { 1717 | margin-left:0 !important; 1718 | height:auto !important; 1719 | width:auto !important; 1720 | overflow:inherit; 1721 | display:inline; 1722 | } 1723 | } 1724 | 1725 | /* @group Markdown */ 1726 | 1727 | table.markdownTable { 1728 | border-collapse:collapse; 1729 | margin-top: 4px; 1730 | margin-bottom: 4px; 1731 | } 1732 | 1733 | table.markdownTable td, table.markdownTable th { 1734 | border: 1px solid #2D4068; 1735 | padding: 3px 7px 2px; 1736 | } 1737 | 1738 | table.markdownTable tr { 1739 | } 1740 | 1741 | th.markdownTableHeadLeft, th.markdownTableHeadRight, th.markdownTableHeadCenter, th.markdownTableHeadNone { 1742 | background-color: #374F7F; 1743 | color: #FFFFFF; 1744 | font-size: 110%; 1745 | padding-bottom: 4px; 1746 | padding-top: 5px; 1747 | } 1748 | 1749 | th.markdownTableHeadLeft, td.markdownTableBodyLeft { 1750 | text-align: left 1751 | } 1752 | 1753 | th.markdownTableHeadRight, td.markdownTableBodyRight { 1754 | text-align: right 1755 | } 1756 | 1757 | th.markdownTableHeadCenter, td.markdownTableBodyCenter { 1758 | text-align: center 1759 | } 1760 | 1761 | .DocNodeRTL { 1762 | text-align: right; 1763 | direction: rtl; 1764 | } 1765 | 1766 | .DocNodeLTR { 1767 | text-align: left; 1768 | direction: ltr; 1769 | } 1770 | 1771 | table.DocNodeRTL { 1772 | width: auto; 1773 | margin-right: 0; 1774 | margin-left: auto; 1775 | } 1776 | 1777 | table.DocNodeLTR { 1778 | width: auto; 1779 | margin-right: auto; 1780 | margin-left: 0; 1781 | } 1782 | 1783 | tt, code, kbd, samp 1784 | { 1785 | display: inline-block; 1786 | direction:ltr; 1787 | } 1788 | /* @end */ 1789 | 1790 | u { 1791 | text-decoration: underline; 1792 | } 1793 | 1794 | -------------------------------------------------------------------------------- /extras/doc/doxygen.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/waspinator/AccelStepper/1255ab56820746137aba3d5d788f5d0b9baf6d4a/extras/doc/doxygen.png -------------------------------------------------------------------------------- /extras/doc/files.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: File List 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |
42 |
File List
43 |
44 |
45 |
Here is a list of all documented files with brief descriptions:
46 | 47 | 48 | 49 |
 AccelStepper.h
 MultiStepper.h
50 |
51 |
52 | 53 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /extras/doc/functions.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: Class Members 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |
Here is a list of all documented class members with links to the class documentation for each member:
42 | 43 |

- _ -

51 | 52 | 53 |

- a -

64 | 65 | 66 |

- c -

74 | 75 | 76 |

- d -

96 | 97 | 98 |

- e -

103 | 104 | 105 |

- f -

119 | 120 | 121 |

- h -

129 | 130 | 131 |

- i -

136 | 137 | 138 |

- m -

156 | 157 | 158 |

- r -

177 | 178 | 179 |

- s -

241 | 242 | 243 |

- t -

248 | 249 | 250 |

- ~ -

255 |
256 | 257 | 260 | 261 | 262 | -------------------------------------------------------------------------------- /extras/doc/functions_func.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: Class Members - Functions 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |   42 | 43 |

- a -

54 | 55 | 56 |

- c -

64 | 65 | 66 |

- d -

74 | 75 | 76 |

- e -

81 | 82 | 83 |

- i -

88 | 89 | 90 |

- m -

105 | 106 | 107 |

- r -

126 | 127 | 128 |

- s -

190 | 191 | 192 |

- t -

197 | 198 | 199 |

- ~ -

204 |
205 | 206 | 209 | 210 | 211 | -------------------------------------------------------------------------------- /extras/doc/index.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | AccelStepper: AccelStepper library for Arduino 9 | 10 | 11 | 12 | 13 | 14 | 15 |
16 |
17 | 18 | 19 | 20 | 24 | 25 | 26 |
21 |
AccelStepper 22 |
23 |
27 |
28 | 29 | 30 | 31 | 32 | 38 | 39 |
40 |
41 |
42 |
AccelStepper library for Arduino
43 |
44 |
45 |

This is the Arduino AccelStepper library. It provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers.

46 |

The standard Arduino IDE includes the Stepper library (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is perfectly adequate for simple, single motor applications.

47 |

AccelStepper significantly improves on the standard Arduino Stepper library in several ways:

    48 |
  • Supports acceleration and deceleration
  • 49 |
  • Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
  • 50 |
  • Most API functions never delay() or block (unless otherwise stated)
  • 51 |
  • Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers.
  • 52 |
  • Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)
  • 53 |
  • Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
  • 54 |
  • Very slow speeds are supported
  • 55 |
  • Extensive API
  • 56 |
  • Subclass support
  • 57 |
58 |

The latest version of this documentation can be downloaded from http://www.airspayce.com/mikem/arduino/AccelStepper The version of the package that this documentation refers to can be downloaded from http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.64.zip

59 |

Example Arduino programs are included to show the main modes of use.

60 |

You can also find online help and discussion at http://groups.google.com/group/accelstepper Please use that group for all questions and discussions on this topic. Do not contact the author directly, unless it is to discuss commercial licensing. Before asking a question or reporting a bug, please read

65 |

Beginners to C++ and stepper motors in general may find this helpful:

69 |

Tested on Arduino Diecimila and Mega with arduino-0018 & arduino-0021 on OpenSuSE 11.1 and avr-libc-1.6.1-1.15, cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5. Tested on Teensy http://www.pjrc.com/teensy including Teensy 3.1 built using Arduino IDE 1.0.5 with teensyduino addon 1.18 and later.

70 |
Installation
71 |

Install in the usual way: unzip the distribution zip file to the libraries sub-folder of your sketchbook.

72 |
Theory
73 |

This code uses speed calculations as described in "Generate stepper-motor speed profiles in real time" by David Austin http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf or http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time or http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf with the exception that AccelStepper uses steps per second rather than radians per second (because we dont know the step angle of the motor) An initial step interval is calculated for the first step, based on the desired acceleration On subsequent steps, shorter step intervals are calculated based on the previous step until max speed is achieved.

74 |
Adafruit Motor Shield V2
75 |

The included examples AFMotor_* are for Adafruit Motor Shield V1 and do not work with Adafruit Motor Shield V2. See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library for examples that work with Adafruit Motor Shield V2.

76 |
Donations
77 |

This library is offered under a free GPL license for those who want to use it that way. We try hard to keep it up to date, fix bugs and to provide free support. If this library has helped you save time or money, please consider donating at http://www.airspayce.com or here:

78 |

79 |
Trademarks
80 |

AccelStepper is a trademark of AirSpayce Pty Ltd. The AccelStepper mark was first used on April 26 2010 for international trade, and is used only in relation to motor control hardware and software. It is not to be confused with any other similar marks covering other goods and services.

81 |
Copyright
82 |

This software is Copyright (C) 2010-2021 Mike McCauley. Use is subject to license conditions. The main licensing options available are GPL V3 or Commercial:

83 |
Open Source Licensing GPL V3
This is the appropriate option if you want to share the source code of your application with everyone you distribute it to, and you also want to give them the right to share who uses it. If you wish to use this software under Open Source Licensing, you must contribute all your source code to the open source community in accordance with the GPL Version 23 when your application is distributed. See https://www.gnu.org/licenses/gpl-3.0.html
84 |
Commercial Licensing
This is the appropriate option if you are creating proprietary applications and you are not prepared to distribute and share the source code of your application. To purchase a commercial license, contact info@.nosp@m.airs.nosp@m.payce.nosp@m..com
85 |
Revision History
86 |
Version
1.0 Initial release
87 |
88 | 1.1 Added speed() function to get the current speed.
89 |
90 | 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.
91 |
92 | 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1
93 |
94 | 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.
95 |
96 | 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width. Added checks for already running at max speed and skip further calcs if so.
97 |
98 | 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang. Reported by Sandy Noble. Removed redundant _lastRunTime member.
99 |
100 | 1.7 Fixed a bug where setCurrentPosition() did not always work as expected. Reported by Peter Linhart.
101 |
102 | 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon
103 |
104 | 1.9 setCurrentPosition() now also sets motor speed to 0.
105 |
106 | 1.10 Builds on Arduino 1.0
107 |
108 | 1.11 Improvments from Michael Ellison: Added optional enable line support for stepper drivers Added inversion for step/direction/enable lines for stepper drivers
109 |
110 | 1.12 Announce Google Group
111 |
112 | 1.13 Improvements to speed calculation. Cost of calculation is now less in the worst case, and more or less constant in all cases. This should result in slightly beter high speed performance, and reduce anomalous speed glitches when other steppers are accelerating. However, its hard to see how to replace the sqrt() required at the very first step from 0 speed.
113 |
114 | 1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan
115 |
116 | 1.15 Fixed a problem with runSpeedToPosition which did not correctly handle running backwards to a smaller target position. Added examples
117 |
118 | 1.16 Fixed some cases in the code where abs() was used instead of fabs().
119 |
120 | 1.17 Added example ProportionalControl
121 |
122 | 1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps without counting. reported by Friedrich, Klappenbach.
123 |
124 | 1.19 Added MotorInterfaceType and symbolic names for the number of pins to use for the motor interface. Updated examples to suit. Replaced individual pin assignment variables _pin1, _pin2 etc with array _pin[4]. _pins member changed to _interface. Added _pinInverted array to simplify pin inversion operations. Added new function setOutputPins() which sets the motor output pins. It can be overridden in order to provide, say, serial output instead of parallel output Some refactoring and code size reduction.
125 |
126 | 1.20 Improved documentation and examples to show need for correctly specifying AccelStepper::FULL4WIRE and friends.
127 |
128 | 1.21 Fixed a problem where desiredSpeed could compute the wrong step acceleration when _speed was small but non-zero. Reported by Brian Schmalz. Precompute sqrt_twoa to improve performance and max possible stepping speed
129 |
130 | 1.22 Added Bounce.pde example Fixed a problem where calling moveTo(), setMaxSpeed(), setAcceleration() more frequently than the step time, even with the same values, would interfere with speed calcs. Now a new speed is computed only if there was a change in the set value. Reported by Brian Schmalz.
131 |
132 | 1.23 Rewrite of the speed algorithms in line with http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf Now expect smoother and more linear accelerations and decelerations. The desiredSpeed() function was removed.
133 |
134 | 1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned
135 |
136 | 1.25 Now ignore attempts to set acceleration to 0.0
137 |
138 | 1.26 Fixed a problem where certina combinations of speed and accelration could cause oscillation about the target position.
139 |
140 | 1.27 Added stop() function to stop as fast as possible with current acceleration parameters. Also added new Quickstop example showing its use.
141 |
142 | 1.28 Fixed another problem where certain combinations of speed and acceleration could cause oscillation about the target position. Added support for 3 wire full and half steppers such as Hard Disk Drive spindle. Contributed by Yuri Ivatchkovitch.
143 |
144 | 1.29 Fixed a problem that could cause a DRIVER stepper to continually step with some sketches. Reported by Vadim.
145 |
146 | 1.30 Fixed a problem that could cause stepper to back up a few steps at the end of accelerated travel with certain speeds. Reported and patched by jolo.
147 |
148 | 1.31 Updated author and distribution location details to airspayce.com
149 |
150 | 1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that prevented the enable pin changing stae correctly. Reported by Duane Bishop.
151 |
152 | 1.33 Fixed an error in example AFMotor_ConstantSpeed.pde did not setMaxSpeed(); Fixed a problem that caused incorrect pin sequencing of FULL3WIRE and HALF3WIRE. Unfortunately this meant changing the signature for all step*() functions. Added example MotorShield, showing how to use AdaFruit Motor Shield to control a 3 phase motor such as a HDD spindle motor (and without using the AFMotor library.
153 |
154 | 1.34 Added setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert) to allow inversion of 2, 3 and 4 wire stepper pins. Requested by Oleg.
155 |
156 | 1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with setPinsInverted(bool, bool, bool). Reported by Mac Mac.
157 |
158 | 1.36 Changed enableOutputs() and disableOutputs() to be virtual so can be overridden. Added new optional argument 'enable' to constructor, which allows you toi disable the automatic enabling of outputs at construction time. Suggested by Guido.
159 |
160 | 1.37 Fixed a problem with step1 that could cause a rogue step in the wrong direction (or not, depending on the setup-time requirements of the connected hardware). Reported by Mark Tillotson.
161 |
162 | 1.38 run() function incorrectly always returned true. Updated function and doc so it returns true if the motor is still running to the target position.
163 |
164 | 1.39 Updated typos in keywords.txt, courtesey Jon Magill.
165 |
166 | 1.40 Updated documentation, including testing on Teensy 3.1
167 |
168 | 1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value
169 |
170 | 1.42 Improved support for FULL3WIRE and HALF3WIRE output pins. These changes were in Yuri's original contribution but did not make it into production.
171 |
172 |
173 | 1.43 Added DualMotorShield example. Shows how to use AccelStepper to control 2 x 2 phase steppers using the Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.
174 |
175 |
176 | 1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde was missing from the distribution.
177 |
178 |
179 | 1.45 Fixed a problem where if setAcceleration was not called, there was no default acceleration. Reported by Michael Newman.
180 |
181 |
182 | 1.45 Fixed inaccuracy in acceleration rate by using Equation 15, suggested by Sebastian Gracki.
183 | Performance improvements in runSpeed suggested by Jaakko Fagerlund.
184 |
185 |
186 | 1.46 Fixed error in documentation for runToPosition(). Reinstated time calculations in runSpeed() since new version is reported not to work correctly under some circumstances. Reported by Oleg V Gavva.
187 |
188 |
189 | 1.48 2015-08-25 Added new class MultiStepper that can manage multiple AccelSteppers, and cause them all to move to selected positions at such a (constant) speed that they all arrive at their target position at the same time. Suitable for X-Y flatbeds etc.
190 | Added new method maxSpeed() to AccelStepper to return the currently configured maxSpeed.
191 |
192 |
193 | 1.49 2016-01-02 Testing with VID28 series instrument stepper motors and EasyDriver. OK, although with light pointers and slow speeds like 180 full steps per second the motor movement can be erratic, probably due to some mechanical resonance. Best to accelerate through this speed.
194 | Added isRunning().
195 |
196 |
197 | 1.50 2016-02-25 AccelStepper::disableOutputs now sets the enable pion to OUTPUT mode if the enable pin is defined. Patch from Piet De Jong.
198 | Added notes about the fact that AFMotor_* examples do not work with Adafruit Motor Shield V2.
199 |
200 |
201 | 1.51 2016-03-24 Fixed a problem reported by gregor: when resetting the stepper motor position using setCurrentPosition() the stepper speed is reset by setting _stepInterval to 0, but _speed is not reset. this results in the stepper motor not starting again when calling setSpeed() with the same speed the stepper was set to before.
202 |
203 | 1.52 2016-08-09 Added MultiStepper to keywords.txt. Improvements to efficiency of AccelStepper::runSpeed() as suggested by David Grayson. Improvements to speed accuracy as suggested by David Grayson.
204 |
205 | 1.53 2016-08-14 Backed out Improvements to speed accuracy from 1.52 as it did not work correctly.
206 |
207 | 1.54 2017-01-24 Fixed some warnings about unused arguments.
208 |
209 | 1.55 2017-01-25 Fixed another warning in MultiStepper.cpp
210 |
211 | 1.56 2017-02-03 Fixed minor documentation error with DIRECTION_CCW and DIRECTION_CW. Reported by David Mutterer. Added link to Binpress commercial license purchasing.
212 |
213 | 1.57 2017-03-28 _direction moved to protected at the request of Rudy Ercek. setMaxSpeed() and setAcceleration() now correct negative values to be positive.
214 |
215 | 1.58 2018-04-13 Add initialisation for _enableInverted in constructor.
216 |
217 | 1.59 2018-08-28 Update commercial licensing, remove binpress.
218 |
219 | 1.60 2020-03-07 Release under GPL V3
220 |
221 | 1.61 2020-04-20 Added yield() call in runToPosition(), so that platforms like esp8266 dont hang/crash during long runs.
222 |
223 | 1.62 2022-05-22 Added link to AccelStepper - The Missing Manual.
224 | Fixed a problem when setting the maxSpeed to 1.0 due to incomplete initialisation. Reported by Olivier Pécheux.
225 |
226 |
227 | 1.63 2022-06-30 Added virtual destructor at the request of Jan.
228 |
229 |
230 | 1.64 2022-10-31 Patch courtesy acwest: Changes to make AccelStepper more subclassable. These changes are largely oriented to implementing new step-scheduling algorithms.
231 |
Author
Mike McCauley (mikem.nosp@m.@air.nosp@m.spayc.nosp@m.e.co.nosp@m.m) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE GOOGLE GROUP
232 |
233 |
234 | 235 | 238 | 239 | 240 | -------------------------------------------------------------------------------- /extras/doc/tab_b.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/waspinator/AccelStepper/1255ab56820746137aba3d5d788f5d0b9baf6d4a/extras/doc/tab_b.gif -------------------------------------------------------------------------------- /extras/doc/tab_l.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/waspinator/AccelStepper/1255ab56820746137aba3d5d788f5d0b9baf6d4a/extras/doc/tab_l.gif -------------------------------------------------------------------------------- /extras/doc/tab_r.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/waspinator/AccelStepper/1255ab56820746137aba3d5d788f5d0b9baf6d4a/extras/doc/tab_r.gif -------------------------------------------------------------------------------- /extras/doc/tabs.css: -------------------------------------------------------------------------------- 1 | .sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0px/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.sm-dox{background-image:url("tab_b.png")}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0px 12px;padding-right:43px;font-family:"Lucida Grande","Geneva","Helvetica",Arial,sans-serif;font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:0px 1px 1px rgba(255,255,255,0.9);color:#283A5D;outline:none}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox a.current{color:#D23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:rgba(255,255,255,0.5);border-radius:5px}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{border-radius:0}.sm-dox ul{background:rgba(162,162,162,0.1)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:white;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media (min-width: 768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:url("tab_b.png");line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:#283A5D transparent transparent transparent;background:transparent;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0px 12px;background-image:url("tab_s.png");background-repeat:no-repeat;background-position:right;border-radius:0 !important}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox a:hover span.sub-arrow{border-color:#fff transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent #fff transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:#fff;border-radius:5px !important;box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent #555;border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:#555;background-image:none;border:0 !important;color:#555;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent #fff}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:#fff;height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #D23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#D23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent #555 transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:#555 transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:url("tab_b.png")}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:#fff}} 2 | -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For AccelStepper 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | AccelStepper KEYWORD1 10 | MultiStepper KEYWORD1 11 | 12 | ####################################### 13 | # Methods and Functions (KEYWORD2) 14 | ####################################### 15 | 16 | moveTo KEYWORD2 17 | move KEYWORD2 18 | run KEYWORD2 19 | runSpeed KEYWORD2 20 | setMaxSpeed KEYWORD2 21 | setAcceleration KEYWORD2 22 | setSpeed KEYWORD2 23 | speed KEYWORD2 24 | distanceToGo KEYWORD2 25 | targetPosition KEYWORD2 26 | currentPosition KEYWORD2 27 | setCurrentPosition KEYWORD2 28 | runToPosition KEYWORD2 29 | runSpeedToPosition KEYWORD2 30 | runToNewPosition KEYWORD2 31 | stop KEYWORD2 32 | disableOutputs KEYWORD2 33 | enableOutputs KEYWORD2 34 | setMinPulseWidth KEYWORD2 35 | setEnablePin KEYWORD2 36 | setPinsInverted KEYWORD2 37 | maxSpeed KEYWORD2 38 | isRunning KEYWORD2 39 | ####################################### 40 | # Constants (LITERAL1) 41 | ####################################### 42 | 43 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=AccelStepper 2 | version=1.64 3 | author=Mike McCauley 4 | maintainer=Patrick Wasp 5 | sentence=Allows Arduino boards to control a variety of stepper motors. 6 | paragraph=Provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers. 7 | category=Device Control 8 | url=http://www.airspayce.com/mikem/arduino/AccelStepper/ 9 | architectures=* 10 | -------------------------------------------------------------------------------- /src/AccelStepper.cpp: -------------------------------------------------------------------------------- 1 | // AccelStepper.cpp 2 | // 3 | // Copyright (C) 2009-2020 Mike McCauley 4 | // $Id: AccelStepper.cpp,v 1.24 2020/04/20 00:15:03 mikem Exp mikem $ 5 | 6 | #include "AccelStepper.h" 7 | 8 | #if 0 9 | // Some debugging assistance 10 | void dump(uint8_t* p, int l) 11 | { 12 | int i; 13 | 14 | for (i = 0; i < l; i++) 15 | { 16 | Serial.print(p[i], HEX); 17 | Serial.print(" "); 18 | } 19 | Serial.println(""); 20 | } 21 | #endif 22 | 23 | void AccelStepper::moveTo(long absolute) 24 | { 25 | if (_targetPos != absolute) 26 | { 27 | _targetPos = absolute; 28 | computeNewSpeed(); 29 | // compute new n? 30 | } 31 | } 32 | 33 | void AccelStepper::move(long relative) 34 | { 35 | moveTo(_currentPos + relative); 36 | } 37 | 38 | // Implements steps according to the current step interval 39 | // You must call this at least once per step 40 | // returns true if a step occurred 41 | boolean AccelStepper::runSpeed() 42 | { 43 | // Dont do anything unless we actually have a step interval 44 | if (!_stepInterval) 45 | return false; 46 | 47 | unsigned long time = micros(); 48 | if (time - _lastStepTime >= _stepInterval) 49 | { 50 | if (_direction == DIRECTION_CW) 51 | { 52 | // Clockwise 53 | _currentPos += 1; 54 | } 55 | else 56 | { 57 | // Anticlockwise 58 | _currentPos -= 1; 59 | } 60 | step(_currentPos); 61 | 62 | _lastStepTime = time; // Caution: does not account for costs in step() 63 | 64 | return true; 65 | } 66 | else 67 | { 68 | return false; 69 | } 70 | } 71 | 72 | long AccelStepper::distanceToGo() 73 | { 74 | return _targetPos - _currentPos; 75 | } 76 | 77 | long AccelStepper::targetPosition() 78 | { 79 | return _targetPos; 80 | } 81 | 82 | long AccelStepper::currentPosition() 83 | { 84 | return _currentPos; 85 | } 86 | 87 | // Useful during initialisations or after initial positioning 88 | // Sets speed to 0 89 | void AccelStepper::setCurrentPosition(long position) 90 | { 91 | _targetPos = _currentPos = position; 92 | _n = 0; 93 | _stepInterval = 0; 94 | _speed = 0.0; 95 | } 96 | 97 | // Subclasses can override 98 | unsigned long AccelStepper::computeNewSpeed() 99 | { 100 | long distanceTo = distanceToGo(); // +ve is clockwise from curent location 101 | 102 | long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16 103 | 104 | if (distanceTo == 0 && stepsToStop <= 1) 105 | { 106 | // We are at the target and its time to stop 107 | _stepInterval = 0; 108 | _speed = 0.0; 109 | _n = 0; 110 | return _stepInterval; 111 | } 112 | 113 | if (distanceTo > 0) 114 | { 115 | // We are anticlockwise from the target 116 | // Need to go clockwise from here, maybe decelerate now 117 | if (_n > 0) 118 | { 119 | // Currently accelerating, need to decel now? Or maybe going the wrong way? 120 | if ((stepsToStop >= distanceTo) || _direction == DIRECTION_CCW) 121 | _n = -stepsToStop; // Start deceleration 122 | } 123 | else if (_n < 0) 124 | { 125 | // Currently decelerating, need to accel again? 126 | if ((stepsToStop < distanceTo) && _direction == DIRECTION_CW) 127 | _n = -_n; // Start accceleration 128 | } 129 | } 130 | else if (distanceTo < 0) 131 | { 132 | // We are clockwise from the target 133 | // Need to go anticlockwise from here, maybe decelerate 134 | if (_n > 0) 135 | { 136 | // Currently accelerating, need to decel now? Or maybe going the wrong way? 137 | if ((stepsToStop >= -distanceTo) || _direction == DIRECTION_CW) 138 | _n = -stepsToStop; // Start deceleration 139 | } 140 | else if (_n < 0) 141 | { 142 | // Currently decelerating, need to accel again? 143 | if ((stepsToStop < -distanceTo) && _direction == DIRECTION_CCW) 144 | _n = -_n; // Start accceleration 145 | } 146 | } 147 | 148 | // Need to accelerate or decelerate 149 | if (_n == 0) 150 | { 151 | // First step from stopped 152 | _cn = _c0; 153 | _direction = (distanceTo > 0) ? DIRECTION_CW : DIRECTION_CCW; 154 | } 155 | else 156 | { 157 | // Subsequent step. Works for accel (n is +_ve) and decel (n is -ve). 158 | _cn = _cn - ((2.0 * _cn) / ((4.0 * _n) + 1)); // Equation 13 159 | _cn = max(_cn, _cmin); 160 | } 161 | _n++; 162 | _stepInterval = _cn; 163 | _speed = 1000000.0 / _cn; 164 | if (_direction == DIRECTION_CCW) 165 | _speed = -_speed; 166 | 167 | #if 0 168 | Serial.println(_speed); 169 | Serial.println(_acceleration); 170 | Serial.println(_cn); 171 | Serial.println(_c0); 172 | Serial.println(_n); 173 | Serial.println(_stepInterval); 174 | Serial.println(distanceTo); 175 | Serial.println(stepsToStop); 176 | Serial.println("-----"); 177 | #endif 178 | return _stepInterval; 179 | } 180 | 181 | // Run the motor to implement speed and acceleration in order to proceed to the target position 182 | // You must call this at least once per step, preferably in your main loop 183 | // If the motor is in the desired position, the cost is very small 184 | // returns true if the motor is still running to the target position. 185 | boolean AccelStepper::run() 186 | { 187 | if (runSpeed()) 188 | computeNewSpeed(); 189 | return _speed != 0.0 || distanceToGo() != 0; 190 | } 191 | 192 | AccelStepper::AccelStepper(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4, bool enable) 193 | { 194 | _interface = interface; 195 | _currentPos = 0; 196 | _targetPos = 0; 197 | _speed = 0.0; 198 | _maxSpeed = 0.0; 199 | _acceleration = 0.0; 200 | _sqrt_twoa = 1.0; 201 | _stepInterval = 0; 202 | _minPulseWidth = 1; 203 | _enablePin = 0xff; 204 | _lastStepTime = 0; 205 | _pin[0] = pin1; 206 | _pin[1] = pin2; 207 | _pin[2] = pin3; 208 | _pin[3] = pin4; 209 | _enableInverted = false; 210 | 211 | // NEW 212 | _n = 0; 213 | _c0 = 0.0; 214 | _cn = 0.0; 215 | _cmin = 1.0; 216 | _direction = DIRECTION_CCW; 217 | 218 | int i; 219 | for (i = 0; i < 4; i++) 220 | _pinInverted[i] = 0; 221 | if (enable) 222 | enableOutputs(); 223 | // Some reasonable default 224 | setAcceleration(1); 225 | setMaxSpeed(1); 226 | } 227 | 228 | AccelStepper::AccelStepper(void (*forward)(), void (*backward)()) 229 | { 230 | _interface = 0; 231 | _currentPos = 0; 232 | _targetPos = 0; 233 | _speed = 0.0; 234 | _maxSpeed = 0.0; 235 | _acceleration = 0.0; 236 | _sqrt_twoa = 1.0; 237 | _stepInterval = 0; 238 | _minPulseWidth = 1; 239 | _enablePin = 0xff; 240 | _lastStepTime = 0; 241 | _pin[0] = 0; 242 | _pin[1] = 0; 243 | _pin[2] = 0; 244 | _pin[3] = 0; 245 | _forward = forward; 246 | _backward = backward; 247 | 248 | // NEW 249 | _n = 0; 250 | _c0 = 0.0; 251 | _cn = 0.0; 252 | _cmin = 1.0; 253 | _direction = DIRECTION_CCW; 254 | 255 | int i; 256 | for (i = 0; i < 4; i++) 257 | _pinInverted[i] = 0; 258 | // Some reasonable default 259 | setAcceleration(1); 260 | setMaxSpeed(1); 261 | } 262 | 263 | void AccelStepper::setMaxSpeed(float speed) 264 | { 265 | if (speed < 0.0) 266 | speed = -speed; 267 | if (_maxSpeed != speed) 268 | { 269 | _maxSpeed = speed; 270 | _cmin = 1000000.0 / speed; 271 | // Recompute _n from current speed and adjust speed if accelerating or cruising 272 | if (_n > 0) 273 | { 274 | _n = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16 275 | computeNewSpeed(); 276 | } 277 | } 278 | } 279 | 280 | float AccelStepper::maxSpeed() 281 | { 282 | return _maxSpeed; 283 | } 284 | 285 | void AccelStepper::setAcceleration(float acceleration) 286 | { 287 | if (acceleration == 0.0) 288 | return; 289 | if (acceleration < 0.0) 290 | acceleration = -acceleration; 291 | if (_acceleration != acceleration) 292 | { 293 | // Recompute _n per Equation 17 294 | _n = _n * (_acceleration / acceleration); 295 | // New c0 per Equation 7, with correction per Equation 15 296 | _c0 = 0.676 * sqrt(2.0 / acceleration) * 1000000.0; // Equation 15 297 | _acceleration = acceleration; 298 | computeNewSpeed(); 299 | } 300 | } 301 | 302 | float AccelStepper::acceleration() 303 | { 304 | return _acceleration; 305 | } 306 | 307 | void AccelStepper::setSpeed(float speed) 308 | { 309 | if (speed == _speed) 310 | return; 311 | speed = constrain(speed, -_maxSpeed, _maxSpeed); 312 | if (speed == 0.0) 313 | _stepInterval = 0; 314 | else 315 | { 316 | _stepInterval = fabs(1000000.0 / speed); 317 | _direction = (speed > 0.0) ? DIRECTION_CW : DIRECTION_CCW; 318 | } 319 | _speed = speed; 320 | } 321 | 322 | float AccelStepper::speed() 323 | { 324 | return _speed; 325 | } 326 | 327 | // Subclasses can override 328 | void AccelStepper::step(long step) 329 | { 330 | switch (_interface) 331 | { 332 | case FUNCTION: 333 | step0(step); 334 | break; 335 | 336 | case DRIVER: 337 | step1(step); 338 | break; 339 | 340 | case FULL2WIRE: 341 | step2(step); 342 | break; 343 | 344 | case FULL3WIRE: 345 | step3(step); 346 | break; 347 | 348 | case FULL4WIRE: 349 | step4(step); 350 | break; 351 | 352 | case HALF3WIRE: 353 | step6(step); 354 | break; 355 | 356 | case HALF4WIRE: 357 | step8(step); 358 | break; 359 | } 360 | } 361 | 362 | long AccelStepper::stepForward() 363 | { 364 | // Clockwise 365 | _currentPos += 1; 366 | step(_currentPos); 367 | _lastStepTime = micros(); 368 | return _currentPos; 369 | } 370 | 371 | long AccelStepper::stepBackward() 372 | { 373 | // Counter-clockwise 374 | _currentPos -= 1; 375 | step(_currentPos); 376 | _lastStepTime = micros(); 377 | return _currentPos; 378 | } 379 | 380 | // You might want to override this to implement eg serial output 381 | // bit 0 of the mask corresponds to _pin[0] 382 | // bit 1 of the mask corresponds to _pin[1] 383 | // .... 384 | void AccelStepper::setOutputPins(uint8_t mask) 385 | { 386 | uint8_t numpins = 2; 387 | if (_interface == FULL4WIRE || _interface == HALF4WIRE) 388 | numpins = 4; 389 | else if (_interface == FULL3WIRE || _interface == HALF3WIRE) 390 | numpins = 3; 391 | uint8_t i; 392 | for (i = 0; i < numpins; i++) 393 | digitalWrite(_pin[i], (mask & (1 << i)) ? (HIGH ^ _pinInverted[i]) : (LOW ^ _pinInverted[i])); 394 | } 395 | 396 | // 0 pin step function (ie for functional usage) 397 | void AccelStepper::step0(long step) 398 | { 399 | (void)(step); // Unused 400 | if (_speed > 0) 401 | _forward(); 402 | else 403 | _backward(); 404 | } 405 | 406 | // 1 pin step function (ie for stepper drivers) 407 | // This is passed the current step number (0 to 7) 408 | // Subclasses can override 409 | void AccelStepper::step1(long step) 410 | { 411 | (void)(step); // Unused 412 | 413 | // _pin[0] is step, _pin[1] is direction 414 | setOutputPins(_direction ? 0b10 : 0b00); // Set direction first else get rogue pulses 415 | setOutputPins(_direction ? 0b11 : 0b01); // step HIGH 416 | // Caution 200ns setup time 417 | // Delay the minimum allowed pulse width 418 | delayMicroseconds(_minPulseWidth); 419 | setOutputPins(_direction ? 0b10 : 0b00); // step LOW 420 | } 421 | 422 | 423 | // 2 pin step function 424 | // This is passed the current step number (0 to 7) 425 | // Subclasses can override 426 | void AccelStepper::step2(long step) 427 | { 428 | switch (step & 0x3) 429 | { 430 | case 0: /* 01 */ 431 | setOutputPins(0b10); 432 | break; 433 | 434 | case 1: /* 11 */ 435 | setOutputPins(0b11); 436 | break; 437 | 438 | case 2: /* 10 */ 439 | setOutputPins(0b01); 440 | break; 441 | 442 | case 3: /* 00 */ 443 | setOutputPins(0b00); 444 | break; 445 | } 446 | } 447 | // 3 pin step function 448 | // This is passed the current step number (0 to 7) 449 | // Subclasses can override 450 | void AccelStepper::step3(long step) 451 | { 452 | switch (step % 3) 453 | { 454 | case 0: // 100 455 | setOutputPins(0b100); 456 | break; 457 | 458 | case 1: // 001 459 | setOutputPins(0b001); 460 | break; 461 | 462 | case 2: //010 463 | setOutputPins(0b010); 464 | break; 465 | 466 | } 467 | } 468 | 469 | // 4 pin step function for half stepper 470 | // This is passed the current step number (0 to 7) 471 | // Subclasses can override 472 | void AccelStepper::step4(long step) 473 | { 474 | switch (step & 0x3) 475 | { 476 | case 0: // 1010 477 | setOutputPins(0b0101); 478 | break; 479 | 480 | case 1: // 0110 481 | setOutputPins(0b0110); 482 | break; 483 | 484 | case 2: //0101 485 | setOutputPins(0b1010); 486 | break; 487 | 488 | case 3: //1001 489 | setOutputPins(0b1001); 490 | break; 491 | } 492 | } 493 | 494 | // 3 pin half step function 495 | // This is passed the current step number (0 to 7) 496 | // Subclasses can override 497 | void AccelStepper::step6(long step) 498 | { 499 | switch (step % 6) 500 | { 501 | case 0: // 100 502 | setOutputPins(0b100); 503 | break; 504 | 505 | case 1: // 101 506 | setOutputPins(0b101); 507 | break; 508 | 509 | case 2: // 001 510 | setOutputPins(0b001); 511 | break; 512 | 513 | case 3: // 011 514 | setOutputPins(0b011); 515 | break; 516 | 517 | case 4: // 010 518 | setOutputPins(0b010); 519 | break; 520 | 521 | case 5: // 011 522 | setOutputPins(0b110); 523 | break; 524 | 525 | } 526 | } 527 | 528 | // 4 pin half step function 529 | // This is passed the current step number (0 to 7) 530 | // Subclasses can override 531 | void AccelStepper::step8(long step) 532 | { 533 | switch (step & 0x7) 534 | { 535 | case 0: // 1000 536 | setOutputPins(0b0001); 537 | break; 538 | 539 | case 1: // 1010 540 | setOutputPins(0b0101); 541 | break; 542 | 543 | case 2: // 0010 544 | setOutputPins(0b0100); 545 | break; 546 | 547 | case 3: // 0110 548 | setOutputPins(0b0110); 549 | break; 550 | 551 | case 4: // 0100 552 | setOutputPins(0b0010); 553 | break; 554 | 555 | case 5: //0101 556 | setOutputPins(0b1010); 557 | break; 558 | 559 | case 6: // 0001 560 | setOutputPins(0b1000); 561 | break; 562 | 563 | case 7: //1001 564 | setOutputPins(0b1001); 565 | break; 566 | } 567 | } 568 | 569 | // Prevents power consumption on the outputs 570 | void AccelStepper::disableOutputs() 571 | { 572 | if (! _interface) return; 573 | 574 | setOutputPins(0); // Handles inversion automatically 575 | if (_enablePin != 0xff) 576 | { 577 | pinMode(_enablePin, OUTPUT); 578 | digitalWrite(_enablePin, LOW ^ _enableInverted); 579 | } 580 | } 581 | 582 | void AccelStepper::enableOutputs() 583 | { 584 | if (! _interface) 585 | return; 586 | 587 | pinMode(_pin[0], OUTPUT); 588 | pinMode(_pin[1], OUTPUT); 589 | if (_interface == FULL4WIRE || _interface == HALF4WIRE) 590 | { 591 | pinMode(_pin[2], OUTPUT); 592 | pinMode(_pin[3], OUTPUT); 593 | } 594 | else if (_interface == FULL3WIRE || _interface == HALF3WIRE) 595 | { 596 | pinMode(_pin[2], OUTPUT); 597 | } 598 | 599 | if (_enablePin != 0xff) 600 | { 601 | pinMode(_enablePin, OUTPUT); 602 | digitalWrite(_enablePin, HIGH ^ _enableInverted); 603 | } 604 | } 605 | 606 | void AccelStepper::setMinPulseWidth(unsigned int minWidth) 607 | { 608 | _minPulseWidth = minWidth; 609 | } 610 | 611 | void AccelStepper::setEnablePin(uint8_t enablePin) 612 | { 613 | _enablePin = enablePin; 614 | 615 | // This happens after construction, so init pin now. 616 | if (_enablePin != 0xff) 617 | { 618 | pinMode(_enablePin, OUTPUT); 619 | digitalWrite(_enablePin, HIGH ^ _enableInverted); 620 | } 621 | } 622 | 623 | void AccelStepper::setPinsInverted(bool directionInvert, bool stepInvert, bool enableInvert) 624 | { 625 | _pinInverted[0] = stepInvert; 626 | _pinInverted[1] = directionInvert; 627 | _enableInverted = enableInvert; 628 | } 629 | 630 | void AccelStepper::setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert) 631 | { 632 | _pinInverted[0] = pin1Invert; 633 | _pinInverted[1] = pin2Invert; 634 | _pinInverted[2] = pin3Invert; 635 | _pinInverted[3] = pin4Invert; 636 | _enableInverted = enableInvert; 637 | } 638 | 639 | // Blocks until the target position is reached and stopped 640 | void AccelStepper::runToPosition() 641 | { 642 | while (run()) 643 | YIELD; // Let system housekeeping occur 644 | } 645 | 646 | boolean AccelStepper::runSpeedToPosition() 647 | { 648 | if (_targetPos == _currentPos) 649 | return false; 650 | if (_targetPos >_currentPos) 651 | _direction = DIRECTION_CW; 652 | else 653 | _direction = DIRECTION_CCW; 654 | return runSpeed(); 655 | } 656 | 657 | // Blocks until the new target position is reached 658 | void AccelStepper::runToNewPosition(long position) 659 | { 660 | moveTo(position); 661 | runToPosition(); 662 | } 663 | 664 | void AccelStepper::stop() 665 | { 666 | if (_speed != 0.0) 667 | { 668 | long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)) + 1; // Equation 16 (+integer rounding) 669 | if (_speed > 0) 670 | move(stepsToStop); 671 | else 672 | move(-stepsToStop); 673 | } 674 | } 675 | 676 | bool AccelStepper::isRunning() 677 | { 678 | return !(_speed == 0.0 && _targetPos == _currentPos); 679 | } 680 | -------------------------------------------------------------------------------- /src/AccelStepper.h: -------------------------------------------------------------------------------- 1 | // AccelStepper.h 2 | // 3 | /// \mainpage AccelStepper library for Arduino 4 | /// 5 | /// This is the Arduino AccelStepper library. 6 | /// It provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers. 7 | /// 8 | /// The standard Arduino IDE includes the Stepper library 9 | /// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is 10 | /// perfectly adequate for simple, single motor applications. 11 | /// 12 | /// AccelStepper significantly improves on the standard Arduino Stepper library in several ways: 13 | /// \li Supports acceleration and deceleration 14 | /// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper 15 | /// \li Most API functions never delay() or block (unless otherwise stated) 16 | /// \li Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers. 17 | /// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library) 18 | /// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip) 19 | /// \li Very slow speeds are supported 20 | /// \li Extensive API 21 | /// \li Subclass support 22 | /// 23 | /// The latest version of this documentation can be downloaded from 24 | /// http://www.airspayce.com/mikem/arduino/AccelStepper 25 | /// The version of the package that this documentation refers to can be downloaded 26 | /// from http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.64.zip 27 | /// 28 | /// Example Arduino programs are included to show the main modes of use. 29 | /// 30 | /// You can also find online help and discussion at http://groups.google.com/group/accelstepper 31 | /// Please use that group for all questions and discussions on this topic. 32 | /// Do not contact the author directly, unless it is to discuss commercial licensing. 33 | /// Before asking a question or reporting a bug, please read 34 | /// - http://en.wikipedia.org/wiki/Wikipedia:Reference_desk/How_to_ask_a_software_question 35 | /// - http://www.catb.org/esr/faqs/smart-questions.html 36 | /// - http://www.chiark.greenend.org.uk/~shgtatham/bugs.html 37 | /// 38 | /// Beginners to C++ and stepper motors in general may find this helpful: 39 | /// - https://hackaday.io/project/183279-accelstepper-the-missing-manual 40 | /// - https://hackaday.io/project/183713-using-the-arduino-accelstepper-library 41 | /// 42 | /// Tested on Arduino Diecimila and Mega with arduino-0018 & arduino-0021 43 | /// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15, 44 | /// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5. 45 | /// Tested on Teensy http://www.pjrc.com/teensy including Teensy 3.1 built using Arduino IDE 1.0.5 with 46 | /// teensyduino addon 1.18 and later. 47 | /// 48 | /// \par Installation 49 | /// 50 | /// Install in the usual way: unzip the distribution zip file to the libraries 51 | /// sub-folder of your sketchbook. 52 | /// 53 | /// \par Theory 54 | /// 55 | /// This code uses speed calculations as described in 56 | /// "Generate stepper-motor speed profiles in real time" by David Austin 57 | /// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf or 58 | /// http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time or 59 | /// http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf 60 | /// with the exception that AccelStepper uses steps per second rather than radians per second 61 | /// (because we dont know the step angle of the motor) 62 | /// An initial step interval is calculated for the first step, based on the desired acceleration 63 | /// On subsequent steps, shorter step intervals are calculated based 64 | /// on the previous step until max speed is achieved. 65 | /// 66 | /// \par Adafruit Motor Shield V2 67 | /// 68 | /// The included examples AFMotor_* are for Adafruit Motor Shield V1 and do not work with Adafruit Motor Shield V2. 69 | /// See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library for examples that work with Adafruit Motor Shield V2. 70 | /// 71 | /// \par Donations 72 | /// 73 | /// This library is offered under a free GPL license for those who want to use it that way. 74 | /// We try hard to keep it up to date, fix bugs 75 | /// and to provide free support. If this library has helped you save time or money, please consider donating at 76 | /// http://www.airspayce.com or here: 77 | /// 78 | /// \htmlonly
\endhtmlonly 79 | /// 80 | /// \par Trademarks 81 | /// 82 | /// AccelStepper is a trademark of AirSpayce Pty Ltd. The AccelStepper mark was first used on April 26 2010 for 83 | /// international trade, and is used only in relation to motor control hardware and software. 84 | /// It is not to be confused with any other similar marks covering other goods and services. 85 | /// 86 | /// \par Copyright 87 | /// 88 | /// This software is Copyright (C) 2010-2021 Mike McCauley. Use is subject to license 89 | /// conditions. The main licensing options available are GPL V3 or Commercial: 90 | /// 91 | /// \par Open Source Licensing GPL V3 92 | /// This is the appropriate option if you want to share the source code of your 93 | /// application with everyone you distribute it to, and you also want to give them 94 | /// the right to share who uses it. If you wish to use this software under Open 95 | /// Source Licensing, you must contribute all your source code to the open source 96 | /// community in accordance with the GPL Version 23 when your application is 97 | /// distributed. See https://www.gnu.org/licenses/gpl-3.0.html 98 | /// 99 | /// \par Commercial Licensing 100 | /// This is the appropriate option if you are creating proprietary applications 101 | /// and you are not prepared to distribute and share the source code of your 102 | /// application. To purchase a commercial license, contact info@airspayce.com 103 | /// 104 | /// \par Revision History 105 | /// \version 1.0 Initial release 106 | /// 107 | /// \version 1.1 Added speed() function to get the current speed. 108 | /// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt. 109 | /// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1 110 | /// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches. 111 | /// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements 112 | /// to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width. 113 | /// Added checks for already running at max speed and skip further calcs if so. 114 | /// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang. 115 | /// Reported by Sandy Noble. 116 | /// Removed redundant _lastRunTime member. 117 | /// \version 1.7 Fixed a bug where setCurrentPosition() did not always work as expected. 118 | /// Reported by Peter Linhart. 119 | /// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon 120 | /// \version 1.9 setCurrentPosition() now also sets motor speed to 0. 121 | /// \version 1.10 Builds on Arduino 1.0 122 | /// \version 1.11 Improvments from Michael Ellison: 123 | /// Added optional enable line support for stepper drivers 124 | /// Added inversion for step/direction/enable lines for stepper drivers 125 | /// \version 1.12 Announce Google Group 126 | /// \version 1.13 Improvements to speed calculation. Cost of calculation is now less in the worst case, 127 | /// and more or less constant in all cases. This should result in slightly beter high speed performance, and 128 | /// reduce anomalous speed glitches when other steppers are accelerating. 129 | /// However, its hard to see how to replace the sqrt() required at the very first step from 0 speed. 130 | /// \version 1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan 131 | /// \version 1.15 Fixed a problem with runSpeedToPosition which did not correctly handle 132 | /// running backwards to a smaller target position. Added examples 133 | /// \version 1.16 Fixed some cases in the code where abs() was used instead of fabs(). 134 | /// \version 1.17 Added example ProportionalControl 135 | /// \version 1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps 136 | /// without counting. reported by Friedrich, Klappenbach. 137 | /// \version 1.19 Added MotorInterfaceType and symbolic names for the number of pins to use 138 | /// for the motor interface. Updated examples to suit. 139 | /// Replaced individual pin assignment variables _pin1, _pin2 etc with array _pin[4]. 140 | /// _pins member changed to _interface. 141 | /// Added _pinInverted array to simplify pin inversion operations. 142 | /// Added new function setOutputPins() which sets the motor output pins. 143 | /// It can be overridden in order to provide, say, serial output instead of parallel output 144 | /// Some refactoring and code size reduction. 145 | /// \version 1.20 Improved documentation and examples to show need for correctly 146 | /// specifying AccelStepper::FULL4WIRE and friends. 147 | /// \version 1.21 Fixed a problem where desiredSpeed could compute the wrong step acceleration 148 | /// when _speed was small but non-zero. Reported by Brian Schmalz. 149 | /// Precompute sqrt_twoa to improve performance and max possible stepping speed 150 | /// \version 1.22 Added Bounce.pde example 151 | /// Fixed a problem where calling moveTo(), setMaxSpeed(), setAcceleration() more 152 | /// frequently than the step time, even 153 | /// with the same values, would interfere with speed calcs. Now a new speed is computed 154 | /// only if there was a change in the set value. Reported by Brian Schmalz. 155 | /// \version 1.23 Rewrite of the speed algorithms in line with 156 | /// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf 157 | /// Now expect smoother and more linear accelerations and decelerations. The desiredSpeed() 158 | /// function was removed. 159 | /// \version 1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned 160 | /// \version 1.25 Now ignore attempts to set acceleration to 0.0 161 | /// \version 1.26 Fixed a problem where certina combinations of speed and accelration could cause 162 | /// oscillation about the target position. 163 | /// \version 1.27 Added stop() function to stop as fast as possible with current acceleration parameters. 164 | /// Also added new Quickstop example showing its use. 165 | /// \version 1.28 Fixed another problem where certain combinations of speed and acceleration could cause 166 | /// oscillation about the target position. 167 | /// Added support for 3 wire full and half steppers such as Hard Disk Drive spindle. 168 | /// Contributed by Yuri Ivatchkovitch. 169 | /// \version 1.29 Fixed a problem that could cause a DRIVER stepper to continually step 170 | /// with some sketches. Reported by Vadim. 171 | /// \version 1.30 Fixed a problem that could cause stepper to back up a few steps at the end of 172 | /// accelerated travel with certain speeds. Reported and patched by jolo. 173 | /// \version 1.31 Updated author and distribution location details to airspayce.com 174 | /// \version 1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that 175 | /// prevented the enable pin changing stae correctly. Reported by Duane Bishop. 176 | /// \version 1.33 Fixed an error in example AFMotor_ConstantSpeed.pde did not setMaxSpeed(); 177 | /// Fixed a problem that caused incorrect pin sequencing of FULL3WIRE and HALF3WIRE. 178 | /// Unfortunately this meant changing the signature for all step*() functions. 179 | /// Added example MotorShield, showing how to use AdaFruit Motor Shield to control 180 | /// a 3 phase motor such as a HDD spindle motor (and without using the AFMotor library. 181 | /// \version 1.34 Added setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert) 182 | /// to allow inversion of 2, 3 and 4 wire stepper pins. Requested by Oleg. 183 | /// \version 1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with 184 | /// setPinsInverted(bool, bool, bool). Reported by Mac Mac. 185 | /// \version 1.36 Changed enableOutputs() and disableOutputs() to be virtual so can be overridden. 186 | /// Added new optional argument 'enable' to constructor, which allows you toi disable the 187 | /// automatic enabling of outputs at construction time. Suggested by Guido. 188 | /// \version 1.37 Fixed a problem with step1 that could cause a rogue step in the 189 | /// wrong direction (or not, 190 | /// depending on the setup-time requirements of the connected hardware). 191 | /// Reported by Mark Tillotson. 192 | /// \version 1.38 run() function incorrectly always returned true. Updated function and doc so it returns true 193 | /// if the motor is still running to the target position. 194 | /// \version 1.39 Updated typos in keywords.txt, courtesey Jon Magill. 195 | /// \version 1.40 Updated documentation, including testing on Teensy 3.1 196 | /// \version 1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value 197 | /// \version 1.42 Improved support for FULL3WIRE and HALF3WIRE output pins. These changes were in Yuri's original 198 | /// contribution but did not make it into production.
199 | /// \version 1.43 Added DualMotorShield example. Shows how to use AccelStepper to control 2 x 2 phase steppers using the 200 | /// Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.
201 | /// \version 1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde 202 | /// was missing from the distribution.
203 | /// \version 1.45 Fixed a problem where if setAcceleration was not called, there was no default 204 | /// acceleration. Reported by Michael Newman.
205 | /// \version 1.45 Fixed inaccuracy in acceleration rate by using Equation 15, suggested by Sebastian Gracki.
206 | /// Performance improvements in runSpeed suggested by Jaakko Fagerlund.
207 | /// \version 1.46 Fixed error in documentation for runToPosition(). 208 | /// Reinstated time calculations in runSpeed() since new version is reported 209 | /// not to work correctly under some circumstances. Reported by Oleg V Gavva.
210 | /// \version 1.48 2015-08-25 211 | /// Added new class MultiStepper that can manage multiple AccelSteppers, 212 | /// and cause them all to move 213 | /// to selected positions at such a (constant) speed that they all arrive at their 214 | /// target position at the same time. Suitable for X-Y flatbeds etc.
215 | /// Added new method maxSpeed() to AccelStepper to return the currently configured maxSpeed.
216 | /// \version 1.49 2016-01-02 217 | /// Testing with VID28 series instrument stepper motors and EasyDriver. 218 | /// OK, although with light pointers 219 | /// and slow speeds like 180 full steps per second the motor movement can be erratic, 220 | /// probably due to some mechanical resonance. Best to accelerate through this speed.
221 | /// Added isRunning().
222 | /// \version 1.50 2016-02-25 223 | /// AccelStepper::disableOutputs now sets the enable pion to OUTPUT mode if the enable pin is defined. 224 | /// Patch from Piet De Jong.
225 | /// Added notes about the fact that AFMotor_* examples do not work with Adafruit Motor Shield V2.
226 | /// \version 1.51 2016-03-24 227 | /// Fixed a problem reported by gregor: when resetting the stepper motor position using setCurrentPosition() the 228 | /// stepper speed is reset by setting _stepInterval to 0, but _speed is not 229 | /// reset. this results in the stepper motor not starting again when calling 230 | /// setSpeed() with the same speed the stepper was set to before. 231 | /// \version 1.52 2016-08-09 232 | /// Added MultiStepper to keywords.txt. 233 | /// Improvements to efficiency of AccelStepper::runSpeed() as suggested by David Grayson. 234 | /// Improvements to speed accuracy as suggested by David Grayson. 235 | /// \version 1.53 2016-08-14 236 | /// Backed out Improvements to speed accuracy from 1.52 as it did not work correctly. 237 | /// \version 1.54 2017-01-24 238 | /// Fixed some warnings about unused arguments. 239 | /// \version 1.55 2017-01-25 240 | /// Fixed another warning in MultiStepper.cpp 241 | /// \version 1.56 2017-02-03 242 | /// Fixed minor documentation error with DIRECTION_CCW and DIRECTION_CW. Reported by David Mutterer. 243 | /// Added link to Binpress commercial license purchasing. 244 | /// \version 1.57 2017-03-28 245 | /// _direction moved to protected at the request of Rudy Ercek. 246 | /// setMaxSpeed() and setAcceleration() now correct negative values to be positive. 247 | /// \version 1.58 2018-04-13 248 | /// Add initialisation for _enableInverted in constructor. 249 | /// \version 1.59 2018-08-28 250 | /// Update commercial licensing, remove binpress. 251 | /// \version 1.60 2020-03-07 252 | /// Release under GPL V3 253 | /// \version 1.61 2020-04-20 254 | /// Added yield() call in runToPosition(), so that platforms like esp8266 dont hang/crash 255 | /// during long runs. 256 | /// \version 1.62 2022-05-22 257 | /// Added link to AccelStepper - The Missing Manual.
258 | /// Fixed a problem when setting the maxSpeed to 1.0 due to incomplete initialisation. 259 | /// Reported by Olivier Pécheux.
260 | /// \version 1.63 2022-06-30 261 | /// Added virtual destructor at the request of Jan.
262 | /// \version 1.64 2022-10-31 263 | /// Patch courtesy acwest: Changes to make AccelStepper more subclassable. These changes are 264 | /// largely oriented to implementing new step-scheduling algorithms. 265 | /// 266 | /// \author Mike McCauley (mikem@airspayce.com) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE GOOGLE GROUP 267 | // Copyright (C) 2009-2020 Mike McCauley 268 | // $Id: AccelStepper.h,v 1.28 2020/04/20 00:15:03 mikem Exp mikem $ 269 | 270 | #ifndef AccelStepper_h 271 | #define AccelStepper_h 272 | 273 | #include 274 | #if ARDUINO >= 100 275 | #include 276 | #else 277 | #include 278 | #include 279 | #endif 280 | 281 | // These defs cause trouble on some versions of Arduino 282 | #undef round 283 | 284 | // Use the system yield() whenever possoible, since some platforms require it for housekeeping, especially 285 | // ESP8266 286 | #if (defined(ARDUINO) && ARDUINO >= 155) || defined(ESP8266) 287 | #define YIELD yield(); 288 | #else 289 | #define YIELD 290 | #endif 291 | 292 | ///////////////////////////////////////////////////////////////////// 293 | /// \class AccelStepper AccelStepper.h 294 | /// \brief Support for stepper motors with acceleration etc. 295 | /// 296 | /// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional 297 | /// acceleration, deceleration, absolute positioning commands etc. Multiple 298 | /// simultaneous steppers are supported, all moving 299 | /// at different speeds and accelerations. 300 | /// 301 | /// \par Operation 302 | /// This module operates by computing a step time in microseconds. The step 303 | /// time is recomputed after each step and after speed and acceleration 304 | /// parameters are changed by the caller. The time of each step is recorded in 305 | /// microseconds. The run() function steps the motor once if a new step is due. 306 | /// The run() function must be called frequently until the motor is in the 307 | /// desired position, after which time run() will do nothing. 308 | /// 309 | /// \par Positioning 310 | /// Positions are specified by a signed long integer. At 311 | /// construction time, the current position of the motor is consider to be 0. Positive 312 | /// positions are clockwise from the initial position; negative positions are 313 | /// anticlockwise. The current position can be altered for instance after 314 | /// initialization positioning. 315 | /// 316 | /// \par Caveats 317 | /// This is an open loop controller: If the motor stalls or is oversped, 318 | /// AccelStepper will not have a correct 319 | /// idea of where the motor really is (since there is no feedback of the motor's 320 | /// real position. We only know where we _think_ it is, relative to the 321 | /// initial starting point). 322 | /// 323 | /// \par Performance 324 | /// The fastest motor speed that can be reliably supported is about 4000 steps per 325 | /// second at a clock frequency of 16 MHz on Arduino such as Uno etc. 326 | /// Faster processors can support faster stepping speeds. 327 | /// However, any speed less than that 328 | /// down to very slow speeds (much less than one per second) are also supported, 329 | /// provided the run() function is called frequently enough to step the motor 330 | /// whenever required for the speed set. 331 | /// Calling setAcceleration() is expensive, 332 | /// since it requires a square root to be calculated. 333 | /// 334 | /// Gregor Christandl reports that with an Arduino Due and a simple test program, 335 | /// he measured 43163 steps per second using runSpeed(), 336 | /// and 16214 steps per second using run(); 337 | class AccelStepper 338 | { 339 | public: 340 | /// \brief Symbolic names for number of pins. 341 | /// Use this in the pins argument the AccelStepper constructor to 342 | /// provide a symbolic name for the number of pins 343 | /// to use. 344 | typedef enum 345 | { 346 | FUNCTION = 0, ///< Use the functional interface, implementing your own driver functions (internal use only) 347 | DRIVER = 1, ///< Stepper Driver, 2 driver pins required 348 | FULL2WIRE = 2, ///< 2 wire stepper, 2 motor pins required 349 | FULL3WIRE = 3, ///< 3 wire stepper, such as HDD spindle, 3 motor pins required 350 | FULL4WIRE = 4, ///< 4 wire full stepper, 4 motor pins required 351 | HALF3WIRE = 6, ///< 3 wire half stepper, such as HDD spindle, 3 motor pins required 352 | HALF4WIRE = 8 ///< 4 wire half stepper, 4 motor pins required 353 | } MotorInterfaceType; 354 | 355 | /// Constructor. You can have multiple simultaneous steppers, all moving 356 | /// at different speeds and accelerations, provided you call their run() 357 | /// functions at frequent enough intervals. Current Position is set to 0, target 358 | /// position is set to 0. MaxSpeed and Acceleration default to 1.0. 359 | /// The motor pins will be initialised to OUTPUT mode during the 360 | /// constructor by a call to enableOutputs(). 361 | /// \param[in] interface Number of pins to interface to. Integer values are 362 | /// supported, but it is preferred to use the \ref MotorInterfaceType symbolic names. 363 | /// AccelStepper::DRIVER (1) means a stepper driver (with Step and Direction pins). 364 | /// If an enable line is also needed, call setEnablePin() after construction. 365 | /// You may also invert the pins using setPinsInverted(). 366 | /// Caution: DRIVER implements a blocking delay of minPulseWidth microseconds (default 1us) for each step. 367 | /// You can change this with setMinPulseWidth(). 368 | /// AccelStepper::FULL2WIRE (2) means a 2 wire stepper (2 pins required). 369 | /// AccelStepper::FULL3WIRE (3) means a 3 wire stepper, such as HDD spindle (3 pins required). 370 | /// AccelStepper::FULL4WIRE (4) means a 4 wire stepper (4 pins required). 371 | /// AccelStepper::HALF3WIRE (6) means a 3 wire half stepper, such as HDD spindle (3 pins required) 372 | /// AccelStepper::HALF4WIRE (8) means a 4 wire half stepper (4 pins required) 373 | /// Defaults to AccelStepper::FULL4WIRE (4) pins. 374 | /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults 375 | /// to pin 2. For a AccelStepper::DRIVER (interface==1), 376 | /// this is the Step input to the driver. Low to high transition means to step) 377 | /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults 378 | /// to pin 3. For a AccelStepper::DRIVER (interface==1), 379 | /// this is the Direction input the driver. High means forward. 380 | /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults 381 | /// to pin 4. 382 | /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults 383 | /// to pin 5. 384 | /// \param[in] enable If this is true (the default), enableOutputs() will be called to enable 385 | /// the output pins at construction time. 386 | AccelStepper(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5, bool enable = true); 387 | 388 | /// Alternate Constructor which will call your own functions for forward and backward steps. 389 | /// You can have multiple simultaneous steppers, all moving 390 | /// at different speeds and accelerations, provided you call their run() 391 | /// functions at frequent enough intervals. Current Position is set to 0, target 392 | /// position is set to 0. MaxSpeed and Acceleration default to 1.0. 393 | /// Any motor initialization should happen before hand, no pins are used or initialized. 394 | /// \param[in] forward void-returning procedure that will make a forward step 395 | /// \param[in] backward void-returning procedure that will make a backward step 396 | AccelStepper(void (*forward)(), void (*backward)()); 397 | 398 | /// Set the target position. The run() function will try to move the motor (at most one step per call) 399 | /// from the current position to the target position set by the most 400 | /// recent call to this function. Caution: moveTo() also recalculates the speed for the next step. 401 | /// If you are trying to use constant speed movements, you should call setSpeed() after calling moveTo(). 402 | /// \param[in] absolute The desired absolute position. Negative is 403 | /// anticlockwise from the 0 position. 404 | void moveTo(long absolute); 405 | 406 | /// Set the target position relative to the current position. 407 | /// \param[in] relative The desired position relative to the current position. Negative is 408 | /// anticlockwise from the current position. 409 | void move(long relative); 410 | 411 | /// Poll the motor and step it if a step is due, implementing 412 | /// accelerations and decelerations to achieve the target position. You must call this as 413 | /// frequently as possible, but at least once per minimum step time interval, 414 | /// preferably in your main loop. Note that each call to run() will make at most one step, and then only when a step is due, 415 | /// based on the current speed and the time since the last step. 416 | /// \return true if the motor is still running to the target position. 417 | boolean run(); 418 | 419 | /// Poll the motor and step it if a step is due, implementing a constant 420 | /// speed as set by the most recent call to setSpeed(). You must call this as 421 | /// frequently as possible, but at least once per step interval, 422 | /// \return true if the motor was stepped. 423 | boolean runSpeed(); 424 | 425 | /// Sets the maximum permitted speed. The run() function will accelerate 426 | /// up to the speed set by this function. 427 | /// Caution: the maximum speed achievable depends on your processor and clock speed. 428 | /// The default maxSpeed is 1.0 steps per second. 429 | /// \param[in] speed The desired maximum speed in steps per second. Must 430 | /// be > 0. Caution: Speeds that exceed the maximum speed supported by the processor may 431 | /// Result in non-linear accelerations and decelerations. 432 | void setMaxSpeed(float speed); 433 | 434 | /// Returns the maximum speed configured for this stepper 435 | /// that was previously set by setMaxSpeed(); 436 | /// \return The currently configured maximum speed 437 | float maxSpeed(); 438 | 439 | /// Sets the acceleration/deceleration rate. 440 | /// \param[in] acceleration The desired acceleration in steps per second 441 | /// per second. Must be > 0.0. This is an expensive call since it requires a square 442 | /// root to be calculated. Dont call more ofthen than needed 443 | void setAcceleration(float acceleration); 444 | 445 | /// Returns the acceleration/deceleration rate configured for this stepper 446 | /// that was previously set by setAcceleration(); 447 | /// \return The currently configured acceleration/deceleration 448 | float acceleration(); 449 | 450 | /// Sets the desired constant speed for use with runSpeed(). 451 | /// \param[in] speed The desired constant speed in steps per 452 | /// second. Positive is clockwise. Speeds of more than 1000 steps per 453 | /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for 454 | /// once per hour, approximately. Speed accuracy depends on the Arduino 455 | /// crystal. Jitter depends on how frequently you call the runSpeed() function. 456 | /// The speed will be limited by the current value of setMaxSpeed() 457 | void setSpeed(float speed); 458 | 459 | /// The most recently set speed. 460 | /// \return the most recent speed in steps per second 461 | float speed(); 462 | 463 | /// The distance from the current position to the target position. 464 | /// \return the distance from the current position to the target position 465 | /// in steps. Positive is clockwise from the current position. 466 | long distanceToGo(); 467 | 468 | /// The most recently set target position. 469 | /// \return the target position 470 | /// in steps. Positive is clockwise from the 0 position. 471 | long targetPosition(); 472 | 473 | /// The current motor position. 474 | /// \return the current motor position 475 | /// in steps. Positive is clockwise from the 0 position. 476 | long currentPosition(); 477 | 478 | /// Resets the current position of the motor, so that wherever the motor 479 | /// happens to be right now is considered to be the new 0 position. Useful 480 | /// for setting a zero position on a stepper after an initial hardware 481 | /// positioning move. 482 | /// Has the side effect of setting the current motor speed to 0. 483 | /// \param[in] position The position in steps of wherever the motor 484 | /// happens to be right now. 485 | void setCurrentPosition(long position); 486 | 487 | /// Moves the motor (with acceleration/deceleration) 488 | /// to the target position and blocks until it is at 489 | /// position. Dont use this in event loops, since it blocks. 490 | void runToPosition(); 491 | 492 | /// Executes runSpeed() unless the targetPosition is reached. 493 | /// This function needs to be called often just like runSpeed() or run(). 494 | /// Will step the motor if a step is required at the currently selected 495 | /// speed unless the target position has been reached. 496 | /// Does not implement accelerations. 497 | /// \return true if it stepped 498 | boolean runSpeedToPosition(); 499 | 500 | /// Moves the motor (with acceleration/deceleration) 501 | /// to the new target position and blocks until it is at 502 | /// position. Dont use this in event loops, since it blocks. 503 | /// \param[in] position The new target position. 504 | void runToNewPosition(long position); 505 | 506 | /// Sets a new target position that causes the stepper 507 | /// to stop as quickly as possible, using the current speed and acceleration parameters. 508 | void stop(); 509 | 510 | /// Disable motor pin outputs by setting them all LOW 511 | /// Depending on the design of your electronics this may turn off 512 | /// the power to the motor coils, saving power. 513 | /// This is useful to support Arduino low power modes: disable the outputs 514 | /// during sleep and then reenable with enableOutputs() before stepping 515 | /// again. 516 | /// If the enable Pin is defined, sets it to OUTPUT mode and clears the pin to disabled. 517 | virtual void disableOutputs(); 518 | 519 | /// Enable motor pin outputs by setting the motor pins to OUTPUT 520 | /// mode. Called automatically by the constructor. 521 | /// If the enable Pin is defined, sets it to OUTPUT mode and sets the pin to enabled. 522 | virtual void enableOutputs(); 523 | 524 | /// Sets the minimum pulse width allowed by the stepper driver. The minimum practical pulse width is 525 | /// approximately 20 microseconds. Times less than 20 microseconds 526 | /// will usually result in 20 microseconds or so. 527 | /// \param[in] minWidth The minimum pulse width in microseconds. 528 | void setMinPulseWidth(unsigned int minWidth); 529 | 530 | /// Sets the enable pin number for stepper drivers. 531 | /// 0xFF indicates unused (default). 532 | /// Otherwise, if a pin is set, the pin will be turned on when 533 | /// enableOutputs() is called and switched off when disableOutputs() 534 | /// is called. 535 | /// \param[in] enablePin Arduino digital pin number for motor enable 536 | /// \sa setPinsInverted 537 | void setEnablePin(uint8_t enablePin = 0xff); 538 | 539 | /// Sets the inversion for stepper driver pins 540 | /// \param[in] directionInvert True for inverted direction pin, false for non-inverted 541 | /// \param[in] stepInvert True for inverted step pin, false for non-inverted 542 | /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted 543 | void setPinsInverted(bool directionInvert = false, bool stepInvert = false, bool enableInvert = false); 544 | 545 | /// Sets the inversion for 2, 3 and 4 wire stepper pins 546 | /// \param[in] pin1Invert True for inverted pin1, false for non-inverted 547 | /// \param[in] pin2Invert True for inverted pin2, false for non-inverted 548 | /// \param[in] pin3Invert True for inverted pin3, false for non-inverted 549 | /// \param[in] pin4Invert True for inverted pin4, false for non-inverted 550 | /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted 551 | void setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert); 552 | 553 | /// Checks to see if the motor is currently running to a target 554 | /// \return true if the speed is not zero or not at the target position 555 | bool isRunning(); 556 | 557 | /// Virtual destructor to prevent warnings during delete 558 | virtual ~AccelStepper() {}; 559 | protected: 560 | 561 | /// \brief Direction indicator 562 | /// Symbolic names for the direction the motor is turning 563 | typedef enum 564 | { 565 | DIRECTION_CCW = 0, ///< Counter-Clockwise 566 | DIRECTION_CW = 1 ///< Clockwise 567 | } Direction; 568 | 569 | /// Forces the library to compute a new instantaneous speed and set that as 570 | /// the current speed. It is called by 571 | /// the library: 572 | /// \li after each step 573 | /// \li after change to maxSpeed through setMaxSpeed() 574 | /// \li after change to acceleration through setAcceleration() 575 | /// \li after change to target position (relative or absolute) through 576 | /// move() or moveTo() 577 | /// \return the new step interval 578 | virtual unsigned long computeNewSpeed(); 579 | 580 | /// Low level function to set the motor output pins 581 | /// bit 0 of the mask corresponds to _pin[0] 582 | /// bit 1 of the mask corresponds to _pin[1] 583 | /// You can override this to impment, for example serial chip output insted of using the 584 | /// output pins directly 585 | virtual void setOutputPins(uint8_t mask); 586 | 587 | /// Called to execute a step. Only called when a new step is 588 | /// required. Subclasses may override to implement new stepping 589 | /// interfaces. The default calls step1(), step2(), step4() or step8() depending on the 590 | /// number of pins defined for the stepper. 591 | /// \param[in] step The current step phase number (0 to 7) 592 | virtual void step(long step); 593 | 594 | /// Called to execute a clockwise(+) step. Only called when a new step is 595 | /// required. This increments the _currentPos and calls step() 596 | /// \return the updated current position 597 | long stepForward(); 598 | 599 | /// Called to execute a counter-clockwise(-) step. Only called when a new step is 600 | /// required. This decrements the _currentPos and calls step() 601 | /// \return the updated current position 602 | long stepBackward(); 603 | 604 | /// Called to execute a step using stepper functions (pins = 0) Only called when a new step is 605 | /// required. Calls _forward() or _backward() to perform the step 606 | /// \param[in] step The current step phase number (0 to 7) 607 | virtual void step0(long step); 608 | 609 | /// Called to execute a step on a stepper driver (ie where pins == 1). Only called when a new step is 610 | /// required. Subclasses may override to implement new stepping 611 | /// interfaces. The default sets or clears the outputs of Step pin1 to step, 612 | /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond 613 | /// which is the minimum STEP pulse width for the 3967 driver. 614 | /// \param[in] step The current step phase number (0 to 7) 615 | virtual void step1(long step); 616 | 617 | /// Called to execute a step on a 2 pin motor. Only called when a new step is 618 | /// required. Subclasses may override to implement new stepping 619 | /// interfaces. The default sets or clears the outputs of pin1 and pin2 620 | /// \param[in] step The current step phase number (0 to 7) 621 | virtual void step2(long step); 622 | 623 | /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is 624 | /// required. Subclasses may override to implement new stepping 625 | /// interfaces. The default sets or clears the outputs of pin1, pin2, 626 | /// pin3 627 | /// \param[in] step The current step phase number (0 to 7) 628 | virtual void step3(long step); 629 | 630 | /// Called to execute a step on a 4 pin motor. Only called when a new step is 631 | /// required. Subclasses may override to implement new stepping 632 | /// interfaces. The default sets or clears the outputs of pin1, pin2, 633 | /// pin3, pin4. 634 | /// \param[in] step The current step phase number (0 to 7) 635 | virtual void step4(long step); 636 | 637 | /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is 638 | /// required. Subclasses may override to implement new stepping 639 | /// interfaces. The default sets or clears the outputs of pin1, pin2, 640 | /// pin3 641 | /// \param[in] step The current step phase number (0 to 7) 642 | virtual void step6(long step); 643 | 644 | /// Called to execute a step on a 4 pin half-stepper motor. Only called when a new step is 645 | /// required. Subclasses may override to implement new stepping 646 | /// interfaces. The default sets or clears the outputs of pin1, pin2, 647 | /// pin3, pin4. 648 | /// \param[in] step The current step phase number (0 to 7) 649 | virtual void step8(long step); 650 | 651 | /// Current direction motor is spinning in 652 | /// Protected because some peoples subclasses need it to be so 653 | boolean _direction; // 1 == CW 654 | 655 | /// The current interval between steps in microseconds. 656 | /// 0 means the motor is currently stopped with _speed == 0 657 | unsigned long _stepInterval; 658 | 659 | private: 660 | /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a 661 | /// bipolar, and 4 pins is a unipolar. 662 | uint8_t _interface; // 0, 1, 2, 4, 8, See MotorInterfaceType 663 | 664 | /// Arduino pin number assignments for the 2 or 4 pins required to interface to the 665 | /// stepper motor or driver 666 | uint8_t _pin[4]; 667 | 668 | /// Whether the _pins is inverted or not 669 | uint8_t _pinInverted[4]; 670 | 671 | /// The current absolution position in steps. 672 | long _currentPos; // Steps 673 | 674 | /// The target position in steps. The AccelStepper library will move the 675 | /// motor from the _currentPos to the _targetPos, taking into account the 676 | /// max speed, acceleration and deceleration 677 | long _targetPos; // Steps 678 | 679 | /// The current motos speed in steps per second 680 | /// Positive is clockwise 681 | float _speed; // Steps per second 682 | 683 | /// The maximum permitted speed in steps per second. Must be > 0. 684 | float _maxSpeed; 685 | 686 | /// The acceleration to use to accelerate or decelerate the motor in steps 687 | /// per second per second. Must be > 0 688 | float _acceleration; 689 | float _sqrt_twoa; // Precomputed sqrt(2*_acceleration) 690 | 691 | /// The last step time in microseconds 692 | unsigned long _lastStepTime; 693 | 694 | /// The minimum allowed pulse width in microseconds 695 | unsigned int _minPulseWidth; 696 | 697 | /// Is the direction pin inverted? 698 | ///bool _dirInverted; /// Moved to _pinInverted[1] 699 | 700 | /// Is the step pin inverted? 701 | ///bool _stepInverted; /// Moved to _pinInverted[0] 702 | 703 | /// Is the enable pin inverted? 704 | bool _enableInverted; 705 | 706 | /// Enable pin for stepper driver, or 0xFF if unused. 707 | uint8_t _enablePin; 708 | 709 | /// The pointer to a forward-step procedure 710 | void (*_forward)(); 711 | 712 | /// The pointer to a backward-step procedure 713 | void (*_backward)(); 714 | 715 | /// The step counter for speed calculations 716 | long _n; 717 | 718 | /// Initial step size in microseconds 719 | float _c0; 720 | 721 | /// Last step size in microseconds 722 | float _cn; 723 | 724 | /// Min step size in microseconds based on maxSpeed 725 | float _cmin; // at max speed 726 | 727 | }; 728 | 729 | /// @example Random.pde 730 | /// Make a single stepper perform random changes in speed, position and acceleration 731 | 732 | /// @example Overshoot.pde 733 | /// Check overshoot handling 734 | /// which sets a new target position and then waits until the stepper has 735 | /// achieved it. This is used for testing the handling of overshoots 736 | 737 | /// @example MultipleSteppers.pde 738 | /// Shows how to multiple simultaneous steppers 739 | /// Runs one stepper forwards and backwards, accelerating and decelerating 740 | /// at the limits. Runs other steppers at the same time 741 | 742 | /// @example ConstantSpeed.pde 743 | /// Shows how to run AccelStepper in the simplest, 744 | /// fixed speed mode with no accelerations 745 | 746 | /// @example Blocking.pde 747 | /// Shows how to use the blocking call runToNewPosition 748 | /// Which sets a new target position and then waits until the stepper has 749 | /// achieved it. 750 | 751 | /// @example AFMotor_MultiStepper.pde 752 | /// Control both Stepper motors at the same time with different speeds 753 | /// and accelerations. 754 | 755 | /// @example AFMotor_ConstantSpeed.pde 756 | /// Shows how to run AccelStepper in the simplest, 757 | /// fixed speed mode with no accelerations 758 | 759 | /// @example ProportionalControl.pde 760 | /// Make a single stepper follow the analog value read from a pot or whatever 761 | /// The stepper will move at a constant speed to each newly set posiiton, 762 | /// depending on the value of the pot. 763 | 764 | /// @example Bounce.pde 765 | /// Make a single stepper bounce from one limit to another, observing 766 | /// accelrations at each end of travel 767 | 768 | /// @example Quickstop.pde 769 | /// Check stop handling. 770 | /// Calls stop() while the stepper is travelling at full speed, causing 771 | /// the stepper to stop as quickly as possible, within the constraints of the 772 | /// current acceleration. 773 | 774 | /// @example MotorShield.pde 775 | /// Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor 776 | /// using the Adafruit Motor Shield http://www.ladyada.net/make/mshield/index.html. 777 | 778 | /// @example DualMotorShield.pde 779 | /// Shows how to use AccelStepper to control 2 x 2 phase steppers using the 780 | /// Itead Studio Arduino Dual Stepper Motor Driver Shield 781 | /// model IM120417015 782 | 783 | #endif 784 | -------------------------------------------------------------------------------- /src/MultiStepper.cpp: -------------------------------------------------------------------------------- 1 | // MultiStepper.cpp 2 | // 3 | // Copyright (C) 2015 Mike McCauley 4 | // $Id: MultiStepper.cpp,v 1.3 2020/04/20 00:15:03 mikem Exp mikem $ 5 | 6 | #include "MultiStepper.h" 7 | #include "AccelStepper.h" 8 | 9 | MultiStepper::MultiStepper() 10 | : _num_steppers(0) 11 | { 12 | } 13 | 14 | boolean MultiStepper::addStepper(AccelStepper& stepper) 15 | { 16 | if (_num_steppers >= MULTISTEPPER_MAX_STEPPERS) 17 | return false; // No room for more 18 | _steppers[_num_steppers++] = &stepper; 19 | return true; 20 | } 21 | 22 | void MultiStepper::moveTo(long absolute[]) 23 | { 24 | // First find the stepper that will take the longest time to move 25 | float longestTime = 0.0; 26 | 27 | uint8_t i; 28 | for (i = 0; i < _num_steppers; i++) 29 | { 30 | long thisDistance = absolute[i] - _steppers[i]->currentPosition(); 31 | float thisTime = abs(thisDistance) / _steppers[i]->maxSpeed(); 32 | 33 | if (thisTime > longestTime) 34 | longestTime = thisTime; 35 | } 36 | 37 | if (longestTime > 0.0) 38 | { 39 | // Now work out a new max speed for each stepper so they will all 40 | // arrived at the same time of longestTime 41 | for (i = 0; i < _num_steppers; i++) 42 | { 43 | long thisDistance = absolute[i] - _steppers[i]->currentPosition(); 44 | float thisSpeed = thisDistance / longestTime; 45 | _steppers[i]->moveTo(absolute[i]); // New target position (resets speed) 46 | _steppers[i]->setSpeed(thisSpeed); // New speed 47 | } 48 | } 49 | } 50 | 51 | // Returns true if any motor is still running to the target position. 52 | boolean MultiStepper::run() 53 | { 54 | uint8_t i; 55 | boolean ret = false; 56 | for (i = 0; i < _num_steppers; i++) 57 | { 58 | if ( _steppers[i]->distanceToGo() != 0) 59 | { 60 | _steppers[i]->runSpeed(); 61 | ret = true; 62 | } 63 | // Caution: it has een reported that if any motor is used with acceleration outside of 64 | // MultiStepper, this code is necessary, you get 65 | // strange results where it moves in the wrong direction for a while then 66 | // slams back the correct way. 67 | #if 0 68 | else 69 | { 70 | // Need to call this to clear _stepInterval, _speed and _n 71 | otherwise future calls will fail. 72 | _steppers[i]->setCurrentPosition(_steppers[i]->currentPosition()); 73 | } 74 | #endif 75 | 76 | } 77 | return ret; 78 | } 79 | 80 | // Blocks until all steppers reach their target position and are stopped 81 | void MultiStepper::runSpeedToPosition() 82 | { 83 | while (run()) 84 | ; 85 | } 86 | 87 | -------------------------------------------------------------------------------- /src/MultiStepper.h: -------------------------------------------------------------------------------- 1 | // MultiStepper.h 2 | 3 | #ifndef MultiStepper_h 4 | #define MultiStepper_h 5 | 6 | #include 7 | #if ARDUINO >= 100 8 | #include 9 | #else 10 | #include 11 | #include 12 | #endif 13 | 14 | #define MULTISTEPPER_MAX_STEPPERS 10 15 | 16 | class AccelStepper; 17 | 18 | ///////////////////////////////////////////////////////////////////// 19 | /// \class MultiStepper MultiStepper.h 20 | /// \brief Operate multiple AccelSteppers in a co-ordinated fashion 21 | /// 22 | /// This class can manage multiple AccelSteppers (up to MULTISTEPPER_MAX_STEPPERS = 10), 23 | /// and cause them all to move 24 | /// to selected positions at such a (constant) speed that they all arrive at their 25 | /// target position at the same time. This can be used to support devices with multiple steppers 26 | /// on say multiple axes to cause linear diagonal motion. Suitable for use with X-Y plotters, flatbeds, 27 | /// 3D printers etc 28 | /// to get linear straight line movement between arbitrary 2d (or 3d or ...) positions. 29 | /// 30 | /// Caution: only constant speed stepper motion is supported: acceleration and deceleration is not supported 31 | /// All the steppers managed by MultiStepper will step at a constant speed to their 32 | /// target (albeit perhaps different speeds for each stepper). 33 | class MultiStepper 34 | { 35 | public: 36 | /// Constructor 37 | MultiStepper(); 38 | 39 | /// Add a stepper to the set of managed steppers 40 | /// There is an upper limit of MULTISTEPPER_MAX_STEPPERS = 10 to the number of steppers that can be managed 41 | /// \param[in] stepper Reference to a stepper to add to the managed list 42 | /// \return true if successful. false if the number of managed steppers would exceed MULTISTEPPER_MAX_STEPPERS 43 | boolean addStepper(AccelStepper& stepper); 44 | 45 | /// Set the target positions of all managed steppers 46 | /// according to a coordinate array. 47 | /// New speeds will be computed for each stepper so they will all arrive at their 48 | /// respective targets at very close to the same time. 49 | /// \param[in] absolute An array of desired absolute stepper positions. absolute[0] will be used to set 50 | /// the absolute position of the first stepper added by addStepper() etc. The array must be at least as long as 51 | /// the number of steppers that have been added by addStepper, else results are undefined. 52 | void moveTo(long absolute[]); 53 | 54 | /// Calls runSpeed() on all the managed steppers 55 | /// that have not acheived their target position. 56 | /// \return true if any stepper is still in the process of running to its target position. 57 | boolean run(); 58 | 59 | /// Runs all managed steppers until they acheived their target position. 60 | /// Blocks until all that position is acheived. If you dont 61 | /// want blocking consider using run() instead. 62 | void runSpeedToPosition(); 63 | 64 | private: 65 | /// Array of pointers to the steppers we are controlling. 66 | /// Fills from 0 onwards 67 | AccelStepper* _steppers[MULTISTEPPER_MAX_STEPPERS]; 68 | 69 | /// Number of steppers we are controlling and the number 70 | /// of steppers in _steppers[] 71 | uint8_t _num_steppers; 72 | }; 73 | 74 | /// @example MultiStepper.pde 75 | /// Use MultiStepper class to manage multiple steppers and make them all move to 76 | /// the same position at the same time for linear 2d (or 3d) motion. 77 | 78 | #endif 79 | --------------------------------------------------------------------------------