270 #ifndef AccelStepper_h
271 #define AccelStepper_h
277 #include <WProgram.h>
286 #if (defined(ARDUINO) && ARDUINO >= 155) || defined(ESP8266)
287 #define YIELD yield();
404 void moveTo(
long absolute);
409 void move(
long relative);
543 void setPinsInverted(
bool directionInvert =
false,
bool stepInvert =
false,
bool enableInvert =
false);
551 void setPinsInverted(
bool pin1Invert,
bool pin2Invert,
bool pin3Invert,
bool pin4Invert,
bool enableInvert);
669 uint8_t _pinInverted[4];
692 unsigned long _lastStepTime;
695 unsigned int _minPulseWidth;
704 bool _enableInverted;
Support for stepper motors with acceleration etc.
Definition: AccelStepper.h:338
void runToNewPosition(long position)
Definition: AccelStepper.cpp:658
void runToPosition()
Definition: AccelStepper.cpp:640
boolean _direction
Definition: AccelStepper.h:653
virtual void disableOutputs()
Definition: AccelStepper.cpp:570
bool isRunning()
Definition: AccelStepper.cpp:676
AccelStepper(uint8_t interface=AccelStepper::FULL4WIRE, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5, bool enable=true)
Definition: AccelStepper.cpp:192
virtual void step6(long step)
Definition: AccelStepper.cpp:497
float speed()
Definition: AccelStepper.cpp:322
void setEnablePin(uint8_t enablePin=0xff)
Definition: AccelStepper.cpp:611
long currentPosition()
Definition: AccelStepper.cpp:82
boolean run()
Definition: AccelStepper.cpp:185
float maxSpeed()
Definition: AccelStepper.cpp:280
void stop()
Definition: AccelStepper.cpp:664
virtual void step1(long step)
Definition: AccelStepper.cpp:409
virtual void step2(long step)
Definition: AccelStepper.cpp:426
void move(long relative)
Definition: AccelStepper.cpp:33
MotorInterfaceType
Symbolic names for number of pins. Use this in the pins argument the AccelStepper constructor to prov...
Definition: AccelStepper.h:345
@ HALF3WIRE
3 wire half stepper, such as HDD spindle, 3 motor pins required
Definition: AccelStepper.h:351
@ FULL3WIRE
3 wire stepper, such as HDD spindle, 3 motor pins required
Definition: AccelStepper.h:349
@ FULL2WIRE
2 wire stepper, 2 motor pins required
Definition: AccelStepper.h:348
@ DRIVER
Stepper Driver, 2 driver pins required.
Definition: AccelStepper.h:347
@ FULL4WIRE
4 wire full stepper, 4 motor pins required
Definition: AccelStepper.h:350
@ HALF4WIRE
4 wire half stepper, 4 motor pins required
Definition: AccelStepper.h:352
@ FUNCTION
Use the functional interface, implementing your own driver functions (internal use only)
Definition: AccelStepper.h:346
unsigned long _stepInterval
Definition: AccelStepper.h:657
Direction
Direction indicator Symbolic names for the direction the motor is turning.
Definition: AccelStepper.h:564
@ DIRECTION_CCW
Counter-Clockwise.
Definition: AccelStepper.h:565
@ DIRECTION_CW
Clockwise.
Definition: AccelStepper.h:566
long distanceToGo()
Definition: AccelStepper.cpp:72
virtual void step4(long step)
Definition: AccelStepper.cpp:472
virtual ~AccelStepper()
Virtual destructor to prevent warnings during delete.
Definition: AccelStepper.h:558
virtual void step(long step)
Definition: AccelStepper.cpp:328
float acceleration()
Definition: AccelStepper.cpp:302
boolean runSpeedToPosition()
Definition: AccelStepper.cpp:646
long targetPosition()
Definition: AccelStepper.cpp:77
void setCurrentPosition(long position)
Definition: AccelStepper.cpp:89
virtual void enableOutputs()
Definition: AccelStepper.cpp:582
virtual void step0(long step)
Definition: AccelStepper.cpp:397
boolean runSpeed()
Definition: AccelStepper.cpp:41
virtual void step8(long step)
Definition: AccelStepper.cpp:531
virtual unsigned long computeNewSpeed()
Definition: AccelStepper.cpp:98
void setMaxSpeed(float speed)
Definition: AccelStepper.cpp:263
void setPinsInverted(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)
Definition: AccelStepper.cpp:623
void moveTo(long absolute)
Definition: AccelStepper.cpp:23
virtual void step3(long step)
Definition: AccelStepper.cpp:450
void setAcceleration(float acceleration)
Definition: AccelStepper.cpp:285
void setSpeed(float speed)
Definition: AccelStepper.cpp:307
virtual void setOutputPins(uint8_t mask)
Definition: AccelStepper.cpp:384
long stepForward()
Definition: AccelStepper.cpp:362
void setMinPulseWidth(unsigned int minWidth)
Definition: AccelStepper.cpp:606
long stepBackward()
Definition: AccelStepper.cpp:371