Browse Source

starting a atm_stepper, switched to accelstepper for now

eLandon 6 years ago
parent
commit
73e1d32318
39 changed files with 9074 additions and 145 deletions
  1. 652 0
      HTequi-firmware/lib/AccelStepper/AccelStepper.cpp
  2. 734 0
      HTequi-firmware/lib/AccelStepper/AccelStepper.h
  3. 17 0
      HTequi-firmware/lib/AccelStepper/LICENSE
  4. 38 0
      HTequi-firmware/lib/AccelStepper/MANIFEST
  5. 30 0
      HTequi-firmware/lib/AccelStepper/Makefile
  6. 73 0
      HTequi-firmware/lib/AccelStepper/MultiStepper.cpp
  7. 78 0
      HTequi-firmware/lib/AccelStepper/MultiStepper.h
  8. 420 0
      HTequi-firmware/lib/AccelStepper/doc/AccelStepper_8h-source.html
  9. 58 0
      HTequi-firmware/lib/AccelStepper/doc/annotated.html
  10. 103 0
      HTequi-firmware/lib/AccelStepper/doc/classAccelStepper-members.html
  11. 1344 0
      HTequi-firmware/lib/AccelStepper/doc/classAccelStepper.html
  12. 1596 0
      HTequi-firmware/lib/AccelStepper/doc/doxygen.css
  13. BIN
      HTequi-firmware/lib/AccelStepper/doc/doxygen.png
  14. 58 0
      HTequi-firmware/lib/AccelStepper/doc/files.html
  15. 243 0
      HTequi-firmware/lib/AccelStepper/doc/functions.html
  16. 195 0
      HTequi-firmware/lib/AccelStepper/doc/functions_func.html
  17. 222 0
      HTequi-firmware/lib/AccelStepper/doc/index.html
  18. BIN
      HTequi-firmware/lib/AccelStepper/doc/tab_b.gif
  19. BIN
      HTequi-firmware/lib/AccelStepper/doc/tab_l.gif
  20. BIN
      HTequi-firmware/lib/AccelStepper/doc/tab_r.gif
  21. 1 0
      HTequi-firmware/lib/AccelStepper/doc/tabs.css
  22. 40 0
      HTequi-firmware/lib/AccelStepper/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde
  23. 57 0
      HTequi-firmware/lib/AccelStepper/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde
  24. 28 0
      HTequi-firmware/lib/AccelStepper/examples/Blocking/Blocking.pde
  25. 29 0
      HTequi-firmware/lib/AccelStepper/examples/Bounce/Bounce.pde
  26. 23 0
      HTequi-firmware/lib/AccelStepper/examples/ConstantSpeed/ConstantSpeed.pde
  27. 49 0
      HTequi-firmware/lib/AccelStepper/examples/DualMotorShield/DualMotorShield.pde
  28. 103 0
      HTequi-firmware/lib/AccelStepper/examples/MotorShield/MotorShield.pde
  29. 44 0
      HTequi-firmware/lib/AccelStepper/examples/MultiStepper/MultiStepper.pde
  30. 41 0
      HTequi-firmware/lib/AccelStepper/examples/MultipleSteppers/MultipleSteppers.pde
  31. 28 0
      HTequi-firmware/lib/AccelStepper/examples/Overshoot/Overshoot.pde
  32. 32 0
      HTequi-firmware/lib/AccelStepper/examples/ProportionalControl/ProportionalControl.pde
  33. 40 0
      HTequi-firmware/lib/AccelStepper/examples/Quickstop/Quickstop.pde
  34. 30 0
      HTequi-firmware/lib/AccelStepper/examples/Random/Random.pde
  35. 41 0
      HTequi-firmware/lib/AccelStepper/keywords.txt
  36. 2280 0
      HTequi-firmware/lib/AccelStepper/project.cfg
  37. 124 0
      HTequi-firmware/src/Atm_lien/Atm_stepper.cpp
  38. 68 0
      HTequi-firmware/src/Atm_lien/Atm_stepper.h
  39. 155 145
      HTequi-firmware/src/blobcnc_low/main.cpp

+ 652 - 0
HTequi-firmware/lib/AccelStepper/AccelStepper.cpp

@@ -0,0 +1,652 @@
+// AccelStepper.cpp
+//
+// Copyright (C) 2009-2013 Mike McCauley
+// $Id: AccelStepper.cpp,v 1.23 2016/08/09 00:39:10 mikem Exp $
+
+#include "AccelStepper.h"
+
+#if 0
+// Some debugging assistance
+void dump(uint8_t* p, int l)
+{
+    int i;
+
+    for (i = 0; i < l; i++)
+    {
+	Serial.print(p[i], HEX);
+	Serial.print(" ");
+    }
+    Serial.println("");
+}
+#endif
+
+void AccelStepper::moveTo(long absolute)
+{
+    if (_targetPos != absolute)
+    {
+	_targetPos = absolute;
+	computeNewSpeed();
+	// compute new n?
+    }
+}
+
+void AccelStepper::move(long relative)
+{
+    moveTo(_currentPos + relative);
+}
+
+// Implements steps according to the current step interval
+// You must call this at least once per step
+// returns true if a step occurred
+boolean AccelStepper::runSpeed()
+{
+    // Dont do anything unless we actually have a step interval
+    if (!_stepInterval)
+	return false;
+
+    unsigned long time = micros();   
+    if (time - _lastStepTime >= _stepInterval)
+    {
+	if (_direction == DIRECTION_CW)
+	{
+	    // Clockwise
+	    _currentPos += 1;
+	}
+	else
+	{
+	    // Anticlockwise  
+	    _currentPos -= 1;
+	}
+	step(_currentPos);
+
+	_lastStepTime = time; // Caution: does not account for costs in step()
+
+	return true;
+    }
+    else
+    {
+	return false;
+    }
+}
+
+long AccelStepper::distanceToGo()
+{
+    return _targetPos - _currentPos;
+}
+
+long AccelStepper::targetPosition()
+{
+    return _targetPos;
+}
+
+long AccelStepper::currentPosition()
+{
+    return _currentPos;
+}
+
+// Useful during initialisations or after initial positioning
+// Sets speed to 0
+void AccelStepper::setCurrentPosition(long position)
+{
+    _targetPos = _currentPos = position;
+    _n = 0;
+    _stepInterval = 0;
+    _speed = 0.0;
+}
+
+void AccelStepper::computeNewSpeed()
+{
+    long distanceTo = distanceToGo(); // +ve is clockwise from curent location
+
+    long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
+
+    if (distanceTo == 0 && stepsToStop <= 1)
+    {
+	// We are at the target and its time to stop
+	_stepInterval = 0;
+	_speed = 0.0;
+	_n = 0;
+	return;
+    }
+
+    if (distanceTo > 0)
+    {
+	// We are anticlockwise from the target
+	// Need to go clockwise from here, maybe decelerate now
+	if (_n > 0)
+	{
+	    // Currently accelerating, need to decel now? Or maybe going the wrong way?
+	    if ((stepsToStop >= distanceTo) || _direction == DIRECTION_CCW)
+		_n = -stepsToStop; // Start deceleration
+	}
+	else if (_n < 0)
+	{
+	    // Currently decelerating, need to accel again?
+	    if ((stepsToStop < distanceTo) && _direction == DIRECTION_CW)
+		_n = -_n; // Start accceleration
+	}
+    }
+    else if (distanceTo < 0)
+    {
+	// We are clockwise from the target
+	// Need to go anticlockwise from here, maybe decelerate
+	if (_n > 0)
+	{
+	    // Currently accelerating, need to decel now? Or maybe going the wrong way?
+	    if ((stepsToStop >= -distanceTo) || _direction == DIRECTION_CW)
+		_n = -stepsToStop; // Start deceleration
+	}
+	else if (_n < 0)
+	{
+	    // Currently decelerating, need to accel again?
+	    if ((stepsToStop < -distanceTo) && _direction == DIRECTION_CCW)
+		_n = -_n; // Start accceleration
+	}
+    }
+
+    // Need to accelerate or decelerate
+    if (_n == 0)
+    {
+	// First step from stopped
+	_cn = _c0;
+	_direction = (distanceTo > 0) ? DIRECTION_CW : DIRECTION_CCW;
+    }
+    else
+    {
+	// Subsequent step. Works for accel (n is +_ve) and decel (n is -ve).
+	_cn = _cn - ((2.0 * _cn) / ((4.0 * _n) + 1)); // Equation 13
+	_cn = max(_cn, _cmin); 
+    }
+    _n++;
+    _stepInterval = _cn;
+    _speed = 1000000.0 / _cn;
+    if (_direction == DIRECTION_CCW)
+	_speed = -_speed;
+
+#if 0
+    Serial.println(_speed);
+    Serial.println(_acceleration);
+    Serial.println(_cn);
+    Serial.println(_c0);
+    Serial.println(_n);
+    Serial.println(_stepInterval);
+    Serial.println(distanceTo);
+    Serial.println(stepsToStop);
+    Serial.println("-----");
+#endif
+}
+
+// Run the motor to implement speed and acceleration in order to proceed to the target position
+// You must call this at least once per step, preferably in your main loop
+// If the motor is in the desired position, the cost is very small
+// returns true if the motor is still running to the target position.
+boolean AccelStepper::run()
+{
+    if (runSpeed())
+	computeNewSpeed();
+    return _speed != 0.0 || distanceToGo() != 0;
+}
+
+AccelStepper::AccelStepper(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4, bool enable)
+{
+    _interface = interface;
+    _currentPos = 0;
+    _targetPos = 0;
+    _speed = 0.0;
+    _maxSpeed = 1.0;
+    _acceleration = 0.0;
+    _sqrt_twoa = 1.0;
+    _stepInterval = 0;
+    _minPulseWidth = 1;
+    _enablePin = 0xff;
+    _lastStepTime = 0;
+    _pin[0] = pin1;
+    _pin[1] = pin2;
+    _pin[2] = pin3;
+    _pin[3] = pin4;
+    _enableInverted = false;
+    
+    // NEW
+    _n = 0;
+    _c0 = 0.0;
+    _cn = 0.0;
+    _cmin = 1.0;
+    _direction = DIRECTION_CCW;
+
+    int i;
+    for (i = 0; i < 4; i++)
+	_pinInverted[i] = 0;
+    if (enable)
+	enableOutputs();
+    // Some reasonable default
+    setAcceleration(1);
+}
+
+AccelStepper::AccelStepper(void (*forward)(), void (*backward)())
+{
+    _interface = 0;
+    _currentPos = 0;
+    _targetPos = 0;
+    _speed = 0.0;
+    _maxSpeed = 1.0;
+    _acceleration = 0.0;
+    _sqrt_twoa = 1.0;
+    _stepInterval = 0;
+    _minPulseWidth = 1;
+    _enablePin = 0xff;
+    _lastStepTime = 0;
+    _pin[0] = 0;
+    _pin[1] = 0;
+    _pin[2] = 0;
+    _pin[3] = 0;
+    _forward = forward;
+    _backward = backward;
+
+    // NEW
+    _n = 0;
+    _c0 = 0.0;
+    _cn = 0.0;
+    _cmin = 1.0;
+    _direction = DIRECTION_CCW;
+
+    int i;
+    for (i = 0; i < 4; i++)
+	_pinInverted[i] = 0;
+    // Some reasonable default
+    setAcceleration(1);
+}
+
+void AccelStepper::setMaxSpeed(float speed)
+{
+    if (speed < 0.0)
+       speed = -speed;
+    if (_maxSpeed != speed)
+    {
+	_maxSpeed = speed;
+	_cmin = 1000000.0 / speed;
+	// Recompute _n from current speed and adjust speed if accelerating or cruising
+	if (_n > 0)
+	{
+	    _n = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
+	    computeNewSpeed();
+	}
+    }
+}
+
+float   AccelStepper::maxSpeed()
+{
+    return _maxSpeed;
+}
+
+void AccelStepper::setAcceleration(float acceleration)
+{
+    if (acceleration == 0.0)
+	return;
+    if (acceleration < 0.0)
+      acceleration = -acceleration;
+    if (_acceleration != acceleration)
+    {
+	// Recompute _n per Equation 17
+	_n = _n * (_acceleration / acceleration);
+	// New c0 per Equation 7, with correction per Equation 15
+	_c0 = 0.676 * sqrt(2.0 / acceleration) * 1000000.0; // Equation 15
+	_acceleration = acceleration;
+	computeNewSpeed();
+    }
+}
+
+void AccelStepper::setSpeed(float speed)
+{
+    if (speed == _speed)
+        return;
+    speed = constrain(speed, -_maxSpeed, _maxSpeed);
+    if (speed == 0.0)
+	_stepInterval = 0;
+    else
+    {
+	_stepInterval = fabs(1000000.0 / speed);
+	_direction = (speed > 0.0) ? DIRECTION_CW : DIRECTION_CCW;
+    }
+    _speed = speed;
+}
+
+float AccelStepper::speed()
+{
+    return _speed;
+}
+
+// Subclasses can override
+void AccelStepper::step(long step)
+{
+    switch (_interface)
+    {
+        case FUNCTION:
+            step0(step);
+            break;
+
+	case DRIVER:
+	    step1(step);
+	    break;
+    
+	case FULL2WIRE:
+	    step2(step);
+	    break;
+    
+	case FULL3WIRE:
+	    step3(step);
+	    break;  
+
+	case FULL4WIRE:
+	    step4(step);
+	    break;  
+
+	case HALF3WIRE:
+	    step6(step);
+	    break;  
+		
+	case HALF4WIRE:
+	    step8(step);
+	    break;  
+    }
+}
+
+// You might want to override this to implement eg serial output
+// bit 0 of the mask corresponds to _pin[0]
+// bit 1 of the mask corresponds to _pin[1]
+// ....
+void AccelStepper::setOutputPins(uint8_t mask)
+{
+    uint8_t numpins = 2;
+    if (_interface == FULL4WIRE || _interface == HALF4WIRE)
+	numpins = 4;
+    else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
+	numpins = 3;
+    uint8_t i;
+    for (i = 0; i < numpins; i++)
+	digitalWrite(_pin[i], (mask & (1 << i)) ? (HIGH ^ _pinInverted[i]) : (LOW ^ _pinInverted[i]));
+}
+
+// 0 pin step function (ie for functional usage)
+void AccelStepper::step0(long step)
+{
+    (void)(step); // Unused
+    if (_speed > 0)
+	_forward();
+    else
+	_backward();
+}
+
+// 1 pin step function (ie for stepper drivers)
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step1(long step)
+{
+    (void)(step); // Unused
+
+    // _pin[0] is step, _pin[1] is direction
+    setOutputPins(_direction ? 0b10 : 0b00); // Set direction first else get rogue pulses
+    setOutputPins(_direction ? 0b11 : 0b01); // step HIGH
+    // Caution 200ns setup time 
+    // Delay the minimum allowed pulse width
+    delayMicroseconds(_minPulseWidth);
+    setOutputPins(_direction ? 0b10 : 0b00); // step LOW
+}
+
+
+// 2 pin step function
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step2(long step)
+{
+    switch (step & 0x3)
+    {
+	case 0: /* 01 */
+	    setOutputPins(0b10);
+	    break;
+
+	case 1: /* 11 */
+	    setOutputPins(0b11);
+	    break;
+
+	case 2: /* 10 */
+	    setOutputPins(0b01);
+	    break;
+
+	case 3: /* 00 */
+	    setOutputPins(0b00);
+	    break;
+    }
+}
+// 3 pin step function
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step3(long step)
+{
+    switch (step % 3)
+    {
+	case 0:    // 100
+	    setOutputPins(0b100);
+	    break;
+
+	case 1:    // 001
+	    setOutputPins(0b001);
+	    break;
+
+	case 2:    //010
+	    setOutputPins(0b010);
+	    break;
+	    
+    }
+}
+
+// 4 pin step function for half stepper
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step4(long step)
+{
+    switch (step & 0x3)
+    {
+	case 0:    // 1010
+	    setOutputPins(0b0101);
+	    break;
+
+	case 1:    // 0110
+	    setOutputPins(0b0110);
+	    break;
+
+	case 2:    //0101
+	    setOutputPins(0b1010);
+	    break;
+
+	case 3:    //1001
+	    setOutputPins(0b1001);
+	    break;
+    }
+}
+
+// 3 pin half step function
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step6(long step)
+{
+    switch (step % 6)
+    {
+	case 0:    // 100
+	    setOutputPins(0b100);
+            break;
+	    
+        case 1:    // 101
+	    setOutputPins(0b101);
+            break;
+	    
+	case 2:    // 001
+	    setOutputPins(0b001);
+            break;
+	    
+        case 3:    // 011
+	    setOutputPins(0b011);
+            break;
+	    
+	case 4:    // 010
+	    setOutputPins(0b010);
+            break;
+	    
+	case 5:    // 011
+	    setOutputPins(0b110);
+            break;
+	    
+    }
+}
+
+// 4 pin half step function
+// This is passed the current step number (0 to 7)
+// Subclasses can override
+void AccelStepper::step8(long step)
+{
+    switch (step & 0x7)
+    {
+	case 0:    // 1000
+	    setOutputPins(0b0001);
+            break;
+	    
+        case 1:    // 1010
+	    setOutputPins(0b0101);
+            break;
+	    
+	case 2:    // 0010
+	    setOutputPins(0b0100);
+            break;
+	    
+        case 3:    // 0110
+	    setOutputPins(0b0110);
+            break;
+	    
+	case 4:    // 0100
+	    setOutputPins(0b0010);
+            break;
+	    
+        case 5:    //0101
+	    setOutputPins(0b1010);
+            break;
+	    
+	case 6:    // 0001
+	    setOutputPins(0b1000);
+            break;
+	    
+        case 7:    //1001
+	    setOutputPins(0b1001);
+            break;
+    }
+}
+    
+// Prevents power consumption on the outputs
+void    AccelStepper::disableOutputs()
+{   
+    if (! _interface) return;
+
+    setOutputPins(0); // Handles inversion automatically
+    if (_enablePin != 0xff)
+    {
+        pinMode(_enablePin, OUTPUT);
+        digitalWrite(_enablePin, LOW ^ _enableInverted);
+    }
+}
+
+void    AccelStepper::enableOutputs()
+{
+    if (! _interface) 
+	return;
+
+    pinMode(_pin[0], OUTPUT);
+    pinMode(_pin[1], OUTPUT);
+    if (_interface == FULL4WIRE || _interface == HALF4WIRE)
+    {
+        pinMode(_pin[2], OUTPUT);
+        pinMode(_pin[3], OUTPUT);
+    }
+    else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
+    {
+        pinMode(_pin[2], OUTPUT);
+    }
+
+    if (_enablePin != 0xff)
+    {
+        pinMode(_enablePin, OUTPUT);
+        digitalWrite(_enablePin, HIGH ^ _enableInverted);
+    }
+}
+
+void AccelStepper::setMinPulseWidth(unsigned int minWidth)
+{
+    _minPulseWidth = minWidth;
+}
+
+void AccelStepper::setEnablePin(uint8_t enablePin)
+{
+    _enablePin = enablePin;
+
+    // This happens after construction, so init pin now.
+    if (_enablePin != 0xff)
+    {
+        pinMode(_enablePin, OUTPUT);
+        digitalWrite(_enablePin, HIGH ^ _enableInverted);
+    }
+}
+
+void AccelStepper::setPinsInverted(bool directionInvert, bool stepInvert, bool enableInvert)
+{
+    _pinInverted[0] = stepInvert;
+    _pinInverted[1] = directionInvert;
+    _enableInverted = enableInvert;
+}
+
+void AccelStepper::setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
+{    
+    _pinInverted[0] = pin1Invert;
+    _pinInverted[1] = pin2Invert;
+    _pinInverted[2] = pin3Invert;
+    _pinInverted[3] = pin4Invert;
+    _enableInverted = enableInvert;
+}
+
+// Blocks until the target position is reached and stopped
+void AccelStepper::runToPosition()
+{
+    while (run())
+	;
+}
+
+boolean AccelStepper::runSpeedToPosition()
+{
+    if (_targetPos == _currentPos)
+	return false;
+    if (_targetPos >_currentPos)
+	_direction = DIRECTION_CW;
+    else
+	_direction = DIRECTION_CCW;
+    return runSpeed();
+}
+
+// Blocks until the new target position is reached
+void AccelStepper::runToNewPosition(long position)
+{
+    moveTo(position);
+    runToPosition();
+}
+
+void AccelStepper::stop()
+{
+    if (_speed != 0.0)
+    {    
+	long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)) + 1; // Equation 16 (+integer rounding)
+	if (_speed > 0)
+	    move(stepsToStop);
+	else
+	    move(-stepsToStop);
+    }
+}
+
+bool AccelStepper::isRunning()
+{
+    return !(_speed == 0.0 && _targetPos == _currentPos);
+}

File diff suppressed because it is too large
+ 734 - 0
HTequi-firmware/lib/AccelStepper/AccelStepper.h


+ 17 - 0
HTequi-firmware/lib/AccelStepper/LICENSE

@@ -0,0 +1,17 @@
+This software is Copyright (C) 2008 Mike McCauley. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+Open Source Licensing GPL V2
+
+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 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
+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. Contact info@open.com.au for details.

+ 38 - 0
HTequi-firmware/lib/AccelStepper/MANIFEST

@@ -0,0 +1,38 @@
+AccelStepper/Makefile
+AccelStepper/AccelStepper.h
+AccelStepper/AccelStepper.cpp
+AccelStepper/MultiStepper.h
+AccelStepper/MultiStepper.cpp
+AccelStepper/MANIFEST
+AccelStepper/LICENSE
+AccelStepper/project.cfg
+AccelStepper/keywords.txt
+AccelStepper/doc
+AccelStepper/examples/Blocking/Blocking.pde
+AccelStepper/examples/MultipleSteppers/MultipleSteppers.pde
+AccelStepper/examples/Overshoot/Overshoot.pde
+AccelStepper/examples/ConstantSpeed/ConstantSpeed.pde
+AccelStepper/examples/Random/Random.pde
+AccelStepper/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde
+AccelStepper/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde
+AccelStepper/examples/ProportionalControl/ProportionalControl.pde
+AccelStepper/examples/Bounce/Bounce.pde
+AccelStepper/examples/Quickstop/Quickstop.pde
+AccelStepper/examples/MotorShield/MotorShield.pde
+AccelStepper/examples/DualMotorShield/DualMotorShield.pde
+AccelStepper/examples/MultiStepper/MultiStepper.pde
+AccelStepper/doc
+AccelStepper/doc/index.html
+AccelStepper/doc/functions.html
+AccelStepper/doc/annotated.html
+AccelStepper/doc/tab_l.gif
+AccelStepper/doc/tabs.css
+AccelStepper/doc/files.html
+AccelStepper/doc/classAccelStepper-members.html
+AccelStepper/doc/doxygen.css
+AccelStepper/doc/AccelStepper_8h-source.html
+AccelStepper/doc/tab_r.gif
+AccelStepper/doc/doxygen.png
+AccelStepper/doc/tab_b.gif
+AccelStepper/doc/functions_func.html
+AccelStepper/doc/classAccelStepper.html

+ 30 - 0
HTequi-firmware/lib/AccelStepper/Makefile

@@ -0,0 +1,30 @@
+# Makefile
+#
+# Makefile for the Arduino AccelStepper project
+#
+# Author: Mike McCauley (mikem@airspayce.com)
+# Copyright (C) 2010 Mike McCauley
+# $Id: Makefile,v 1.6 2015/08/25 04:57:29 mikem Exp mikem $
+
+PROJNAME = AccelStepper
+VERSION_MAJOR = 1
+VERSION_MINOR = 59
+
+DISTFILE = $(PROJNAME)-$(VERSION_MAJOR).$(VERSION_MINOR).zip
+
+all:	versioning doxygen dist upload
+
+versioning:
+	sed -i.bak -e 's/AccelStepper-.*\.zip/$(DISTFILE)/' AccelStepper.h
+
+doxygen: 
+	doxygen project.cfg
+
+ci:
+	(cd ..;ci -l `cat $(PROJNAME)/MANIFEST`)
+
+dist:	
+	(cd ..; zip $(PROJNAME)/$(DISTFILE) `cat $(PROJNAME)/MANIFEST`)
+
+upload:
+	rsync -avz $(DISTFILE) doc/ www.airspayce.com:public_html/mikem/arduino/$(PROJNAME)

+ 73 - 0
HTequi-firmware/lib/AccelStepper/MultiStepper.cpp

@@ -0,0 +1,73 @@
+// MultiStepper.cpp
+//
+// Copyright (C) 2015 Mike McCauley
+// $Id: MultiStepper.cpp,v 1.2 2015/10/04 05:16:38 mikem Exp $
+
+#include "MultiStepper.h"
+#include "AccelStepper.h"
+
+MultiStepper::MultiStepper()
+    : _num_steppers(0)
+{
+}
+
+boolean MultiStepper::addStepper(AccelStepper& stepper)
+{
+    if (_num_steppers >= MULTISTEPPER_MAX_STEPPERS)
+	return false; // No room for more
+    _steppers[_num_steppers++] = &stepper;
+    return true;
+}
+
+void MultiStepper::moveTo(long absolute[])
+{
+    // First find the stepper that will take the longest time to move
+    float longestTime = 0.0;
+
+    uint8_t i;
+    for (i = 0; i < _num_steppers; i++)
+    {
+	long thisDistance = absolute[i] - _steppers[i]->currentPosition();
+	float thisTime = abs(thisDistance) / _steppers[i]->maxSpeed();
+
+	if (thisTime > longestTime)
+	    longestTime = thisTime;
+    }
+
+    if (longestTime > 0.0)
+    {
+	// Now work out a new max speed for each stepper so they will all 
+	// arrived at the same time of longestTime
+	for (i = 0; i < _num_steppers; i++)
+	{
+	    long thisDistance = absolute[i] - _steppers[i]->currentPosition();
+	    float thisSpeed = thisDistance / longestTime;
+	    _steppers[i]->moveTo(absolute[i]); // New target position (resets speed)
+	    _steppers[i]->setSpeed(thisSpeed); // New speed
+	}
+    }
+}
+
+// Returns true if any motor is still running to the target position.
+boolean MultiStepper::run()
+{
+    uint8_t i;
+    boolean ret = false;
+    for (i = 0; i < _num_steppers; i++)
+    {
+	if ( _steppers[i]->distanceToGo() != 0)
+	{
+	    _steppers[i]->runSpeed();
+	    ret = true;
+	}
+    }
+    return ret;
+}
+
+// Blocks until all steppers reach their target position and are stopped
+void    MultiStepper::runSpeedToPosition()
+{ 
+    while (run())
+	;
+}
+

+ 78 - 0
HTequi-firmware/lib/AccelStepper/MultiStepper.h

@@ -0,0 +1,78 @@
+// MultiStepper.h
+
+#ifndef MultiStepper_h
+#define MultiStepper_h
+
+#include <stdlib.h>
+#if ARDUINO >= 100
+#include <Arduino.h>
+#else
+#include <WProgram.h>
+#include <wiring.h>
+#endif
+
+#define MULTISTEPPER_MAX_STEPPERS 10
+
+class AccelStepper;
+
+/////////////////////////////////////////////////////////////////////
+/// \class MultiStepper MultiStepper.h <MultiStepper.h>
+/// \brief Operate multiple AccelSteppers in a co-ordinated fashion
+///
+/// This class can manage multiple AccelSteppers (up to MULTISTEPPER_MAX_STEPPERS = 10), 
+/// 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. This can be used to support devices with multiple steppers
+/// on say multiple axes to cause linear diagonal motion. Suitable for use with X-Y plotters, flatbeds,
+/// 3D printers etc
+/// to get linear straight line movement between arbitrary 2d (or 3d or ...) positions.
+///
+/// Caution: only constant speed stepper motion is supported: acceleration and deceleration is not supported
+/// All the steppers managed by MultiStepper will step at a constant speed to their
+/// target (albeit perhaps different speeds for each stepper).
+class MultiStepper
+{
+public:
+    /// Constructor
+    MultiStepper();
+
+    /// Add a stepper to the set of managed steppers
+    /// There is an upper limit of MULTISTEPPER_MAX_STEPPERS = 10 to the number of steppers that can be managed
+    /// \param[in] stepper Reference to a stepper to add to the managed list
+    /// \return true if successful. false if the number of managed steppers would exceed MULTISTEPPER_MAX_STEPPERS
+    boolean addStepper(AccelStepper& stepper);
+
+    /// Set the target positions of all managed steppers 
+    /// according to a coordinate array.
+    /// New speeds will be computed for each stepper so they will all arrive at their 
+    /// respective targets at very close to the same time.
+    /// \param[in] absolute An array of desired absolute stepper positions. absolute[0] will be used to set
+    /// the absolute position of the first stepper added by addStepper() etc. The array must be at least as long as 
+    /// the number of steppers that have been added by addStepper, else results are undefined.
+    void moveTo(long absolute[]);
+    
+    /// Calls runSpeed() on all the managed steppers
+    /// that have not acheived their target position.
+    /// \return true if any stepper is still in the process of running to its target position.
+    boolean run();
+
+    /// Runs all managed steppers until they acheived their target position.
+    /// Blocks until all that position is acheived. If you dont
+    /// want blocking consider using run() instead.
+    void    runSpeedToPosition();
+    
+private:
+    /// Array of pointers to the steppers we are controlling.
+    /// Fills from 0 onwards
+    AccelStepper* _steppers[MULTISTEPPER_MAX_STEPPERS];
+
+    /// Number of steppers we are controlling and the number
+    /// of steppers in _steppers[]
+    uint8_t       _num_steppers;
+};
+
+/// @example MultiStepper.pde
+/// Use MultiStepper class to manage multiple steppers and make them all move to 
+/// the same position at the same time for linear 2d (or 3d) motion.
+
+#endif

+ 420 - 0
HTequi-firmware/lib/AccelStepper/doc/AccelStepper_8h-source.html

@@ -0,0 +1,420 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
+<title>AccelStepper: AccelStepper.h Source File</title>
+<link href="doxygen.css" rel="stylesheet" type="text/css">
+<link href="tabs.css" rel="stylesheet" type="text/css">
+</head><body>
+<!-- Generated by Doxygen 1.5.6 -->
+<div class="navigation" id="top">
+  <div class="tabs">
+    <ul>
+      <li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
+      <li><a href="annotated.html"><span>Classes</span></a></li>
+      <li class="current"><a href="files.html"><span>Files</span></a></li>
+    </ul>
+  </div>
+<h1>AccelStepper.h</h1><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">// AccelStepper.h</span>
+<a name="l00002"></a>00002 <span class="comment">//</span><span class="comment"></span>
+<a name="l00003"></a>00003 <span class="comment">/// \mainpage AccelStepper library for Arduino</span>
+<a name="l00004"></a>00004 <span class="comment">///</span>
+<a name="l00005"></a>00005 <span class="comment">/// This is the Arduino AccelStepper library.</span>
+<a name="l00006"></a>00006 <span class="comment">/// It provides an object-oriented interface for 2 or 4 pin stepper motors.</span>
+<a name="l00007"></a>00007 <span class="comment">///</span>
+<a name="l00008"></a>00008 <span class="comment">/// The standard Arduino IDE includes the Stepper library</span>
+<a name="l00009"></a>00009 <span class="comment">/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is</span>
+<a name="l00010"></a>00010 <span class="comment">/// perfectly adequate for simple, single motor applications.</span>
+<a name="l00011"></a>00011 <span class="comment">///</span>
+<a name="l00012"></a>00012 <span class="comment">/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:</span>
+<a name="l00013"></a>00013 <span class="comment">/// \li Supports acceleration and deceleration</span>
+<a name="l00014"></a>00014 <span class="comment">/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper</span>
+<a name="l00015"></a>00015 <span class="comment">/// \li API functions never delay() or block</span>
+<a name="l00016"></a>00016 <span class="comment">/// \li Supports 2 and 4 wire steppers, plus 4 wire half steppers.</span>
+<a name="l00017"></a>00017 <span class="comment">/// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)</span>
+<a name="l00018"></a>00018 <span class="comment">/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)</span>
+<a name="l00019"></a>00019 <span class="comment">/// \li Very slow speeds are supported</span>
+<a name="l00020"></a>00020 <span class="comment">/// \li Extensive API</span>
+<a name="l00021"></a>00021 <span class="comment">/// \li Subclass support</span>
+<a name="l00022"></a>00022 <span class="comment">///</span>
+<a name="l00023"></a>00023 <span class="comment">/// The latest version of this documentation can be downloaded from </span>
+<a name="l00024"></a>00024 <span class="comment">/// http://www.open.com.au/mikem/arduino/AccelStepper</span>
+<a name="l00025"></a>00025 <span class="comment">///</span>
+<a name="l00026"></a>00026 <span class="comment">/// Example Arduino programs are included to show the main modes of use.</span>
+<a name="l00027"></a>00027 <span class="comment">///</span>
+<a name="l00028"></a>00028 <span class="comment">/// The version of the package that this documentation refers to can be downloaded </span>
+<a name="l00029"></a>00029 <span class="comment">/// from http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.11.zip</span>
+<a name="l00030"></a>00030 <span class="comment">/// You can find the latest version at http://www.open.com.au/mikem/arduino/AccelStepper</span>
+<a name="l00031"></a>00031 <span class="comment">///</span>
+<a name="l00032"></a>00032 <span class="comment">/// Tested on Arduino Diecimila and Mega with arduino-0018 &amp; arduino-0021 </span>
+<a name="l00033"></a>00033 <span class="comment">/// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,</span>
+<a name="l00034"></a>00034 <span class="comment">/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.</span>
+<a name="l00035"></a>00035 <span class="comment">///</span>
+<a name="l00036"></a>00036 <span class="comment">/// \par Installation</span>
+<a name="l00037"></a>00037 <span class="comment">/// Install in the usual way: unzip the distribution zip file to the libraries</span>
+<a name="l00038"></a>00038 <span class="comment">/// sub-folder of your sketchbook. </span>
+<a name="l00039"></a>00039 <span class="comment">///</span>
+<a name="l00040"></a>00040 <span class="comment">/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license</span>
+<a name="l00041"></a>00041 <span class="comment">/// conditions. The main licensing options available are GPL V2 or Commercial:</span>
+<a name="l00042"></a>00042 <span class="comment">/// </span>
+<a name="l00043"></a>00043 <span class="comment">/// \par Open Source Licensing GPL V2</span>
+<a name="l00044"></a>00044 <span class="comment">/// This is the appropriate option if you want to share the source code of your</span>
+<a name="l00045"></a>00045 <span class="comment">/// application with everyone you distribute it to, and you also want to give them</span>
+<a name="l00046"></a>00046 <span class="comment">/// the right to share who uses it. If you wish to use this software under Open</span>
+<a name="l00047"></a>00047 <span class="comment">/// Source Licensing, you must contribute all your source code to the open source</span>
+<a name="l00048"></a>00048 <span class="comment">/// community in accordance with the GPL Version 2 when your application is</span>
+<a name="l00049"></a>00049 <span class="comment">/// distributed. See http://www.gnu.org/copyleft/gpl.html</span>
+<a name="l00050"></a>00050 <span class="comment">/// </span>
+<a name="l00051"></a>00051 <span class="comment">/// \par Commercial Licensing</span>
+<a name="l00052"></a>00052 <span class="comment">/// This is the appropriate option if you are creating proprietary applications</span>
+<a name="l00053"></a>00053 <span class="comment">/// and you are not prepared to distribute and share the source code of your</span>
+<a name="l00054"></a>00054 <span class="comment">/// application. Contact info@open.com.au for details.</span>
+<a name="l00055"></a>00055 <span class="comment">///</span>
+<a name="l00056"></a>00056 <span class="comment">/// \par Revision History</span>
+<a name="l00057"></a>00057 <span class="comment">/// \version 1.0 Initial release</span>
+<a name="l00058"></a>00058 <span class="comment">///</span>
+<a name="l00059"></a>00059 <span class="comment">/// \version 1.1 Added speed() function to get the current speed.</span>
+<a name="l00060"></a>00060 <span class="comment">/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.</span>
+<a name="l00061"></a>00061 <span class="comment">/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1</span>
+<a name="l00062"></a>00062 <span class="comment">/// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.</span>
+<a name="l00063"></a>00063 <span class="comment">/// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements</span>
+<a name="l00064"></a>00064 <span class="comment">///              to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width.</span>
+<a name="l00065"></a>00065 <span class="comment">///              Added checks for already running at max speed and skip further calcs if so. </span>
+<a name="l00066"></a>00066 <span class="comment">/// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang. </span>
+<a name="l00067"></a>00067 <span class="comment">///              Reported by Sandy Noble.</span>
+<a name="l00068"></a>00068 <span class="comment">///              Removed redundant _lastRunTime member.</span>
+<a name="l00069"></a>00069 <span class="comment">/// \version 1.7 Fixed a bug where setCurrentPosition() did always work as expected. Reported by Peter Linhart.</span>
+<a name="l00070"></a>00070 <span class="comment">///              Reported by Sandy Noble.</span>
+<a name="l00071"></a>00071 <span class="comment">///              Removed redundant _lastRunTime member.</span>
+<a name="l00072"></a>00072 <span class="comment">/// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon</span>
+<a name="l00073"></a>00073 <span class="comment">/// \version 1.9 setCurrentPosition() now also sets motor speed to 0.</span>
+<a name="l00074"></a>00074 <span class="comment">/// \version 1.10 Builds on Arduino 1.0</span>
+<a name="l00075"></a>00075 <span class="comment">/// \version 1.11 Improvments from Michael Ellison:</span>
+<a name="l00076"></a>00076 <span class="comment">///   Added optional enable line support for stepper drivers</span>
+<a name="l00077"></a>00077 <span class="comment">///   Added inversion for step/direction/enable lines for stepper drivers</span>
+<a name="l00078"></a>00078 <span class="comment">///</span>
+<a name="l00079"></a>00079 <span class="comment">/// \author  Mike McCauley (mikem@open.com.au)</span>
+<a name="l00080"></a>00080 <span class="comment"></span><span class="comment">// Copyright (C) 2009 Mike McCauley</span>
+<a name="l00081"></a>00081 <span class="comment">// $Id: AccelStepper.h,v 1.5 2011/03/21 00:42:15 mikem Exp mikem $</span>
+<a name="l00082"></a>00082 
+<a name="l00083"></a>00083 <span class="preprocessor">#ifndef AccelStepper_h</span>
+<a name="l00084"></a>00084 <span class="preprocessor"></span><span class="preprocessor">#define AccelStepper_h</span>
+<a name="l00085"></a>00085 <span class="preprocessor"></span>
+<a name="l00086"></a>00086 <span class="preprocessor">#include &lt;stdlib.h&gt;</span>
+<a name="l00087"></a>00087 <span class="preprocessor">#if ARDUINO &gt;= 100</span>
+<a name="l00088"></a>00088 <span class="preprocessor"></span><span class="preprocessor">#include &lt;Arduino.h&gt;</span>
+<a name="l00089"></a>00089 <span class="preprocessor">#else</span>
+<a name="l00090"></a>00090 <span class="preprocessor"></span><span class="preprocessor">#include &lt;wiring.h&gt;</span>
+<a name="l00091"></a>00091 <span class="preprocessor">#endif</span>
+<a name="l00092"></a>00092 <span class="preprocessor"></span>
+<a name="l00093"></a>00093 <span class="comment">// These defs cause trouble on some versions of Arduino</span>
+<a name="l00094"></a>00094 <span class="preprocessor">#undef round</span>
+<a name="l00095"></a>00095 <span class="preprocessor"></span><span class="comment"></span>
+<a name="l00096"></a>00096 <span class="comment">/////////////////////////////////////////////////////////////////////</span>
+<a name="l00097"></a>00097 <span class="comment">/// \class AccelStepper AccelStepper.h &lt;AccelStepper.h&gt;</span>
+<a name="l00098"></a>00098 <span class="comment">/// \brief Support for stepper motors with acceleration etc.</span>
+<a name="l00099"></a>00099 <span class="comment">///</span>
+<a name="l00100"></a>00100 <span class="comment">/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional</span>
+<a name="l00101"></a>00101 <span class="comment">/// acceleration, deceleration, absolute positioning commands etc. Multiple</span>
+<a name="l00102"></a>00102 <span class="comment">/// simultaneous steppers are supported, all moving </span>
+<a name="l00103"></a>00103 <span class="comment">/// at different speeds and accelerations. </span>
+<a name="l00104"></a>00104 <span class="comment">///</span>
+<a name="l00105"></a>00105 <span class="comment">/// \par Operation</span>
+<a name="l00106"></a>00106 <span class="comment">/// This module operates by computing a step time in microseconds. The step</span>
+<a name="l00107"></a>00107 <span class="comment">/// time is recomputed after each step and after speed and acceleration</span>
+<a name="l00108"></a>00108 <span class="comment">/// parameters are changed by the caller. The time of each step is recorded in</span>
+<a name="l00109"></a>00109 <span class="comment">/// microseconds. The run() function steps the motor if a new step is due.</span>
+<a name="l00110"></a>00110 <span class="comment">/// The run() function must be called frequently until the motor is in the</span>
+<a name="l00111"></a>00111 <span class="comment">/// desired position, after which time run() will do nothing.</span>
+<a name="l00112"></a>00112 <span class="comment">///</span>
+<a name="l00113"></a>00113 <span class="comment">/// \par Positioning</span>
+<a name="l00114"></a>00114 <span class="comment">/// Positions are specified by a signed long integer. At</span>
+<a name="l00115"></a>00115 <span class="comment">/// construction time, the current position of the motor is consider to be 0. Positive</span>
+<a name="l00116"></a>00116 <span class="comment">/// positions are clockwise from the initial position; negative positions are</span>
+<a name="l00117"></a>00117 <span class="comment">/// anticlockwise. The curent position can be altered for instance after</span>
+<a name="l00118"></a>00118 <span class="comment">/// initialization positioning.</span>
+<a name="l00119"></a>00119 <span class="comment">///</span>
+<a name="l00120"></a>00120 <span class="comment">/// \par Caveats</span>
+<a name="l00121"></a>00121 <span class="comment">/// This is an open loop controller: If the motor stalls or is oversped,</span>
+<a name="l00122"></a>00122 <span class="comment">/// AccelStepper will not have a correct </span>
+<a name="l00123"></a>00123 <span class="comment">/// idea of where the motor really is (since there is no feedback of the motor's</span>
+<a name="l00124"></a>00124 <span class="comment">/// real position. We only know where we _think_ it is, relative to the</span>
+<a name="l00125"></a>00125 <span class="comment">/// initial starting point).</span>
+<a name="l00126"></a>00126 <span class="comment">///</span>
+<a name="l00127"></a>00127 <span class="comment">/// The fastest motor speed that can be reliably supported is 4000 steps per</span>
+<a name="l00128"></a>00128 <span class="comment">/// second (4 kHz) at a clock frequency of 16 MHz. However, any speed less than that</span>
+<a name="l00129"></a>00129 <span class="comment">/// down to very slow speeds (much less than one per second) are also supported,</span>
+<a name="l00130"></a>00130 <span class="comment">/// provided the run() function is called frequently enough to step the motor</span>
+<a name="l00131"></a>00131 <span class="comment">/// whenever required for the speed set.</span>
+<a name="l00132"></a><a class="code" href="classAccelStepper.html">00132</a> <span class="comment"></span><span class="keyword">class </span><a class="code" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a>
+<a name="l00133"></a>00133 {
+<a name="l00134"></a>00134 <span class="keyword">public</span>:<span class="comment"></span>
+<a name="l00135"></a>00135 <span class="comment">    /// Constructor. You can have multiple simultaneous steppers, all moving</span>
+<a name="l00136"></a>00136 <span class="comment">    /// at different speeds and accelerations, provided you call their run()</span>
+<a name="l00137"></a>00137 <span class="comment">    /// functions at frequent enough intervals. Current Position is set to 0, target</span>
+<a name="l00138"></a>00138 <span class="comment">    /// position is set to 0. MaxSpeed and Acceleration default to 1.0.</span>
+<a name="l00139"></a>00139 <span class="comment">    /// The motor pins will be initialised to OUTPUT mode during the</span>
+<a name="l00140"></a>00140 <span class="comment">    /// constructor by a call to enableOutputs().</span>
+<a name="l00141"></a>00141 <span class="comment">    /// \param[in] pins Number of pins to interface to. 1, 2 or 4 are</span>
+<a name="l00142"></a>00142 <span class="comment">    /// supported. 1 means a stepper driver (with Step and Direction pins).</span>
+<a name="l00143"></a>00143 <span class="comment">    /// If an enable line is also needed, call setEnablePin() after construction.</span>
+<a name="l00144"></a>00144 <span class="comment">    /// You may also invert the pins using setPinsInverted().</span>
+<a name="l00145"></a>00145 <span class="comment">    /// 2 means a 2 wire stepper. 4 means a 4 wire stepper. 8 means a 4 wire half stepper</span>
+<a name="l00146"></a>00146 <span class="comment">    /// Defaults to 4 pins.</span>
+<a name="l00147"></a>00147 <span class="comment">    /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults</span>
+<a name="l00148"></a>00148 <span class="comment">    /// to pin 2. For a driver (pins==1), this is the Step input to the driver. Low to high transition means to step)</span>
+<a name="l00149"></a>00149 <span class="comment">    /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults</span>
+<a name="l00150"></a>00150 <span class="comment">    /// to pin 3. For a driver (pins==1), this is the Direction input the driver. High means forward.</span>
+<a name="l00151"></a>00151 <span class="comment">    /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults</span>
+<a name="l00152"></a>00152 <span class="comment">    /// to pin 4.</span>
+<a name="l00153"></a>00153 <span class="comment">    /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults</span>
+<a name="l00154"></a>00154 <span class="comment">    /// to pin 5.</span>
+<a name="l00155"></a>00155 <span class="comment"></span>    <a class="code" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(uint8_t pins = 4, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5);
+<a name="l00156"></a>00156 <span class="comment"></span>
+<a name="l00157"></a>00157 <span class="comment">    /// Alternate Constructor which will call your own functions for forward and backward steps. </span>
+<a name="l00158"></a>00158 <span class="comment">    /// You can have multiple simultaneous steppers, all moving</span>
+<a name="l00159"></a>00159 <span class="comment">    /// at different speeds and accelerations, provided you call their run()</span>
+<a name="l00160"></a>00160 <span class="comment">    /// functions at frequent enough intervals. Current Position is set to 0, target</span>
+<a name="l00161"></a>00161 <span class="comment">    /// position is set to 0. MaxSpeed and Acceleration default to 1.0.</span>
+<a name="l00162"></a>00162 <span class="comment">    /// Any motor initialization should happen before hand, no pins are used or initialized.</span>
+<a name="l00163"></a>00163 <span class="comment">    /// \param[in] forward void-returning procedure that will make a forward step</span>
+<a name="l00164"></a>00164 <span class="comment">    /// \param[in] backward void-returning procedure that will make a backward step</span>
+<a name="l00165"></a>00165 <span class="comment"></span>    <a class="code" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(<span class="keywordtype">void</span> (*forward)(), <span class="keywordtype">void</span> (*backward)());
+<a name="l00166"></a>00166     <span class="comment"></span>
+<a name="l00167"></a>00167 <span class="comment">    /// Set the target position. The run() function will try to move the motor</span>
+<a name="l00168"></a>00168 <span class="comment">    /// from the current position to the target position set by the most</span>
+<a name="l00169"></a>00169 <span class="comment">    /// recent call to this function.</span>
+<a name="l00170"></a>00170 <span class="comment">    /// \param[in] absolute The desired absolute position. Negative is</span>
+<a name="l00171"></a>00171 <span class="comment">    /// anticlockwise from the 0 position.</span>
+<a name="l00172"></a>00172 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo</a>(<span class="keywordtype">long</span> absolute); 
+<a name="l00173"></a>00173 <span class="comment"></span>
+<a name="l00174"></a>00174 <span class="comment">    /// Set the target position relative to the current position</span>
+<a name="l00175"></a>00175 <span class="comment">    /// \param[in] relative The desired position relative to the current position. Negative is</span>
+<a name="l00176"></a>00176 <span class="comment">    /// anticlockwise from the current position.</span>
+<a name="l00177"></a>00177 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(<span class="keywordtype">long</span> relative);
+<a name="l00178"></a>00178 <span class="comment"></span>
+<a name="l00179"></a>00179 <span class="comment">    /// Poll the motor and step it if a step is due, implementing</span>
+<a name="l00180"></a>00180 <span class="comment">    /// accelerations and decelerations to achive the ratget position. You must call this as</span>
+<a name="l00181"></a>00181 <span class="comment">    /// fequently as possible, but at least once per minimum step interval,</span>
+<a name="l00182"></a>00182 <span class="comment">    /// preferably in your main loop.</span>
+<a name="l00183"></a>00183 <span class="comment">    /// \return true if the motor is at the target position.</span>
+<a name="l00184"></a>00184 <span class="comment"></span>    <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run</a>();
+<a name="l00185"></a>00185 <span class="comment"></span>
+<a name="l00186"></a>00186 <span class="comment">    /// Poll the motor and step it if a step is due, implmenting a constant</span>
+<a name="l00187"></a>00187 <span class="comment">    /// speed as set by the most recent call to setSpeed().</span>
+<a name="l00188"></a>00188 <span class="comment">    /// \return true if the motor was stepped.</span>
+<a name="l00189"></a>00189 <span class="comment"></span>    <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>();
+<a name="l00190"></a>00190 <span class="comment"></span>
+<a name="l00191"></a>00191 <span class="comment">    /// Sets the maximum permitted speed. the run() function will accelerate</span>
+<a name="l00192"></a>00192 <span class="comment">    /// up to the speed set by this function.</span>
+<a name="l00193"></a>00193 <span class="comment">    /// \param[in] speed The desired maximum speed in steps per second. Must</span>
+<a name="l00194"></a>00194 <span class="comment">    /// be &gt; 0. Speeds of more than 1000 steps per second are unreliable. </span>
+<a name="l00195"></a>00195 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(<span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>);
+<a name="l00196"></a>00196 <span class="comment"></span>
+<a name="l00197"></a>00197 <span class="comment">    /// Sets the acceleration and deceleration parameter.</span>
+<a name="l00198"></a>00198 <span class="comment">    /// \param[in] acceleration The desired acceleration in steps per second</span>
+<a name="l00199"></a>00199 <span class="comment">    /// per second. Must be &gt; 0.</span>
+<a name="l00200"></a>00200 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(<span class="keywordtype">float</span> acceleration);
+<a name="l00201"></a>00201 <span class="comment"></span>
+<a name="l00202"></a>00202 <span class="comment">    /// Sets the desired constant speed for use with runSpeed().</span>
+<a name="l00203"></a>00203 <span class="comment">    /// \param[in] speed The desired constant speed in steps per</span>
+<a name="l00204"></a>00204 <span class="comment">    /// second. Positive is clockwise. Speeds of more than 1000 steps per</span>
+<a name="l00205"></a>00205 <span class="comment">    /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for</span>
+<a name="l00206"></a>00206 <span class="comment">    /// once per hour, approximately. Speed accuracy depends on the Arduino</span>
+<a name="l00207"></a>00207 <span class="comment">    /// crystal. Jitter depends on how frequently you call the runSpeed() function.</span>
+<a name="l00208"></a>00208 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(<span class="keywordtype">float</span> speed);
+<a name="l00209"></a>00209 <span class="comment"></span>
+<a name="l00210"></a>00210 <span class="comment">    /// The most recently set speed</span>
+<a name="l00211"></a>00211 <span class="comment">    /// \return the most recent speed in steps per second</span>
+<a name="l00212"></a>00212 <span class="comment"></span>    <span class="keywordtype">float</span>   <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>();
+<a name="l00213"></a>00213 <span class="comment"></span>
+<a name="l00214"></a>00214 <span class="comment">    /// The distance from the current position to the target position.</span>
+<a name="l00215"></a>00215 <span class="comment">    /// \return the distance from the current position to the target position</span>
+<a name="l00216"></a>00216 <span class="comment">    /// in steps. Positive is clockwise from the current position.</span>
+<a name="l00217"></a>00217 <span class="comment"></span>    <span class="keywordtype">long</span>    <a class="code" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>();
+<a name="l00218"></a>00218 <span class="comment"></span>
+<a name="l00219"></a>00219 <span class="comment">    /// The most recently set target position.</span>
+<a name="l00220"></a>00220 <span class="comment">    /// \return the target position</span>
+<a name="l00221"></a>00221 <span class="comment">    /// in steps. Positive is clockwise from the 0 position.</span>
+<a name="l00222"></a>00222 <span class="comment"></span>    <span class="keywordtype">long</span>    <a class="code" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">targetPosition</a>();
+<a name="l00223"></a>00223 
+<a name="l00224"></a>00224 <span class="comment"></span>
+<a name="l00225"></a>00225 <span class="comment">    /// The currently motor position.</span>
+<a name="l00226"></a>00226 <span class="comment">    /// \return the current motor position</span>
+<a name="l00227"></a>00227 <span class="comment">    /// in steps. Positive is clockwise from the 0 position.</span>
+<a name="l00228"></a>00228 <span class="comment"></span>    <span class="keywordtype">long</span>    <a class="code" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>();  
+<a name="l00229"></a>00229 <span class="comment"></span>
+<a name="l00230"></a>00230 <span class="comment">    /// Resets the current position of the motor, so that wherever the motor</span>
+<a name="l00231"></a>00231 <span class="comment">    /// happens to be right now is considered to be the new 0 position. Useful</span>
+<a name="l00232"></a>00232 <span class="comment">    /// for setting a zero position on a stepper after an initial hardware</span>
+<a name="l00233"></a>00233 <span class="comment">    /// positioning move.</span>
+<a name="l00234"></a>00234 <span class="comment">    /// Has the side effect of setting the current motor speed to 0.</span>
+<a name="l00235"></a>00235 <span class="comment">    /// \param[in] position The position in steps of wherever the motor</span>
+<a name="l00236"></a>00236 <span class="comment">    /// happens to be right now.</span>
+<a name="l00237"></a>00237 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(<span class="keywordtype">long</span> position);  
+<a name="l00238"></a>00238     <span class="comment"></span>
+<a name="l00239"></a>00239 <span class="comment">    /// Moves the motor to the target position and blocks until it is at</span>
+<a name="l00240"></a>00240 <span class="comment">    /// position. Dont use this in event loops, since it blocks.</span>
+<a name="l00241"></a>00241 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>();
+<a name="l00242"></a>00242 <span class="comment"></span>
+<a name="l00243"></a>00243 <span class="comment">    /// Runs at the currently selected speed until the target position is reached</span>
+<a name="l00244"></a>00244 <span class="comment">    /// Does not implement accelerations.</span>
+<a name="l00245"></a>00245 <span class="comment"></span>    <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>();
+<a name="l00246"></a>00246 <span class="comment"></span>
+<a name="l00247"></a>00247 <span class="comment">    /// Moves the motor to the new target position and blocks until it is at</span>
+<a name="l00248"></a>00248 <span class="comment">    /// position. Dont use this in event loops, since it blocks.</span>
+<a name="l00249"></a>00249 <span class="comment">    /// \param[in] position The new target position.</span>
+<a name="l00250"></a>00250 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(<span class="keywordtype">long</span> position);
+<a name="l00251"></a>00251 <span class="comment"></span>
+<a name="l00252"></a>00252 <span class="comment">    /// Disable motor pin outputs by setting them all LOW</span>
+<a name="l00253"></a>00253 <span class="comment">    /// Depending on the design of your electronics this may turn off</span>
+<a name="l00254"></a>00254 <span class="comment">    /// the power to the motor coils, saving power.</span>
+<a name="l00255"></a>00255 <span class="comment">    /// This is useful to support Arduino low power modes: disable the outputs</span>
+<a name="l00256"></a>00256 <span class="comment">    /// during sleep and then reenable with enableOutputs() before stepping</span>
+<a name="l00257"></a>00257 <span class="comment">    /// again.</span>
+<a name="l00258"></a>00258 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>();
+<a name="l00259"></a>00259 <span class="comment"></span>
+<a name="l00260"></a>00260 <span class="comment">    /// Enable motor pin outputs by setting the motor pins to OUTPUT</span>
+<a name="l00261"></a>00261 <span class="comment">    /// mode. Called automatically by the constructor.</span>
+<a name="l00262"></a>00262 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs</a>();
+<a name="l00263"></a>00263 <span class="comment"></span>
+<a name="l00264"></a>00264 <span class="comment">    /// Sets the minimum pulse width allowed by the stepper driver.</span>
+<a name="l00265"></a>00265 <span class="comment">    /// \param[in] minWidth The minimum pulse width in microseconds.</span>
+<a name="l00266"></a>00266 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#f4d3818e691dad5dc518308796ccf154">setMinPulseWidth</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> minWidth);
+<a name="l00267"></a>00267 <span class="comment"></span>
+<a name="l00268"></a>00268 <span class="comment">    /// Sets the enable pin number for stepper drivers.</span>
+<a name="l00269"></a>00269 <span class="comment">        /// 0xFF indicates unused (default).</span>
+<a name="l00270"></a>00270 <span class="comment">    /// Otherwise, if a pin is set, the pin will be turned on when </span>
+<a name="l00271"></a>00271 <span class="comment">    /// enableOutputs() is called and switched off when disableOutputs() </span>
+<a name="l00272"></a>00272 <span class="comment">    /// is called.</span>
+<a name="l00273"></a>00273 <span class="comment">    /// \param[in] enablePin Arduino digital pin number for motor enable</span>
+<a name="l00274"></a>00274 <span class="comment">    /// \sa setPinsInverted</span>
+<a name="l00275"></a>00275 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#56a81c5f00d02ca19646718e88e974c0">setEnablePin</a>(uint8_t enablePin = 0xff);
+<a name="l00276"></a>00276 <span class="comment"></span>
+<a name="l00277"></a>00277 <span class="comment">    /// Sets the inversion for stepper driver pins</span>
+<a name="l00278"></a>00278 <span class="comment">    /// \param[in] direction True for inverted direction pin, false for non-inverted</span>
+<a name="l00279"></a>00279 <span class="comment">    /// \param[in] step      True for inverted step pin, false for non-inverted</span>
+<a name="l00280"></a>00280 <span class="comment">    /// \param[in] enable    True for inverted enable pin, false (default) for non-inverted</span>
+<a name="l00281"></a>00281 <span class="comment"></span>    <span class="keywordtype">void</span>    <a class="code" href="classAccelStepper.html#797b4bdb580d4ca7a1cfeabe3df0de35">setPinsInverted</a>(<span class="keywordtype">bool</span> direction, <span class="keywordtype">bool</span> <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>, <span class="keywordtype">bool</span> enable = <span class="keyword">false</span>);
+<a name="l00282"></a>00282 
+<a name="l00283"></a>00283 <span class="keyword">protected</span>:
+<a name="l00284"></a>00284 <span class="comment"></span>
+<a name="l00285"></a>00285 <span class="comment">    /// Forces the library to compute a new instantaneous speed and set that as</span>
+<a name="l00286"></a>00286 <span class="comment">    /// the current speed. Calls</span>
+<a name="l00287"></a>00287 <span class="comment">    /// desiredSpeed(), which can be overridden by subclasses. It is called by</span>
+<a name="l00288"></a>00288 <span class="comment">    /// the library:</span>
+<a name="l00289"></a>00289 <span class="comment">    /// \li  after each step</span>
+<a name="l00290"></a>00290 <span class="comment">    /// \li  after change to maxSpeed through setMaxSpeed()</span>
+<a name="l00291"></a>00291 <span class="comment">    /// \li  after change to acceleration through setAcceleration()</span>
+<a name="l00292"></a>00292 <span class="comment">    /// \li  after change to target position (relative or absolute) through</span>
+<a name="l00293"></a>00293 <span class="comment">    /// move() or moveTo()</span>
+<a name="l00294"></a>00294 <span class="comment"></span>    <span class="keywordtype">void</span>           <a class="code" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">computeNewSpeed</a>();
+<a name="l00295"></a>00295 <span class="comment"></span>
+<a name="l00296"></a>00296 <span class="comment">    /// Called to execute a step. Only called when a new step is</span>
+<a name="l00297"></a>00297 <span class="comment">    /// required. Subclasses may override to implement new stepping</span>
+<a name="l00298"></a>00298 <span class="comment">    /// interfaces. The default calls step1(), step2(), step4() or step8() depending on the</span>
+<a name="l00299"></a>00299 <span class="comment">    /// number of pins defined for the stepper.</span>
+<a name="l00300"></a>00300 <span class="comment">    /// \param[in] step The current step phase number (0 to 7)</span>
+<a name="l00301"></a>00301 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>(uint8_t step);
+<a name="l00302"></a>00302 <span class="comment"></span>
+<a name="l00303"></a>00303 <span class="comment">    /// Called to execute a step using stepper functions (pins = 0) Only called when a new step is</span>
+<a name="l00304"></a>00304 <span class="comment">    /// required. Calls _forward() or _backward() to perform the step</span>
+<a name="l00305"></a>00305 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#889f109756aa4c0a2feefebd8081a337">step0</a>(<span class="keywordtype">void</span>);
+<a name="l00306"></a>00306 <span class="comment"></span>
+<a name="l00307"></a>00307 <span class="comment">    /// Called to execute a step on a stepper drover (ie where pins == 1). Only called when a new step is</span>
+<a name="l00308"></a>00308 <span class="comment">    /// required. Subclasses may override to implement new stepping</span>
+<a name="l00309"></a>00309 <span class="comment">    /// interfaces. The default sets or clears the outputs of Step pin1 to step, </span>
+<a name="l00310"></a>00310 <span class="comment">    /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond</span>
+<a name="l00311"></a>00311 <span class="comment">    /// which is the minimum STEP pulse width for the 3967 driver.</span>
+<a name="l00312"></a>00312 <span class="comment">    /// \param[in] step The current step phase number (0 to 7)</span>
+<a name="l00313"></a>00313 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1</a>(uint8_t step);
+<a name="l00314"></a>00314 <span class="comment"></span>
+<a name="l00315"></a>00315 <span class="comment">    /// Called to execute a step on a 2 pin motor. Only called when a new step is</span>
+<a name="l00316"></a>00316 <span class="comment">    /// required. Subclasses may override to implement new stepping</span>
+<a name="l00317"></a>00317 <span class="comment">    /// interfaces. The default sets or clears the outputs of pin1 and pin2</span>
+<a name="l00318"></a>00318 <span class="comment">    /// \param[in] step The current step phase number (0 to 7)</span>
+<a name="l00319"></a>00319 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2</a>(uint8_t step);
+<a name="l00320"></a>00320 <span class="comment"></span>
+<a name="l00321"></a>00321 <span class="comment">    /// Called to execute a step on a 4 pin motor. Only called when a new step is</span>
+<a name="l00322"></a>00322 <span class="comment">    /// required. Subclasses may override to implement new stepping</span>
+<a name="l00323"></a>00323 <span class="comment">    /// interfaces. The default sets or clears the outputs of pin1, pin2,</span>
+<a name="l00324"></a>00324 <span class="comment">    /// pin3, pin4.</span>
+<a name="l00325"></a>00325 <span class="comment">    /// \param[in] step The current step phase number (0 to 7)</span>
+<a name="l00326"></a>00326 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4</a>(uint8_t step);
+<a name="l00327"></a>00327 <span class="comment"></span>
+<a name="l00328"></a>00328 <span class="comment">    /// Called to execute a step on a 4 pin half-steper motor. Only called when a new step is</span>
+<a name="l00329"></a>00329 <span class="comment">    /// required. Subclasses may override to implement new stepping</span>
+<a name="l00330"></a>00330 <span class="comment">    /// interfaces. The default sets or clears the outputs of pin1, pin2,</span>
+<a name="l00331"></a>00331 <span class="comment">    /// pin3, pin4.</span>
+<a name="l00332"></a>00332 <span class="comment">    /// \param[in] step The current step phase number (0 to 7)</span>
+<a name="l00333"></a>00333 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">void</span>   <a class="code" href="classAccelStepper.html#5b33d1088e2beaf2176c42b08fb675ea">step8</a>(uint8_t step);
+<a name="l00334"></a>00334 <span class="comment"></span>
+<a name="l00335"></a>00335 <span class="comment">    /// Compute and return the desired speed. The default algorithm uses</span>
+<a name="l00336"></a>00336 <span class="comment">    /// maxSpeed, acceleration and the current speed to set a new speed to</span>
+<a name="l00337"></a>00337 <span class="comment">    /// move the motor from teh current position to the target</span>
+<a name="l00338"></a>00338 <span class="comment">    /// position. Subclasses may override this to provide an alternate</span>
+<a name="l00339"></a>00339 <span class="comment">    /// algorithm (but do not block). Called by computeNewSpeed whenever a new speed neds to be</span>
+<a name="l00340"></a>00340 <span class="comment">    /// computed. </span>
+<a name="l00341"></a>00341 <span class="comment"></span>    <span class="keyword">virtual</span> <span class="keywordtype">float</span>  <a class="code" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed</a>();
+<a name="l00342"></a>00342     
+<a name="l00343"></a>00343 <span class="keyword">private</span>:<span class="comment"></span>
+<a name="l00344"></a>00344 <span class="comment">    /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a</span>
+<a name="l00345"></a>00345 <span class="comment">    /// bipolar, and 4 pins is a unipolar.</span>
+<a name="l00346"></a>00346 <span class="comment"></span>    uint8_t        _pins;          <span class="comment">// 2 or 4</span>
+<a name="l00347"></a>00347 <span class="comment"></span>
+<a name="l00348"></a>00348 <span class="comment">    /// Arduino pin number for the 2 or 4 pins required to interface to the</span>
+<a name="l00349"></a>00349 <span class="comment">    /// stepper motor.</span>
+<a name="l00350"></a>00350 <span class="comment"></span>    uint8_t        _pin1, _pin2, _pin3, _pin4;
+<a name="l00351"></a>00351 <span class="comment"></span>
+<a name="l00352"></a>00352 <span class="comment">    /// The current absolution position in steps.</span>
+<a name="l00353"></a>00353 <span class="comment"></span>    <span class="keywordtype">long</span>           _currentPos;    <span class="comment">// Steps</span>
+<a name="l00354"></a>00354 <span class="comment"></span>
+<a name="l00355"></a>00355 <span class="comment">    /// The target position in steps. The AccelStepper library will move the</span>
+<a name="l00356"></a>00356 <span class="comment">    /// motor from the _currentPos to the _targetPos, taking into account the</span>
+<a name="l00357"></a>00357 <span class="comment">    /// max speed, acceleration and deceleration</span>
+<a name="l00358"></a>00358 <span class="comment"></span>    <span class="keywordtype">long</span>           _targetPos;     <span class="comment">// Steps</span>
+<a name="l00359"></a>00359 <span class="comment"></span>
+<a name="l00360"></a>00360 <span class="comment">    /// The current motos speed in steps per second</span>
+<a name="l00361"></a>00361 <span class="comment">    /// Positive is clockwise</span>
+<a name="l00362"></a>00362 <span class="comment"></span>    <span class="keywordtype">float</span>          _speed;         <span class="comment">// Steps per second</span>
+<a name="l00363"></a>00363 <span class="comment"></span>
+<a name="l00364"></a>00364 <span class="comment">    /// The maximum permitted speed in steps per second. Must be &gt; 0.</span>
+<a name="l00365"></a>00365 <span class="comment"></span>    <span class="keywordtype">float</span>          _maxSpeed;
+<a name="l00366"></a>00366 <span class="comment"></span>
+<a name="l00367"></a>00367 <span class="comment">    /// The acceleration to use to accelerate or decelerate the motor in steps</span>
+<a name="l00368"></a>00368 <span class="comment">    /// per second per second. Must be &gt; 0</span>
+<a name="l00369"></a>00369 <span class="comment"></span>    <span class="keywordtype">float</span>          _acceleration;
+<a name="l00370"></a>00370 <span class="comment"></span>
+<a name="l00371"></a>00371 <span class="comment">    /// The current interval between steps in microseconds</span>
+<a name="l00372"></a>00372 <span class="comment"></span>    <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span>  _stepInterval;
+<a name="l00373"></a>00373 <span class="comment"></span>
+<a name="l00374"></a>00374 <span class="comment">    /// The last step time in microseconds</span>
+<a name="l00375"></a>00375 <span class="comment"></span>    <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span>  _lastStepTime;
+<a name="l00376"></a>00376 <span class="comment"></span>
+<a name="l00377"></a>00377 <span class="comment">    /// The minimum allowed pulse width in microseconds</span>
+<a name="l00378"></a>00378 <span class="comment"></span>    <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span>   _minPulseWidth;
+<a name="l00379"></a>00379 <span class="comment"></span>
+<a name="l00380"></a>00380 <span class="comment">    /// Is the direction pin inverted?</span>
+<a name="l00381"></a>00381 <span class="comment"></span>    <span class="keywordtype">bool</span>           _dirInverted;
+<a name="l00382"></a>00382 <span class="comment"></span>
+<a name="l00383"></a>00383 <span class="comment">    /// Is the step pin inverted?</span>
+<a name="l00384"></a>00384 <span class="comment"></span>    <span class="keywordtype">bool</span>           _stepInverted;
+<a name="l00385"></a>00385 <span class="comment"></span>
+<a name="l00386"></a>00386 <span class="comment">    /// Is the enable pin inverted?</span>
+<a name="l00387"></a>00387 <span class="comment"></span>    <span class="keywordtype">bool</span>           _enableInverted;
+<a name="l00388"></a>00388 <span class="comment"></span>
+<a name="l00389"></a>00389 <span class="comment">        /// Enable pin for stepper driver, or 0xFF if unused.</span>
+<a name="l00390"></a>00390 <span class="comment"></span>    uint8_t        _enablePin;
+<a name="l00391"></a>00391 
+<a name="l00392"></a>00392     <span class="comment">// The pointer to a forward-step procedure</span>
+<a name="l00393"></a>00393     void (*_forward)();
+<a name="l00394"></a>00394 
+<a name="l00395"></a>00395     <span class="comment">// The pointer to a backward-step procedure</span>
+<a name="l00396"></a>00396     void (*_backward)();
+<a name="l00397"></a>00397 };
+<a name="l00398"></a>00398 
+<a name="l00399"></a>00399 <span class="preprocessor">#endif </span>
+</pre></div></div>
+<hr size="1"><address style="text-align: right;"><small>Generated on Sun Jan 8 17:27:41 2012 for AccelStepper by&nbsp;
+<a href="http://www.doxygen.org/index.html">
+<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
+</body>
+</html>

+ 58 - 0
HTequi-firmware/lib/AccelStepper/doc/annotated.html

@@ -0,0 +1,58 @@
+<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
+<html xmlns="http://www.w3.org/1999/xhtml">
+<head>
+<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
+<meta http-equiv="X-UA-Compatible" content="IE=9"/>
+<meta name="generator" content="Doxygen 1.8.13"/>
+<meta name="viewport" content="width=device-width, initial-scale=1"/>
+<title>AccelStepper: Class List</title>
+<link href="tabs.css" rel="stylesheet" type="text/css"/>
+<script type="text/javascript" src="jquery.js"></script>
+<script type="text/javascript" src="dynsections.js"></script>
+<link href="doxygen.css" rel="stylesheet" type="text/css" />
+</head>
+<body>
+<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
+<div id="titlearea">
+<table cellspacing="0" cellpadding="0">
+ <tbody>
+ <tr style="height: 56px;">
+  <td id="projectalign" style="padding-left: 0.5em;">
+   <div id="projectname">AccelStepper
+   </div>
+  </td>
+ </tr>
+ </tbody>
+</table>
+</div>
+<!-- end header part -->
+<!-- Generated by Doxygen 1.8.13 -->
+<script type="text/javascript" src="menudata.js"></script>
+<script type="text/javascript" src="menu.js"></script>
+<script type="text/javascript">
+$(function() {
+  initMenu('',false,false,'search.php','Search');
+});
+</script>
+<div id="main-nav"></div>
+</div><!-- top -->
+<div class="header">
+  <div class="headertitle">
+<div class="title">Class List</div>  </div>
+</div><!--header-->
+<div class="contents">
+<div class="textblock">Here are the classes, structs, unions and interfaces with brief descriptions:</div><div class="directory">
+<table class="directory">
+<tr id="row_0_" class="even"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><span class="icona"><span class="icon">C</span></span><a class="el" href="classAccelStepper.html" target="_self">AccelStepper</a></td><td class="desc">Support for stepper motors with acceleration etc </td></tr>
+<tr id="row_1_"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><span class="icona"><span class="icon">C</span></span><a class="el" href="classMultiStepper.html" target="_self">MultiStepper</a></td><td class="desc">Operate multiple AccelSteppers in a co-ordinated fashion </td></tr>
+</table>
+</div><!-- directory -->
+</div><!-- contents -->
+<!-- start footer part -->
+<hr class="footer"/><address class="footer"><small>
+Generated by &#160;<a href="http://www.doxygen.org/index.html">
+<img class="footer" src="doxygen.png" alt="doxygen"/>
+</a> 1.8.13
+</small></address>
+</body>
+</html>

+ 103 - 0
HTequi-firmware/lib/AccelStepper/doc/classAccelStepper-members.html

@@ -0,0 +1,103 @@
+<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
+<html xmlns="http://www.w3.org/1999/xhtml">
+<head>
+<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
+<meta http-equiv="X-UA-Compatible" content="IE=9"/>
+<meta name="generator" content="Doxygen 1.8.13"/>
+<meta name="viewport" content="width=device-width, initial-scale=1"/>
+<title>AccelStepper: Member List</title>
+<link href="tabs.css" rel="stylesheet" type="text/css"/>
+<script type="text/javascript" src="jquery.js"></script>
+<script type="text/javascript" src="dynsections.js"></script>
+<link href="doxygen.css" rel="stylesheet" type="text/css" />
+</head>
+<body>
+<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
+<div id="titlearea">
+<table cellspacing="0" cellpadding="0">
+ <tbody>
+ <tr style="height: 56px;">
+  <td id="projectalign" style="padding-left: 0.5em;">
+   <div id="projectname">AccelStepper
+   </div>
+  </td>
+ </tr>
+ </tbody>
+</table>
+</div>
+<!-- end header part -->
+<!-- Generated by Doxygen 1.8.13 -->
+<script type="text/javascript" src="menudata.js"></script>
+<script type="text/javascript" src="menu.js"></script>
+<script type="text/javascript">
+$(function() {
+  initMenu('',false,false,'search.php','Search');
+});
+</script>
+<div id="main-nav"></div>
+</div><!-- top -->
+<div class="header">
+  <div class="headertitle">
+<div class="title">AccelStepper Member List</div>  </div>
+</div><!--header-->
+<div class="contents">
+
+<p>This is the complete list of members for <a class="el" href="classAccelStepper.html">AccelStepper</a>, including all inherited members.</p>
+<table class="directory">
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a35162cdf8ed9a98f98984c177d5ade58">_direction</a></td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>(uint8_t interface=AccelStepper::FULL4WIRE, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5, bool enable=true)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#afa3061ce813303a8f2fa206ee8d012bd">AccelStepper</a>(void(*forward)(), void(*backward)())</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">computeNewSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228">Direction</a> enum name</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228a6959a4549f734bd771d418f995ba4fb4">DIRECTION_CCW</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228ad604e0047f7cb47662c5a1cf6999337c">DIRECTION_CW</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">virtual</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5ac3523e4cf6763ba518d16fec3708ef23">DRIVER</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">enableOutputs</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a62a305b52f749ff8c89138273fbb012d">FULL2WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a0b8eea5cf0f8ce70b1959d2977ccc996">FULL3WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5adedd394a375190a3df8d4519c0d4dc2f">FULL4WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5af5bb99ad9d67ad2d85f840e3abcfe068">FUNCTION</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a00c2387a5af43d8e97639699ab7a5c7f">HALF3WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5aecc0900c55b777d2e885581b8c434b07">HALF4WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">isRunning</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">maxSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5">MotorInterfaceType</a> enum name</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(long relative)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">moveTo</a>(long absolute)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">run</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(long position)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(float acceleration)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(long position)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">setEnablePin</a>(uint8_t enablePin=0xff)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(float speed)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">setMinPulseWidth</a>(unsigned int minWidth)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">setOutputPins</a>(uint8_t mask)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ac62cae590c2f9c303519a3a1c4adc8ab">setPinsInverted</a>(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a38298ac2dd852fb22259f6c4bbe08c94">setPinsInverted</a>(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(float speed)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">speed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">step</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">step0</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">step1</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">step2</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">step3</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">step4</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">step6</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">step8</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
+  <tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">stop</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+  <tr><td class="entry"><a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">targetPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
+</table></div><!-- contents -->
+<!-- start footer part -->
+<hr class="footer"/><address class="footer"><small>
+Generated by &#160;<a href="http://www.doxygen.org/index.html">
+<img class="footer" src="doxygen.png" alt="doxygen"/>
+</a> 1.8.13
+</small></address>
+</body>
+</html>

File diff suppressed because it is too large
+ 1344 - 0
HTequi-firmware/lib/AccelStepper/doc/classAccelStepper.html


File diff suppressed because it is too large
+ 1596 - 0
HTequi-firmware/lib/AccelStepper/doc/doxygen.css


BIN
HTequi-firmware/lib/AccelStepper/doc/doxygen.png


+ 58 - 0
HTequi-firmware/lib/AccelStepper/doc/files.html

@@ -0,0 +1,58 @@
+<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
+<html xmlns="http://www.w3.org/1999/xhtml">
+<head>
+<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
+<meta http-equiv="X-UA-Compatible" content="IE=9"/>
+<meta name="generator" content="Doxygen 1.8.13"/>
+<meta name="viewport" content="width=device-width, initial-scale=1"/>
+<title>AccelStepper: File List</title>
+<link href="tabs.css" rel="stylesheet" type="text/css"/>
+<script type="text/javascript" src="jquery.js"></script>
+<script type="text/javascript" src="dynsections.js"></script>
+<link href="doxygen.css" rel="stylesheet" type="text/css" />
+</head>
+<body>
+<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
+<div id="titlearea">
+<table cellspacing="0" cellpadding="0">
+ <tbody>
+ <tr style="height: 56px;">
+  <td id="projectalign" style="padding-left: 0.5em;">
+   <div id="projectname">AccelStepper
+   </div>
+  </td>
+ </tr>
+ </tbody>
+</table>
+</div>
+<!-- end header part -->
+<!-- Generated by Doxygen 1.8.13 -->
+<script type="text/javascript" src="menudata.js"></script>
+<script type="text/javascript" src="menu.js"></script>
+<script type="text/javascript">
+$(function() {
+  initMenu('',false,false,'search.php','Search');
+});
+</script>
+<div id="main-nav"></div>
+</div><!-- top -->
+<div class="header">
+  <div class="headertitle">
+<div class="title">File List</div>  </div>
+</div><!--header-->
+<div class="contents">
+<div class="textblock">Here is a list of all documented files with brief descriptions:</div><div class="directory">
+<table class="directory">
+<tr id="row_0_" class="even"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><a href="AccelStepper_8h_source.html"><span class="icondoc"></span></a><b>AccelStepper.h</b></td><td class="desc"></td></tr>
+<tr id="row_1_"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><a href="MultiStepper_8h_source.html"><span class="icondoc"></span></a><b>MultiStepper.h</b></td><td class="desc"></td></tr>
+</table>
+</div><!-- directory -->
+</div><!-- contents -->
+<!-- start footer part -->
+<hr class="footer"/><address class="footer"><small>
+Generated by &#160;<a href="http://www.doxygen.org/index.html">
+<img class="footer" src="doxygen.png" alt="doxygen"/>
+</a> 1.8.13
+</small></address>
+</body>
+</html>

+ 243 - 0
HTequi-firmware/lib/AccelStepper/doc/functions.html

@@ -0,0 +1,243 @@
+<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
+<html xmlns="http://www.w3.org/1999/xhtml">
+<head>
+<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
+<meta http-equiv="X-UA-Compatible" content="IE=9"/>
+<meta name="generator" content="Doxygen 1.8.13"/>
+<meta name="viewport" content="width=device-width, initial-scale=1"/>
+<title>AccelStepper: Class Members</title>
+<link href="tabs.css" rel="stylesheet" type="text/css"/>
+<script type="text/javascript" src="jquery.js"></script>
+<script type="text/javascript" src="dynsections.js"></script>
+<link href="doxygen.css" rel="stylesheet" type="text/css" />
+</head>
+<body>
+<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
+<div id="titlearea">
+<table cellspacing="0" cellpadding="0">
+ <tbody>
+ <tr style="height: 56px;">
+  <td id="projectalign" style="padding-left: 0.5em;">
+   <div id="projectname">AccelStepper
+   </div>
+  </td>
+ </tr>
+ </tbody>
+</table>
+</div>
+<!-- end header part -->
+<!-- Generated by Doxygen 1.8.13 -->
+<script type="text/javascript" src="menudata.js"></script>
+<script type="text/javascript" src="menu.js"></script>
+<script type="text/javascript">
+$(function() {
+  initMenu('',false,false,'search.php','Search');
+});
+</script>
+<div id="main-nav"></div>
+</div><!-- top -->
+<div class="contents">
+<div class="textblock">Here is a list of all documented class members with links to the class documentation for each member:</div>
+
+<h3><a id="index__"></a>- _ -</h3><ul>
+<li>_direction
+: <a class="el" href="classAccelStepper.html#a35162cdf8ed9a98f98984c177d5ade58">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_a"></a>- a -</h3><ul>
+<li>AccelStepper()
+: <a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>
+</li>
+<li>addStepper()
+: <a class="el" href="classMultiStepper.html#a383d8486e17ad9de9f1bafcbd9aa52ee">MultiStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_c"></a>- c -</h3><ul>
+<li>computeNewSpeed()
+: <a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">AccelStepper</a>
+</li>
+<li>currentPosition()
+: <a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_d"></a>- d -</h3><ul>
+<li>Direction
+: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228">AccelStepper</a>
+</li>
+<li>DIRECTION_CCW
+: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228a6959a4549f734bd771d418f995ba4fb4">AccelStepper</a>
+</li>
+<li>DIRECTION_CW
+: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228ad604e0047f7cb47662c5a1cf6999337c">AccelStepper</a>
+</li>
+<li>disableOutputs()
+: <a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
+</li>
+<li>distanceToGo()
+: <a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
+</li>
+<li>DRIVER
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5ac3523e4cf6763ba518d16fec3708ef23">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_e"></a>- e -</h3><ul>
+<li>enableOutputs()
+: <a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_f"></a>- f -</h3><ul>
+<li>FULL2WIRE
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a62a305b52f749ff8c89138273fbb012d">AccelStepper</a>
+</li>
+<li>FULL3WIRE
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a0b8eea5cf0f8ce70b1959d2977ccc996">AccelStepper</a>
+</li>
+<li>FULL4WIRE
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5adedd394a375190a3df8d4519c0d4dc2f">AccelStepper</a>
+</li>
+<li>FUNCTION
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5af5bb99ad9d67ad2d85f840e3abcfe068">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_h"></a>- h -</h3><ul>
+<li>HALF3WIRE
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a00c2387a5af43d8e97639699ab7a5c7f">AccelStepper</a>
+</li>
+<li>HALF4WIRE
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5aecc0900c55b777d2e885581b8c434b07">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_i"></a>- i -</h3><ul>
+<li>isRunning()
+: <a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_m"></a>- m -</h3><ul>
+<li>maxSpeed()
+: <a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">AccelStepper</a>
+</li>
+<li>MotorInterfaceType
+: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5">AccelStepper</a>
+</li>
+<li>move()
+: <a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
+</li>
+<li>moveTo()
+: <a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a291fec32a79390b6eb00296cffac49ee">MultiStepper</a>
+</li>
+<li>MultiStepper()
+: <a class="el" href="classMultiStepper.html#a14c0c1c0f55e5bbdc4971730e32304c2">MultiStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_r"></a>- r -</h3><ul>
+<li>run()
+: <a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a26c2f53b1e7ddf5d5dfb333f6fb7fb92">MultiStepper</a>
+</li>
+<li>runSpeed()
+: <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
+</li>
+<li>runSpeedToPosition()
+: <a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a2592f55864ce3ace125944db624317bc">MultiStepper</a>
+</li>
+<li>runToNewPosition()
+: <a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
+</li>
+<li>runToPosition()
+: <a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_s"></a>- s -</h3><ul>
+<li>setAcceleration()
+: <a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
+</li>
+<li>setCurrentPosition()
+: <a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
+</li>
+<li>setEnablePin()
+: <a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">AccelStepper</a>
+</li>
+<li>setMaxSpeed()
+: <a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">AccelStepper</a>
+</li>
+<li>setMinPulseWidth()
+: <a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">AccelStepper</a>
+</li>
+<li>setOutputPins()
+: <a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">AccelStepper</a>
+</li>
+<li>setPinsInverted()
+: <a class="el" href="classAccelStepper.html#ac62cae590c2f9c303519a3a1c4adc8ab">AccelStepper</a>
+</li>
+<li>setSpeed()
+: <a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
+</li>
+<li>speed()
+: <a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
+</li>
+<li>step()
+: <a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">AccelStepper</a>
+</li>
+<li>step0()
+: <a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">AccelStepper</a>
+</li>
+<li>step1()
+: <a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">AccelStepper</a>
+</li>
+<li>step2()
+: <a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">AccelStepper</a>
+</li>
+<li>step3()
+: <a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">AccelStepper</a>
+</li>
+<li>step4()
+: <a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">AccelStepper</a>
+</li>
+<li>step6()
+: <a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">AccelStepper</a>
+</li>
+<li>step8()
+: <a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">AccelStepper</a>
+</li>
+<li>stop()
+: <a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_t"></a>- t -</h3><ul>
+<li>targetPosition()
+: <a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
+</li>
+</ul>
+</div><!-- contents -->
+<!-- start footer part -->
+<hr class="footer"/><address class="footer"><small>
+Generated by &#160;<a href="http://www.doxygen.org/index.html">
+<img class="footer" src="doxygen.png" alt="doxygen"/>
+</a> 1.8.13
+</small></address>
+</body>
+</html>

+ 195 - 0
HTequi-firmware/lib/AccelStepper/doc/functions_func.html

@@ -0,0 +1,195 @@
+<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
+<html xmlns="http://www.w3.org/1999/xhtml">
+<head>
+<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
+<meta http-equiv="X-UA-Compatible" content="IE=9"/>
+<meta name="generator" content="Doxygen 1.8.13"/>
+<meta name="viewport" content="width=device-width, initial-scale=1"/>
+<title>AccelStepper: Class Members - Functions</title>
+<link href="tabs.css" rel="stylesheet" type="text/css"/>
+<script type="text/javascript" src="jquery.js"></script>
+<script type="text/javascript" src="dynsections.js"></script>
+<link href="doxygen.css" rel="stylesheet" type="text/css" />
+</head>
+<body>
+<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
+<div id="titlearea">
+<table cellspacing="0" cellpadding="0">
+ <tbody>
+ <tr style="height: 56px;">
+  <td id="projectalign" style="padding-left: 0.5em;">
+   <div id="projectname">AccelStepper
+   </div>
+  </td>
+ </tr>
+ </tbody>
+</table>
+</div>
+<!-- end header part -->
+<!-- Generated by Doxygen 1.8.13 -->
+<script type="text/javascript" src="menudata.js"></script>
+<script type="text/javascript" src="menu.js"></script>
+<script type="text/javascript">
+$(function() {
+  initMenu('',false,false,'search.php','Search');
+});
+</script>
+<div id="main-nav"></div>
+</div><!-- top -->
+<div class="contents">
+&#160;
+
+<h3><a id="index_a"></a>- a -</h3><ul>
+<li>AccelStepper()
+: <a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>
+</li>
+<li>addStepper()
+: <a class="el" href="classMultiStepper.html#a383d8486e17ad9de9f1bafcbd9aa52ee">MultiStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_c"></a>- c -</h3><ul>
+<li>computeNewSpeed()
+: <a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">AccelStepper</a>
+</li>
+<li>currentPosition()
+: <a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_d"></a>- d -</h3><ul>
+<li>disableOutputs()
+: <a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
+</li>
+<li>distanceToGo()
+: <a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_e"></a>- e -</h3><ul>
+<li>enableOutputs()
+: <a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_i"></a>- i -</h3><ul>
+<li>isRunning()
+: <a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_m"></a>- m -</h3><ul>
+<li>maxSpeed()
+: <a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">AccelStepper</a>
+</li>
+<li>move()
+: <a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
+</li>
+<li>moveTo()
+: <a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a291fec32a79390b6eb00296cffac49ee">MultiStepper</a>
+</li>
+<li>MultiStepper()
+: <a class="el" href="classMultiStepper.html#a14c0c1c0f55e5bbdc4971730e32304c2">MultiStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_r"></a>- r -</h3><ul>
+<li>run()
+: <a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a26c2f53b1e7ddf5d5dfb333f6fb7fb92">MultiStepper</a>
+</li>
+<li>runSpeed()
+: <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
+</li>
+<li>runSpeedToPosition()
+: <a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
+, <a class="el" href="classMultiStepper.html#a2592f55864ce3ace125944db624317bc">MultiStepper</a>
+</li>
+<li>runToNewPosition()
+: <a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
+</li>
+<li>runToPosition()
+: <a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_s"></a>- s -</h3><ul>
+<li>setAcceleration()
+: <a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
+</li>
+<li>setCurrentPosition()
+: <a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
+</li>
+<li>setEnablePin()
+: <a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">AccelStepper</a>
+</li>
+<li>setMaxSpeed()
+: <a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">AccelStepper</a>
+</li>
+<li>setMinPulseWidth()
+: <a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">AccelStepper</a>
+</li>
+<li>setOutputPins()
+: <a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">AccelStepper</a>
+</li>
+<li>setPinsInverted()
+: <a class="el" href="classAccelStepper.html#a38298ac2dd852fb22259f6c4bbe08c94">AccelStepper</a>
+</li>
+<li>setSpeed()
+: <a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
+</li>
+<li>speed()
+: <a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
+</li>
+<li>step()
+: <a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">AccelStepper</a>
+</li>
+<li>step0()
+: <a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">AccelStepper</a>
+</li>
+<li>step1()
+: <a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">AccelStepper</a>
+</li>
+<li>step2()
+: <a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">AccelStepper</a>
+</li>
+<li>step3()
+: <a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">AccelStepper</a>
+</li>
+<li>step4()
+: <a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">AccelStepper</a>
+</li>
+<li>step6()
+: <a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">AccelStepper</a>
+</li>
+<li>step8()
+: <a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">AccelStepper</a>
+</li>
+<li>stop()
+: <a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">AccelStepper</a>
+</li>
+</ul>
+
+
+<h3><a id="index_t"></a>- t -</h3><ul>
+<li>targetPosition()
+: <a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
+</li>
+</ul>
+</div><!-- contents -->
+<!-- start footer part -->
+<hr class="footer"/><address class="footer"><small>
+Generated by &#160;<a href="http://www.doxygen.org/index.html">
+<img class="footer" src="doxygen.png" alt="doxygen"/>
+</a> 1.8.13
+</small></address>
+</body>
+</html>

File diff suppressed because it is too large
+ 222 - 0
HTequi-firmware/lib/AccelStepper/doc/index.html


BIN
HTequi-firmware/lib/AccelStepper/doc/tab_b.gif


BIN
HTequi-firmware/lib/AccelStepper/doc/tab_l.gif


BIN
HTequi-firmware/lib/AccelStepper/doc/tab_r.gif


File diff suppressed because it is too large
+ 1 - 0
HTequi-firmware/lib/AccelStepper/doc/tabs.css


+ 40 - 0
HTequi-firmware/lib/AccelStepper/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde

@@ -0,0 +1,40 @@
+// AFMotor_ConstantSpeed.pde
+// -*- mode: C++ -*-
+//
+// Shows how to run AccelStepper in the simplest,
+// fixed speed mode with no accelerations
+// Requires the AFMotor library
+// (https://github.com/adafruit/Adafruit-Motor-Shield-library)
+// Caution, does 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.
+
+#include <AccelStepper.h>
+#include <AFMotor.h>
+
+AF_Stepper motor1(200, 1);
+
+
+// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
+void forwardstep() {  
+  motor1.onestep(FORWARD, SINGLE);
+}
+void backwardstep() {  
+  motor1.onestep(BACKWARD, SINGLE);
+}
+
+AccelStepper stepper(forwardstep, backwardstep); // use functions to step
+
+void setup()
+{  
+   Serial.begin(9600);           // set up Serial library at 9600 bps
+   Serial.println("Stepper test!");
+  
+   stepper.setMaxSpeed(50);	
+   stepper.setSpeed(50);	
+}
+
+void loop()
+{  
+   stepper.runSpeed();
+}

+ 57 - 0
HTequi-firmware/lib/AccelStepper/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde

@@ -0,0 +1,57 @@
+// AFMotor_MultiStepper.pde
+// -*- mode: C++ -*-
+//
+// Control both Stepper motors at the same time with different speeds
+// and accelerations. 
+// Requires the AFMotor library (https://github.com/adafruit/Adafruit-Motor-Shield-library)
+// Caution, does 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.
+
+#include <AccelStepper.h>
+#include <AFMotor.h>
+
+// two stepper motors one on each port
+AF_Stepper motor1(200, 1);
+AF_Stepper motor2(200, 2);
+
+// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
+// wrappers for the first motor!
+void forwardstep1() {  
+  motor1.onestep(FORWARD, SINGLE);
+}
+void backwardstep1() {  
+  motor1.onestep(BACKWARD, SINGLE);
+}
+// wrappers for the second motor!
+void forwardstep2() {  
+  motor2.onestep(FORWARD, SINGLE);
+}
+void backwardstep2() {  
+  motor2.onestep(BACKWARD, SINGLE);
+}
+
+// Motor shield has two motor ports, now we'll wrap them in an AccelStepper object
+AccelStepper stepper1(forwardstep1, backwardstep1);
+AccelStepper stepper2(forwardstep2, backwardstep2);
+
+void setup()
+{  
+    stepper1.setMaxSpeed(200.0);
+    stepper1.setAcceleration(100.0);
+    stepper1.moveTo(24);
+    
+    stepper2.setMaxSpeed(300.0);
+    stepper2.setAcceleration(100.0);
+    stepper2.moveTo(1000000);
+    
+}
+
+void loop()
+{
+    // Change direction at the limits
+    if (stepper1.distanceToGo() == 0)
+	stepper1.moveTo(-stepper1.currentPosition());
+    stepper1.run();
+    stepper2.run();
+}

+ 28 - 0
HTequi-firmware/lib/AccelStepper/examples/Blocking/Blocking.pde

@@ -0,0 +1,28 @@
+// Blocking.pde
+// -*- mode: C++ -*-
+//
+// Shows how to use the blocking call runToNewPosition
+// Which sets a new target position and then waits until the stepper has 
+// achieved it.
+//
+// Copyright (C) 2009 Mike McCauley
+// $Id: Blocking.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+    stepper.setMaxSpeed(200.0);
+    stepper.setAcceleration(100.0);
+}
+
+void loop()
+{    
+    stepper.runToNewPosition(0);
+    stepper.runToNewPosition(500);
+    stepper.runToNewPosition(100);
+    stepper.runToNewPosition(120);
+}

+ 29 - 0
HTequi-firmware/lib/AccelStepper/examples/Bounce/Bounce.pde

@@ -0,0 +1,29 @@
+// Bounce.pde
+// -*- mode: C++ -*-
+//
+// Make a single stepper bounce from one limit to another
+//
+// Copyright (C) 2012 Mike McCauley
+// $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+  // Change these to suit your stepper if you want
+  stepper.setMaxSpeed(100);
+  stepper.setAcceleration(20);
+  stepper.moveTo(500);
+}
+
+void loop()
+{
+    // If at the end of travel go to the other end
+    if (stepper.distanceToGo() == 0)
+      stepper.moveTo(-stepper.currentPosition());
+
+    stepper.run();
+}

+ 23 - 0
HTequi-firmware/lib/AccelStepper/examples/ConstantSpeed/ConstantSpeed.pde

@@ -0,0 +1,23 @@
+// ConstantSpeed.pde
+// -*- mode: C++ -*-
+//
+// Shows how to run AccelStepper in the simplest,
+// fixed speed mode with no accelerations
+/// \author  Mike McCauley (mikem@airspayce.com)
+// Copyright (C) 2009 Mike McCauley
+// $Id: ConstantSpeed.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+   stepper.setMaxSpeed(1000);
+   stepper.setSpeed(50);	
+}
+
+void loop()
+{  
+   stepper.runSpeed();
+}

+ 49 - 0
HTequi-firmware/lib/AccelStepper/examples/DualMotorShield/DualMotorShield.pde

@@ -0,0 +1,49 @@
+// DualMotorShield.pde
+// -*- mode: C++ -*-
+//
+// Shows how to run 2 simultaneous steppers
+// using the Itead Studio Arduino Dual Stepper Motor Driver Shield
+// model IM120417015
+// This shield is capable of driving 2 steppers at 
+// currents of up to 750mA
+// and voltages up to 30V
+// Runs both steppers forwards and backwards, accelerating and decelerating
+// at the limits.
+//
+// Copyright (C) 2014 Mike McCauley
+// $Id:  $
+
+#include <AccelStepper.h>
+
+// The X Stepper pins
+#define STEPPER1_DIR_PIN 3
+#define STEPPER1_STEP_PIN 2
+// The Y stepper pins
+#define STEPPER2_DIR_PIN 7
+#define STEPPER2_STEP_PIN 6
+
+// Define some steppers and the pins the will use
+AccelStepper stepper1(AccelStepper::DRIVER, STEPPER1_STEP_PIN, STEPPER1_DIR_PIN);
+AccelStepper stepper2(AccelStepper::DRIVER, STEPPER2_STEP_PIN, STEPPER2_DIR_PIN);
+
+void setup()
+{  
+    stepper1.setMaxSpeed(200.0);
+    stepper1.setAcceleration(200.0);
+    stepper1.moveTo(100);
+    
+    stepper2.setMaxSpeed(100.0);
+    stepper2.setAcceleration(100.0);
+    stepper2.moveTo(100);
+}
+
+void loop()
+{
+    // Change direction at the limits
+    if (stepper1.distanceToGo() == 0)
+	stepper1.moveTo(-stepper1.currentPosition());
+    if (stepper2.distanceToGo() == 0)
+	stepper2.moveTo(-stepper2.currentPosition());
+    stepper1.run();
+    stepper2.run();
+}

+ 103 - 0
HTequi-firmware/lib/AccelStepper/examples/MotorShield/MotorShield.pde

@@ -0,0 +1,103 @@
+// AFMotor_ConstantSpeed.pde
+// -*- mode: C++ -*-
+//
+// Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor
+// using the Adafruit Motor Shield
+// http://www.ladyada.net/make/mshield/index.html.
+// Create a subclass of AccelStepper which controls the motor  pins via the
+// Motor Shield serial-to-parallel interface
+
+#include <AccelStepper.h>
+
+// Arduino pin names for interface to 74HCT595 latch
+// on Adafruit Motor Shield
+#define MOTORLATCH   12
+#define MOTORCLK     4
+#define MOTORENABLE  7
+#define MOTORDATA    8
+
+// PWM pins, also used to enable motor outputs
+#define PWM0A        5
+#define PWM0B        6
+#define PWM1A        9
+#define PWM1B        10
+#define PWM2A        11
+#define PWM2B        3
+
+
+// The main purpose of this class is to override setOutputPins to work with Adafruit Motor Shield
+class AFMotorShield : public AccelStepper
+{
+  public:
+  AFMotorShield(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5); 
+
+  virtual void   setOutputPins(uint8_t mask);
+};
+
+
+AFMotorShield::AFMotorShield(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4)
+    : AccelStepper(interface, pin1, pin2, pin3, pin4) 
+{
+    // Enable motor control serial to parallel latch
+    pinMode(MOTORLATCH, OUTPUT);
+    pinMode(MOTORENABLE, OUTPUT);
+    pinMode(MOTORDATA, OUTPUT);
+    pinMode(MOTORCLK, OUTPUT);
+    digitalWrite(MOTORENABLE, LOW);
+    
+    // enable both H bridges on motor 1
+    pinMode(PWM2A, OUTPUT);
+    pinMode(PWM2B, OUTPUT);
+    pinMode(PWM0A, OUTPUT);
+    pinMode(PWM0B, OUTPUT);
+    digitalWrite(PWM2A, HIGH);
+    digitalWrite(PWM2B, HIGH);
+    digitalWrite(PWM0A, HIGH);
+    digitalWrite(PWM0B, HIGH);
+
+    setOutputPins(0); // Reset
+};
+    
+// Use the AF Motor Shield serial-to-parallel to set the state of the motor pins
+// Caution: the mapping of AccelStepper pins to AF motor outputs is not
+// obvious:
+// AccelStepper     Motor Shield output
+// pin1                M4A
+// pin2                M1A
+// pin3                M2A
+// pin4                M3A
+// Caution this is pretty slow and limits the max speed of the motor to about 500/3 rpm
+void AFMotorShield::setOutputPins(uint8_t mask)
+{
+  uint8_t i;
+  
+  digitalWrite(MOTORLATCH, LOW);
+  digitalWrite(MOTORDATA, LOW);
+
+  for (i=0; i<8; i++) 
+  {
+    digitalWrite(MOTORCLK, LOW);
+
+    if (mask & _BV(7-i))
+      digitalWrite(MOTORDATA, HIGH);
+    else
+      digitalWrite(MOTORDATA, LOW);
+ 
+    digitalWrite(MOTORCLK, HIGH);
+  }
+  digitalWrite(MOTORLATCH, HIGH);
+}
+
+AFMotorShield stepper(AccelStepper::HALF3WIRE, 0, 0, 0, 0); // 3 phase HDD spindle drive
+
+void setup()
+{  
+   stepper.setMaxSpeed(500);	// divide by 3 to get rpm
+   stepper.setAcceleration(80);
+   stepper.moveTo(10000000);	
+}
+
+void loop()
+{  
+   stepper.run();
+}

+ 44 - 0
HTequi-firmware/lib/AccelStepper/examples/MultiStepper/MultiStepper.pde

@@ -0,0 +1,44 @@
+// MultiStepper.pde
+// -*- mode: C++ -*-
+// Use MultiStepper class to manage multiple steppers and make them all move to 
+// the same position at the same time for linear 2d (or 3d) motion.
+
+#include <AccelStepper.h>
+#include <MultiStepper.h>
+
+// EG X-Y position bed driven by 2 steppers
+// Alas its not possible to build an array of these with different pins for each :-(
+AccelStepper stepper1(AccelStepper::FULL4WIRE, 2, 3, 4, 5);
+AccelStepper stepper2(AccelStepper::FULL4WIRE, 8, 9, 10, 11);
+
+// Up to 10 steppers can be handled as a group by MultiStepper
+MultiStepper steppers;
+
+void setup() {
+  Serial.begin(9600);
+
+  // Configure each stepper
+  stepper1.setMaxSpeed(100);
+  stepper2.setMaxSpeed(100);
+
+  // Then give them to MultiStepper to manage
+  steppers.addStepper(stepper1);
+  steppers.addStepper(stepper2);
+}
+
+void loop() {
+  long positions[2]; // Array of desired stepper positions
+  
+  positions[0] = 1000;
+  positions[1] = 50;
+  steppers.moveTo(positions);
+  steppers.runSpeedToPosition(); // Blocks until all are in position
+  delay(1000);
+  
+  // Move to a different coordinate
+  positions[0] = -100;
+  positions[1] = 100;
+  steppers.moveTo(positions);
+  steppers.runSpeedToPosition(); // Blocks until all are in position
+  delay(1000);
+}

+ 41 - 0
HTequi-firmware/lib/AccelStepper/examples/MultipleSteppers/MultipleSteppers.pde

@@ -0,0 +1,41 @@
+// MultiStepper.pde
+// -*- mode: C++ -*-
+//
+// Shows how to multiple simultaneous steppers
+// Runs one stepper forwards and backwards, accelerating and decelerating
+// at the limits. Runs other steppers at the same time
+//
+// Copyright (C) 2009 Mike McCauley
+// $Id: MultiStepper.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define some steppers and the pins the will use
+AccelStepper stepper1; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+AccelStepper stepper2(AccelStepper::FULL4WIRE, 6, 7, 8, 9);
+AccelStepper stepper3(AccelStepper::FULL2WIRE, 10, 11);
+
+void setup()
+{  
+    stepper1.setMaxSpeed(200.0);
+    stepper1.setAcceleration(100.0);
+    stepper1.moveTo(24);
+    
+    stepper2.setMaxSpeed(300.0);
+    stepper2.setAcceleration(100.0);
+    stepper2.moveTo(1000000);
+    
+    stepper3.setMaxSpeed(300.0);
+    stepper3.setAcceleration(100.0);
+    stepper3.moveTo(1000000); 
+}
+
+void loop()
+{
+    // Change direction at the limits
+    if (stepper1.distanceToGo() == 0)
+	stepper1.moveTo(-stepper1.currentPosition());
+    stepper1.run();
+    stepper2.run();
+    stepper3.run();
+}

+ 28 - 0
HTequi-firmware/lib/AccelStepper/examples/Overshoot/Overshoot.pde

@@ -0,0 +1,28 @@
+// Overshoot.pde
+// -*- mode: C++ -*-
+//
+// Check overshoot handling
+// which sets a new target position and then waits until the stepper has 
+// achieved it. This is used for testing the handling of overshoots
+//
+// Copyright (C) 2009 Mike McCauley
+// $Id: Overshoot.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+  stepper.setMaxSpeed(150);
+  stepper.setAcceleration(100);
+}
+
+void loop()
+{    
+  stepper.moveTo(500);
+  while (stepper.currentPosition() != 300) // Full speed up to 300
+    stepper.run();
+  stepper.runToNewPosition(0); // Cause an overshoot then back to 0
+}

+ 32 - 0
HTequi-firmware/lib/AccelStepper/examples/ProportionalControl/ProportionalControl.pde

@@ -0,0 +1,32 @@
+// ProportionalControl.pde
+// -*- mode: C++ -*-
+//
+// Make a single stepper follow the analog value read from a pot or whatever
+// The stepper will move at a constant speed to each newly set posiiton, 
+// depending on the value of the pot.
+//
+// Copyright (C) 2012 Mike McCauley
+// $Id: ProportionalControl.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+// This defines the analog input pin for reading the control voltage
+// Tested with a 10k linear pot between 5v and GND
+#define ANALOG_IN A0
+
+void setup()
+{  
+  stepper.setMaxSpeed(1000);
+}
+
+void loop()
+{
+  // Read new position
+  int analog_in = analogRead(ANALOG_IN);
+  stepper.moveTo(analog_in);
+  stepper.setSpeed(100);
+  stepper.runSpeedToPosition();
+}

+ 40 - 0
HTequi-firmware/lib/AccelStepper/examples/Quickstop/Quickstop.pde

@@ -0,0 +1,40 @@
+// Quickstop.pde
+// -*- mode: C++ -*-
+//
+// Check stop handling.
+// Calls stop() while the stepper is travelling at full speed, causing
+// the stepper to stop as quickly as possible, within the constraints of the
+// current acceleration.
+//
+// Copyright (C) 2012 Mike McCauley
+// $Id:  $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+  stepper.setMaxSpeed(150);
+  stepper.setAcceleration(100);
+}
+
+void loop()
+{    
+  stepper.moveTo(500);
+  while (stepper.currentPosition() != 300) // Full speed up to 300
+    stepper.run();
+  stepper.stop(); // Stop as fast as possible: sets new target
+  stepper.runToPosition(); 
+  // Now stopped after quickstop
+
+  // Now go backwards
+  stepper.moveTo(-500);
+  while (stepper.currentPosition() != 0) // Full speed basck to 0
+    stepper.run();
+  stepper.stop(); // Stop as fast as possible: sets new target
+  stepper.runToPosition(); 
+  // Now stopped after quickstop
+
+}

+ 30 - 0
HTequi-firmware/lib/AccelStepper/examples/Random/Random.pde

@@ -0,0 +1,30 @@
+// Random.pde
+// -*- mode: C++ -*-
+//
+// Make a single stepper perform random changes in speed, position and acceleration
+//
+// Copyright (C) 2009 Mike McCauley
+// $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
+
+#include <AccelStepper.h>
+
+// Define a stepper and the pins it will use
+AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
+
+void setup()
+{  
+}
+
+void loop()
+{
+    if (stepper.distanceToGo() == 0)
+    {
+	// Random change to speed, position and acceleration
+	// Make sure we dont get 0 speed or accelerations
+	delay(1000);
+	stepper.moveTo(rand() % 200);
+	stepper.setMaxSpeed((rand() % 200) + 1);
+	stepper.setAcceleration((rand() % 200) + 1);
+    }
+    stepper.run();
+}

+ 41 - 0
HTequi-firmware/lib/AccelStepper/keywords.txt

@@ -0,0 +1,41 @@
+#######################################
+# Syntax Coloring Map For AccelStepper
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+AccelStepper	KEYWORD1
+MultiStepper	KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+moveTo	KEYWORD2
+move	KEYWORD2
+run	KEYWORD2
+runSpeed	KEYWORD2
+setMaxSpeed	KEYWORD2
+setAcceleration	KEYWORD2
+setSpeed	KEYWORD2
+speed	KEYWORD2
+distanceToGo	KEYWORD2
+targetPosition	KEYWORD2
+currentPosition	KEYWORD2
+setCurrentPosition	KEYWORD2
+runToPosition	KEYWORD2
+runSpeedToPosition	KEYWORD2
+runToNewPosition	KEYWORD2
+stop	KEYWORD2
+disableOutputs	KEYWORD2
+enableOutputs	KEYWORD2
+setMinPulseWidth	KEYWORD2
+setEnablePin	KEYWORD2
+setPinsInverted	KEYWORD2
+maxSpeed	KEYWORD2
+#######################################
+# Constants (LITERAL1)
+#######################################
+ 

File diff suppressed because it is too large
+ 2280 - 0
HTequi-firmware/lib/AccelStepper/project.cfg


+ 124 - 0
HTequi-firmware/src/Atm_lien/Atm_stepper.cpp

@@ -0,0 +1,124 @@
+#include "Atm_stepper.h"
+
+/* Add optional parameters for the state machine to begin()
+ * Add extra initialization code
+ */
+
+Atm_stepper& Atm_stepper::begin(int stepPin, int dirPin) {
+  // clang-format off
+  const static state_t state_table[] PROGMEM = {
+    /*                 ON_ENTER     ON_LOOP       ON_EXIT  EVT_IDLE_TIMER  EVT_ON_TARGET  EVT_GOTO  ELSE */
+    /*     IDLE */     ENT_IDLE,         -1,           -1,             -1,            -1,  RUNNING,   -1,
+    /*    READY */    ENT_READY,         -1,           -1,           IDLE,            -1,  RUNNING,   -1,
+    /*  RUNNING */  ENT_RUNNING, LP_RUNNING,           -1,             -1,      STOPPING,  RUNNING,   -1,
+    /* STOPPING */ ENT_STOPPING,         -1, EXT_STOPPING,             -1,         READY,       -1,   -1,
+  };
+  // clang-format on
+  Machine::begin( state_table, ELSE );
+  _motor = new AccelStepper(1, stepPin, dirPin);
+  _motor->setMaxSpeed(2000);
+  _motor->setAcceleration(2000);
+  //_controller = new StepControl;
+  pinMode(0, OUTPUT);
+  digitalWrite(0, HIGH);
+  return *this;
+}
+
+/* Add C++ code for each internally handled event (input)
+ * The code must return 1 to trigger the event
+ */
+
+int Atm_stepper::event( int id ) {
+  switch ( id ) {
+    case EVT_IDLE_TIMER:
+      return 0;
+    case EVT_ON_TARGET:
+      return 0;
+  }
+  return 0;
+}
+
+/* Add C++ code for each action
+ * This generates the 'output' for the state machine
+ *
+ * Available connectors:
+ *   push( connectors, ON_ONCHANGE, 0, <v>, <up> );
+ */
+
+void Atm_stepper::action( int id ) {
+  switch ( id ) {
+    case ENT_IDLE:
+      digitalWrite(0, LOW);
+      return;
+    case ENT_READY:
+    digitalWrite(0, HIGH);
+      return;
+    case ENT_RUNNING:
+      digitalWrite(0, HIGH);
+      return;
+    case LP_RUNNING:
+      _motor->run();
+      // _controller.moveAsync(_motor);
+      Serial.println(_motor->distanceToGo());
+      return;
+    case ENT_STOPPING:
+      return;
+    case EXT_STOPPING:
+      return;
+  }
+}
+
+/* Optionally override the default trigger() method
+ * Control how your machine processes triggers
+ */
+
+Atm_stepper& Atm_stepper::trigger( int event ) {
+  Machine::trigger( event );
+  return *this;
+}
+
+/* Optionally override the default state() method
+ * Control what the machine returns when another process requests its state
+ */
+
+int Atm_stepper::state( void ) {
+  return Machine::state();
+}
+
+/* Nothing customizable below this line
+ ************************************************************************************************
+*/
+
+/* Public event methods
+ *
+ */
+
+Atm_stepper& Atm_stepper::gotoStep(long int targetStep ) {
+  _motor->moveTo(targetStep);
+  trigger( EVT_GOTO );
+  return *this;
+}
+
+/*
+ * onOnchange() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_stepper& Atm_stepper::onOnchange( Machine& machine, int event ) {
+  onPush( connectors, ON_ONCHANGE, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_stepper& Atm_stepper::onOnchange( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_ONCHANGE, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/* State trace method
+ * Sets the symbol table and the default logging method for serial monitoring
+ */
+
+Atm_stepper& Atm_stepper::trace( Stream & stream ) {
+  Machine::setTrace( &stream, atm_serial_debug::trace,
+    "STEPPER\0EVT_IDLE_TIMER\0EVT_ON_TARGET\0EVT_GOTO\0ELSE\0IDLE\0READY\0RUNNING\0STOPPING" );
+  return *this;
+}

+ 68 - 0
HTequi-firmware/src/Atm_lien/Atm_stepper.h

@@ -0,0 +1,68 @@
+#pragma once
+
+#include <Automaton.h>
+// #include <TeensyStep.h>
+#include <AccelStepper.h>
+class Atm_stepper: public Machine {
+
+ public:
+  enum { IDLE, READY, RUNNING, STOPPING }; // STATES
+  enum { EVT_IDLE_TIMER, EVT_ON_TARGET, EVT_GOTO, ELSE }; // EVENTS
+  Atm_stepper( void ) : Machine()  {};
+  Atm_stepper& begin( int setpPin, int dirPin ) ;
+  Atm_stepper& trace( Stream & stream );
+  Atm_stepper& trigger( int event );
+  int state( void );
+  Atm_stepper& onOnchange( Machine& machine, int event = 0 );
+  Atm_stepper& onOnchange( atm_cb_push_t callback, int idx = 0 );
+  Atm_stepper& gotoStep( long int targetStep );
+
+ private:
+  AccelStepper *_motor;
+  // Stepper _motor;       // STEP pin: 2, DIR pin: 3
+  // StepControl _controller;
+  enum { ENT_IDLE, ENT_READY, ENT_RUNNING, LP_RUNNING, ENT_STOPPING, EXT_STOPPING }; // ACTIONS
+  enum { ON_ONCHANGE, CONN_MAX }; // CONNECTORS
+  atm_connector connectors[CONN_MAX];
+  int event( int id );
+  void action( int id );
+
+};
+
+/*
+Automaton::ATML::begin - Automaton Markup Language
+
+<?xml version="1.0" encoding="UTF-8"?>
+<machines>
+  <machine name="Atm_stepper">
+    <states>
+      <IDLE index="0" on_enter="ENT_IDLE">
+        <EVT_GOTO>RUNNING</EVT_GOTO>
+      </IDLE>
+      <READY index="1" on_enter="ENT_READY">
+        <EVT_IDLE_TIMER>IDLE</EVT_IDLE_TIMER>
+        <EVT_GOTO>RUNNING</EVT_GOTO>
+      </READY>
+      <RUNNING index="2" on_enter="ENT_RUNNING" on_loop="LP_RUNNING">
+        <EVT_ON_TARGET>STOPPING</EVT_ON_TARGET>
+        <EVT_GOTO>RUNNING</EVT_GOTO>
+      </RUNNING>
+      <STOPPING index="3" on_enter="ENT_STOPPING" on_exit="EXT_STOPPING">
+        <EVT_ON_TARGET>READY</EVT_ON_TARGET>
+      </STOPPING>
+    </states>
+    <events>
+      <EVT_IDLE_TIMER index="0" access="PRIVATE"/>
+      <EVT_ON_TARGET index="1" access="PRIVATE"/>
+      <EVT_GOTO index="2" access="PUBLIC"/>
+    </events>
+    <connectors>
+      <ONCHANGE autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+    </connectors>
+    <methods>
+    </methods>
+  </machine>
+</machines>
+
+Automaton::ATML::end
+*/

+ 155 - 145
HTequi-firmware/src/blobcnc_low/main.cpp

@@ -1,173 +1,183 @@
- #include <Arduino.h>
-
- #include <Automaton.h>
-
- #include <SPI.h>
- #include <Ethernet.h>
- #include <EthernetUdp.h>
- #include <TeensyMAC.h>
- #include <OSCMessage.h>
- // Enter a MAC address and IP address for your controller below.
- // The IP address will be dependent on your local network:
- byte mac[] = {
-   0x00, 0xAA, 0xBB, 0xCC, 0xDE, 0x02
- };
-
- IPAddress ip(192, 168, 1, 204);    //local IP of Arduino/Teensy
- //unsigned int localPort = 8888;      // local port to listen on (not needed for multicast)
-
- IPAddress ipMulti(239, 200, 200, 200); // ipMidi Multicast address
- unsigned int portMulti = 9977;   // ipMidi Mutlicast port 1
-
-
- // buffers for receiving and sending data
- byte packetBuffer[UDP_TX_PACKET_MAX_SIZE];       // buffer to hold incoming packet
- byte sendBuffer1[] = {0x90, 0x14, 0x22};        // MIDI Note On to Multicast address
- byte sendBuffer2[] = {0x80, 0x14, 0x00};        // MIDI Note Off to Multicast address
-
- // An EthernetUDP instance to let us send and receive packets over UDP
- EthernetUDP Udp;
-
-
- class Atm_blink : public Machine {
-
-   public:
-     Atm_blink( void ) : Machine() {};
-
-     short pin;
-     atm_timer_millis timer;
-
-     EthernetUDP* _udpRef ;
-     //Atm_blink& onOSC(OSCMessage& msg );
-
-     enum { IDLE, LED_ON, LED_OFF }; // STATES
-     enum { EVT_TIMER, EVT_ON, EVT_OFF, ELSE }; // EVENTS
-     enum { ENT_ON, ENT_OFF }; // ACTIONS
-
-     Atm_blink & begin( int attached_pin, uint32_t blinkrate, EthernetUDP& udpRef  ) {
-       const static state_t state_table[] PROGMEM = {
-         /*            ON_ENTER    ON_LOOP  ON_EXIT  EVT_TIMER  EVT_ON  EVT_OFF  ELSE */
-         /* IDLE    */  ENT_OFF,        -1,      -1,        -1, LED_ON,      -1,   -1,
-         /* LED_ON  */   ENT_ON,        -1,      -1,   LED_OFF,     -1,    IDLE,   -1,
-         /* LED_OFF */  ENT_OFF,        -1,      -1,    LED_ON,     -1,    IDLE,   -1,
-       };
-       Machine::begin( state_table, ELSE );
-       pin = attached_pin;
-       timer.set( blinkrate );
-       pinMode( pin, OUTPUT );
-       this->_udpRef =   &udpRef;
-       return *this;
-     }
+#include <Arduino.h>
+
+#include <Automaton.h>
+#include "Atm_lien/Atm_stepper.h"
+
+#include <SPI.h>
+#include <Ethernet.h>
+#include <EthernetUdp.h>
+#include <TeensyMAC.h>
+#include <OSCMessage.h>
+// Enter a MAC address and IP address for your controller below.
+// The IP address will be dependent on your local network:
+byte mac[] = {
+ 0x00, 0xAA, 0xBB, 0xCC, 0xDE, 0x02
+};
+
+IPAddress ip(192, 168, 1, 204);    //local IP of Arduino/Teensy
+//unsigned int localPort = 8888;      // local port to listen on (not needed for multicast)
+
+IPAddress ipMulti(239, 200, 200, 200); // ipMidi Multicast address
+unsigned int portMulti = 9977;   // ipMidi Mutlicast port 1
+
+
+// buffers for receiving and sending data
+byte packetBuffer[UDP_TX_PACKET_MAX_SIZE];       // buffer to hold incoming packet
+byte sendBuffer1[] = {0x90, 0x14, 0x22};        // MIDI Note On to Multicast address
+byte sendBuffer2[] = {0x80, 0x14, 0x00};        // MIDI Note Off to Multicast address
+
+// An EthernetUDP instance to let us send and receive packets over UDP
+EthernetUDP Udp;
+
+Atm_stepper stepper;
+
+class Atm_blink : public Machine {
+
+ public:
+   Atm_blink( void ) : Machine() {};
+
+   short pin;
+   atm_timer_millis timer;
+
+   EthernetUDP* _udpRef ;
+   //Atm_blink& onOSC(OSCMessage& msg );
+
+   enum { IDLE, LED_ON, LED_OFF }; // STATES
+   enum { EVT_TIMER, EVT_ON, EVT_OFF, ELSE }; // EVENTS
+   enum { ENT_ON, ENT_OFF }; // ACTIONS
+
+   Atm_blink & begin( int attached_pin, uint32_t blinkrate, EthernetUDP& udpRef  ) {
+     const static state_t state_table[] PROGMEM = {
+       /*            ON_ENTER    ON_LOOP  ON_EXIT  EVT_TIMER  EVT_ON  EVT_OFF  ELSE */
+       /* IDLE    */  ENT_OFF,        -1,      -1,        -1, LED_ON,      -1,   -1,
+       /* LED_ON  */   ENT_ON,        -1,      -1,   LED_OFF,     -1,    IDLE,   -1,
+       /* LED_OFF */  ENT_OFF,        -1,      -1,    LED_ON,     -1,    IDLE,   -1,
+     };
+     Machine::begin( state_table, ELSE );
+     pin = attached_pin;
+     timer.set( blinkrate );
+     pinMode( pin, OUTPUT );
+     this->_udpRef =   &udpRef;
+     return *this;
+   }
 
-     int event( int id ) {
-       switch ( id ) {
-         case EVT_TIMER :
-           return timer.expired( this );
-       }
-       return 0;
+   int event( int id ) {
+     switch ( id ) {
+       case EVT_TIMER :
+         return timer.expired( this );
      }
+     return 0;
+   }
 
-     void action( int id ) {
+   void action( int id ) {
 
-       switch ( id ) {
-         case ENT_ON :
-           digitalWrite( pin, HIGH );
+     switch ( id ) {
+       case ENT_ON :
+         digitalWrite( pin, HIGH );
 
-           return;
+         return;
 
-         case ENT_OFF :
-           digitalWrite( pin, LOW );
-           return;
-       }
+       case ENT_OFF :
+         digitalWrite( pin, LOW );
+         return;
      }
+   }
 
-     Atm_blink& onOSC(OSCMessage& msg ){
-       if(msg.fullMatch("/truc")){
-         OSCMessage _msg("/blink");
-         _msg.add("youpi");
-         _udpRef->beginPacket(ipMulti, portMulti);
-         _msg.send(*_udpRef); // send the bytes to the SLIP stream
-         _udpRef->endPacket(); // mark the end of the OSC Packet
-         _msg.empty();
-       }
+   Atm_blink& onOSC(OSCMessage& msg ){
+     if(msg.fullMatch("/truc")){
+       OSCMessage _msg("/blink");
+       _msg.add("youpi");
+       _udpRef->beginPacket(ipMulti, portMulti);
+       _msg.send(*_udpRef); // send the bytes to the SLIP stream
+       _udpRef->endPacket(); // mark the end of the OSC Packet
+       _msg.empty();
      }
- };
+   }
+};
 
- Atm_blink led;
+Atm_blink led;
 
 void test(OSCMessage &msg, int addrOffset){
-  msg.getInt(0)?led.trigger( led.EVT_ON ):led.trigger( led.EVT_OFF );
+msg.getInt(0)?led.trigger( led.EVT_ON ):led.trigger( led.EVT_OFF );
 }
 
 void routeTone(OSCMessage &msg, int addrOffset ){
-  //iterate through all the analog pins
-  for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
-    //match against the pin number strings
-    int pinMatched = msg.match("5", addrOffset);
-    if(pinMatched){
-      unsigned int frequency = 0;
-      //if it has an int, then it's an integers frequency in Hz
-      if (msg.isInt(0)){
-        frequency = msg.getInt(0);
-      } //otherwise it's a floating point frequency in Hz
-      else if(msg.isFloat(0)){
-        frequency = msg.getFloat(0);
-      }
-      else
-        noTone(pin);
-      if(frequency>0)
-      {
-         if(msg.isInt(1))
-           tone(pin, frequency, msg.getInt(1));
-         else
-           tone(pin, frequency);
-      }
+//iterate through all the analog pins
+for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+  //match against the pin number strings
+  int pinMatched = msg.match("5", addrOffset);
+  if(pinMatched){
+    unsigned int frequency = 0;
+    //if it has an int, then it's an integers frequency in Hz
+    if (msg.isInt(0)){
+      frequency = msg.getInt(0);
+    } //otherwise it's a floating point frequency in Hz
+    else if(msg.isFloat(0)){
+      frequency = msg.getFloat(0);
+    }
+    else
+      noTone(pin);
+    if(frequency>0)
+    {
+       if(msg.isInt(1))
+         tone(pin, frequency, msg.getInt(1));
+       else
+         tone(pin, frequency);
     }
   }
 }
+}
 
- void setup() {
-   SPI.setSCK(27);
-   Ethernet.init(10);
-   teensyMAC(mac);
-   Ethernet.begin(mac, ip);              // start the Ethernet and UDP:
- //  Udp.beginMulti(ipMulti, portMulti);   // for modified Arduino library
-   Udp.beginMulticast(ipMulti, portMulti); // for modified Teensy Ethernet library
-   Serial.begin(115200); // higher Baud rate for faster refresh, CHANGE IN SERIAL MONITOR
+void setup() {
+ SPI.setSCK(27);
+ Ethernet.init(10);
+ teensyMAC(mac);
+ Ethernet.begin(mac, ip);              // start the Ethernet and UDP:
+//  Udp.beginMulti(ipMulti, portMulti);   // for modified Arduino library
+ Udp.beginMulticast(ipMulti, portMulti); // for modified Teensy Ethernet library
+ Serial.begin(115200); // higher Baud rate for faster refresh, CHANGE IN SERIAL MONITOR
+
+ led.begin( 14, 200, Udp);        // Setup a blink machine on pin 4
+ led.trigger( led.EVT_ON );  // Turn it on
+
+  Serial.begin( 9600 );
+  delay(1000);
+  stepper.trace( Serial );
+  Serial.println("Started");
+  stepper.begin(2,1);
+  //stepper.trigger(stepper.EVT_GOTO);
+  stepper.gotoStep(16000);
+  pinMode(00, OUTPUT);
+  digitalWrite(0, HIGH);
+}
 
-   led.begin( 14, 200, Udp);        // Setup a blink machine on pin 4
-   led.trigger( led.EVT_ON );  // Turn it on
+void loop() {
+  automaton.run();
+ OSCMessage msgIn;
+ int size;
 
+ if( (size = Udp.parsePacket())>0)
+ {
+   while(size--)
+     msgIn.fill(Udp.read());
 
+    if(!msgIn.hasError())
+      msgIn.route("/blink", test);
+      led.onOSC(msgIn);
  }
 
- void loop() {
+ OSCMessage msg("/analog/0");
+ msg.add((int32_t)analogRead(0));
 
-   OSCMessage msgIn;
-   int size;
+ Udp.beginPacket(ipMulti, portMulti);
+   msg.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ msg.empty(); // free space occupied by message
 
-   if( (size = Udp.parsePacket())>0)
-   {
-     while(size--)
-       msgIn.fill(Udp.read());
+ // led.cycle();
 
-      if(!msgIn.hasError())
-        msgIn.route("/blink", test);
-        led.onOSC(msgIn);
-   }
-
-   OSCMessage msg("/analog/0");
-   msg.add((int32_t)analogRead(0));
-
-   Udp.beginPacket(ipMulti, portMulti);
-     msg.send(Udp); // send the bytes to the SLIP stream
-   Udp.endPacket(); // mark the end of the OSC Packet
-   msg.empty(); // free space occupied by message
-
-   led.cycle();
+ //delay(10);
+ //UDPsend();   // sending of packets; do not use with UDPreceive because it's including delay()!!
+ //UDPreceive();
 
-   delay(20);
-   //UDPsend();   // sending of packets; do not use with UDPreceive because it's including delay()!!
-   //UDPreceive();
-
- }
+}