AccelStepperI2C  v 0.1
I2C wrapper (and a bit more) for the AccelStepper Arduino library
AccelStepperI2C.h
Go to the documentation of this file.
1 
60 #ifndef AccelStepperI2C_h
61 #define AccelStepperI2C_h
62 
63 #define DEBUG // uncomment for debug output to Serial (which has to be begun() in the main sketch)
64 
65 #include <Arduino.h>
66 #include <AccelStepper.h>
67 #include <I2Cwrapper.h>
68 
69 #ifdef DEBUG
70 #define log(...) Serial.print(__VA_ARGS__)
71 #else
72 #define log(...)
73 #endif // DEBUG
74 
75 const uint8_t AccelStepperI2CmaxBuf = 20; // upper limit of send and receive buffer(s)
76 
77 // used as return valuefor calls with long/float result that got no correct reply from slave
78 // However, errors are now signaled with resultOK, so no need for a special value here, just take 0
79 const long resError = 0;
80 
81 
86 {
87  uint32_t cycles;
88  uint16_t lastProcessTime;
89  uint16_t lastRequestTime;
90  uint16_t lastReceiveTime;
91 };
92 
93 // I2C commands and, if non void, returned bytes, for AccelStepper functions
94 const uint8_t moveToCmd = 10;
95 const uint8_t moveCmd = 11;
96 const uint8_t runCmd = 12; const uint8_t runResult = 1; // 1 boolean
97 const uint8_t runSpeedCmd = 13; const uint8_t runSpeedResult = 1; // 1 boolean
98 const uint8_t setMaxSpeedCmd = 14;
99 const uint8_t maxSpeedCmd = 15; const uint8_t maxSpeedResult = 4; // 1 float
100 const uint8_t setAccelerationCmd = 16;
101 const uint8_t setSpeedCmd = 17;
102 const uint8_t speedCmd = 18; const uint8_t speedResult = 4; // 1 float
103 const uint8_t distanceToGoCmd = 19; const uint8_t distanceToGoResult = 4; // 1 long
104 const uint8_t targetPositionCmd = 20; const uint8_t targetPositionResult = 4; // 1 long
105 const uint8_t currentPositionCmd = 21; const uint8_t currentPositionResult = 4; // 1 long
106 const uint8_t setCurrentPositionCmd = 22;
107 const uint8_t runToPositionCmd = 23; // blocking, implemented, but on master's side alone, so this code is unused
108 const uint8_t runSpeedToPositionCmd = 24; const uint8_t runSpeedToPositionResult = 1; // 1 boolean
109 const uint8_t runToNewPositionCmd = 25; // blocking, implemented, but on master's side alone, so this code is unused
110 const uint8_t stopCmd = 26;
111 const uint8_t disableOutputsCmd = 27;
112 const uint8_t enableOutputsCmd = 28;
113 const uint8_t setMinPulseWidthCmd = 29;
114 const uint8_t setEnablePinCmd = 30;
115 const uint8_t setPinsInverted1Cmd = 31;
116 const uint8_t setPinsInverted2Cmd = 32;
117 const uint8_t isRunningCmd = 33; const uint8_t isRunningResult = 1; // 1 boolean
118 
119 // new commands for AccelStepperI2C start here
120 
121 const uint8_t attachCmd = 40; const uint8_t attachResult = 1; // 1 uint8_t
122 const uint8_t enableDiagnosticsCmd = 41;
123 const uint8_t diagnosticsCmd = 42; const uint8_t diagnosticsResult = sizeof(diagnosticsReport);
124 const uint8_t enableInterruptsCmd = 43;
125 const uint8_t setStateCmd = 44;
126 const uint8_t getStateCmd = 45; const uint8_t getStateResult = 1; // 1 uint8_t
127 const uint8_t setEndstopPinCmd = 46;
128 const uint8_t enableEndstopsCmd = 47;
129 const uint8_t endstopsCmd = 48; const uint8_t endstopsResult = 1; // 1 uint8_t
130 
131 
133 const uint8_t state_stopped = 0;
134 const uint8_t state_run = 1;
135 const uint8_t state_runSpeed = 2;
136 const uint8_t state_runSpeedToPosition = 3;
137 
144 const uint8_t interruptReason_endstopHit = 3;
150 /*****************************************************************************/
151 /*****************************************************************************/
152 
164 {
165 public:
171 
172 
204  void attach(uint8_t interface = AccelStepper::FULL4WIRE,
205  uint8_t pin1 = 2,
206  uint8_t pin2 = 3,
207  uint8_t pin3 = 4,
208  uint8_t pin4 = 5,
209  bool enable = true);
210 
211  // AccelStepper(void (*forward)(), void (*backward)()); // constructor [2/2] makes no sense over I2C, the callbacks would have to go back from slave to master...
212  void moveTo(long absolute);
213  void move(long relative);
214 
219  boolean run();
220 
225  boolean runSpeed();
226 
227  void setMaxSpeed(float speed);
228  float maxSpeed();
229  void setAcceleration(float acceleration);
230  void setSpeed(float speed);
231  float speed();
232  long distanceToGo();
233  long targetPosition();
234  long currentPosition();
235  void setCurrentPosition(long position);
236 
244  void runToPosition();
245 
253  void runToNewPosition(long position);
254 
259  boolean runSpeedToPosition();
260 
261 
262  void stop();
263  void disableOutputs();
264  void enableOutputs();
265  void setMinPulseWidth(unsigned int minWidth);
266  void setEnablePin(uint8_t enablePin = 0xff);
267  void setPinsInverted(bool directionInvert = false, bool stepInvert = false, bool enableInvert = false);
268  void setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert);
269  bool isRunning();
270 
271 
277  void enableDiagnostics(bool enable);
278 
279 
288  void diagnostics(diagnosticsReport* report);
289 
290 
300  void enableInterrupts(bool enable = true);
301 
313  void setEndstopPin(int8_t pin, bool activeLow, bool internalPullup);
314 
338  void enableEndstops(bool enable = true);
339 
346  uint8_t endstops(); // returns endstop(s) states in bits 0 and 1
347 
348 
353  void setState(uint8_t newState);
354 
359  uint8_t getState();
360 
364  void stopState();
365 
370  void runState();
371 
376  void runSpeedState();
377 
382 
383  int8_t myNum = -1;
384 
385 private:
386  //uint8_t attach(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5, bool enable = true);
387  I2Cwrapper* wrapper;
388 
389 };
390 
391 
392 #endif
diagnosticsCmd
const uint8_t diagnosticsCmd
Definition: AccelStepperI2C.h:123
resError
const long resError
Definition: AccelStepperI2C.h:79
I2Cwrapper
A helper class for the AccelStepperI2C (and ServoI2C) library.
Definition: I2Cwrapper.h:79
moveToCmd
const uint8_t moveToCmd
Definition: AccelStepperI2C.h:94
AccelStepperI2C::runSpeedToPosition
boolean runSpeedToPosition()
Don't use this, use state machine instead with runSpeedToPositionState().
Definition: AccelStepperI2C.cpp:90
interruptReason_endstopHit
const uint8_t interruptReason_endstopHit
Definition: AccelStepperI2C.h:144
diagnosticsResult
const uint8_t diagnosticsResult
Definition: AccelStepperI2C.h:123
AccelStepperI2C::setPinsInverted
void setPinsInverted(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)
Definition: AccelStepperI2C.cpp:218
AccelStepperI2C::setState
void setState(uint8_t newState)
Set the state machine's state manually.
Definition: AccelStepperI2C.cpp:297
state_runSpeed
const uint8_t state_runSpeed
corresponds to AccelStepper::runSpeed(), will remain active until stopped by user or endstop
Definition: AccelStepperI2C.h:135
setMinPulseWidthCmd
const uint8_t setMinPulseWidthCmd
Definition: AccelStepperI2C.h:113
interruptReason_targetReachedByRunSpeedToPosition
const uint8_t interruptReason_targetReachedByRunSpeedToPosition
Definition: AccelStepperI2C.h:143
AccelStepperI2C::moveTo
void moveTo(long absolute)
Definition: AccelStepperI2C.cpp:49
speedResult
const uint8_t speedResult
Definition: AccelStepperI2C.h:102
runToNewPositionCmd
const uint8_t runToNewPositionCmd
Definition: AccelStepperI2C.h:109
AccelStepperI2C::setEnablePin
void setEnablePin(uint8_t enablePin=0xff)
Definition: AccelStepperI2C.cpp:210
AccelStepperI2C::enableOutputs
void enableOutputs()
Definition: AccelStepperI2C.cpp:195
AccelStepperI2C::targetPosition
long targetPosition()
Definition: AccelStepperI2C.cpp:112
currentPositionResult
const uint8_t currentPositionResult
Definition: AccelStepperI2C.h:105
AccelStepperI2C::diagnostics
void diagnostics(diagnosticsReport *report)
Get most recent diagnostics data. Needs diagnostics enabled and a slave which was compiled with the D...
Definition: AccelStepperI2C.cpp:287
speedCmd
const uint8_t speedCmd
Definition: AccelStepperI2C.h:102
isRunningCmd
const uint8_t isRunningCmd
Definition: AccelStepperI2C.h:117
AccelStepperI2C::stopState
void stopState()
Will stop any of the above states, i.e. stop polling. It does nothing else, so the master is solely i...
Definition: AccelStepperI2C.cpp:316
AccelStepperI2C::runSpeedState
void runSpeedState()
Will poll runSpeed(), i.e. run at constant speed until told otherwise (see AccelStepperI2C::stopState...
Definition: AccelStepperI2C.cpp:328
runSpeedCmd
const uint8_t runSpeedCmd
Definition: AccelStepperI2C.h:97
stopCmd
const uint8_t stopCmd
Definition: AccelStepperI2C.h:110
diagnosticsReport::cycles
uint32_t cycles
Number of slave's main loop executions since the last reboot.
Definition: AccelStepperI2C.h:87
enableDiagnosticsCmd
const uint8_t enableDiagnosticsCmd
Definition: AccelStepperI2C.h:122
disableOutputsCmd
const uint8_t disableOutputsCmd
Definition: AccelStepperI2C.h:111
AccelStepperI2C::distanceToGo
long distanceToGo()
Definition: AccelStepperI2C.cpp:101
setMaxSpeedCmd
const uint8_t setMaxSpeedCmd
Definition: AccelStepperI2C.h:98
AccelStepperI2C::myNum
int8_t myNum
Stepper number with myNum >= 0 for successfully added steppers.
Definition: AccelStepperI2C.h:383
enableInterruptsCmd
const uint8_t enableInterruptsCmd
Definition: AccelStepperI2C.h:124
AccelStepperI2C::disableOutputs
void disableOutputs()
Definition: AccelStepperI2C.cpp:188
targetPositionResult
const uint8_t targetPositionResult
Definition: AccelStepperI2C.h:104
getStateResult
const uint8_t getStateResult
Definition: AccelStepperI2C.h:126
AccelStepperI2C::endstops
uint8_t endstops()
Read current state of endstops.
Definition: AccelStepperI2C.cpp:360
AccelStepperI2CmaxBuf
const uint8_t AccelStepperI2CmaxBuf
Definition: AccelStepperI2C.h:75
currentPositionCmd
const uint8_t currentPositionCmd
Definition: AccelStepperI2C.h:105
AccelStepperI2C::isRunning
bool isRunning()
Definition: AccelStepperI2C.cpp:259
AccelStepperI2C
An I2C wrapper class for the AccelStepper library.
Definition: AccelStepperI2C.h:163
endstopsResult
const uint8_t endstopsResult
Definition: AccelStepperI2C.h:129
AccelStepperI2C::setMaxSpeed
void setMaxSpeed(float speed)
Definition: AccelStepperI2C.cpp:142
acceleration
const float acceleration
Definition: Interrupt_Endstop.ino:37
diagnosticsReport::lastProcessTime
uint16_t lastProcessTime
microseconds the slave needed to process (interpret) most recently received command
Definition: AccelStepperI2C.h:88
AccelStepperI2C::run
boolean run()
Don't use this, use state machine instead with runState().
Definition: AccelStepperI2C.cpp:66
setPinsInverted1Cmd
const uint8_t setPinsInverted1Cmd
Definition: AccelStepperI2C.h:115
I2Cwrapper.h
A helper class for the AccelStepperI2C (and ServoI2C) library.
runSpeedResult
const uint8_t runSpeedResult
Definition: AccelStepperI2C.h:97
state_run
const uint8_t state_run
corresponds to AccelStepper::run(), will fall back to state_stopped if target reached or endstop hit
Definition: AccelStepperI2C.h:134
AccelStepperI2C::AccelStepperI2C
AccelStepperI2C(I2Cwrapper *w)
Constructor.
Definition: AccelStepperI2C.cpp:26
getStateCmd
const uint8_t getStateCmd
Definition: AccelStepperI2C.h:126
AccelStepperI2C::enableDiagnostics
void enableDiagnostics(bool enable)
Turn on/off diagnostic speed logging.
Definition: AccelStepperI2C.cpp:279
AccelStepperI2C::runSpeedToPositionState
void runSpeedToPositionState()
Will poll runSpeedToPosition(), i.e. run at constant speed until target has been reached.
Definition: AccelStepperI2C.cpp:334
setEnablePinCmd
const uint8_t setEnablePinCmd
Definition: AccelStepperI2C.h:114
AccelStepperI2C::runToNewPosition
void runToNewPosition(long position)
This is a blocking function in the original, it will only return after the new target has been reache...
Definition: AccelStepperI2C.cpp:245
runSpeedToPositionResult
const uint8_t runSpeedToPositionResult
Definition: AccelStepperI2C.h:108
attachCmd
const uint8_t attachCmd
Definition: AccelStepperI2C.h:121
AccelStepperI2C::currentPosition
long currentPosition()
Definition: AccelStepperI2C.cpp:123
AccelStepperI2C::runState
void runState()
Will poll run(), i.e. run to the target with acceleration and stop the state machine upon reaching it...
Definition: AccelStepperI2C.cpp:322
AccelStepperI2C::setAcceleration
void setAcceleration(float acceleration)
Definition: AccelStepperI2C.cpp:161
setAccelerationCmd
const uint8_t setAccelerationCmd
Definition: AccelStepperI2C.h:100
moveCmd
const uint8_t moveCmd
Definition: AccelStepperI2C.h:95
runCmd
const uint8_t runCmd
Definition: AccelStepperI2C.h:96
setPinsInverted2Cmd
const uint8_t setPinsInverted2Cmd
Definition: AccelStepperI2C.h:116
setCurrentPositionCmd
const uint8_t setCurrentPositionCmd
Definition: AccelStepperI2C.h:106
state_stopped
const uint8_t state_stopped
stepper state machine states
Definition: AccelStepperI2C.h:133
attachResult
const uint8_t attachResult
Definition: AccelStepperI2C.h:121
AccelStepperI2C::runSpeed
boolean runSpeed()
Don't use this, use state machine instead with runSpeedState().
Definition: AccelStepperI2C.cpp:78
diagnosticsReport
Used to transmit diagnostic info with AccelStepperI2C::diagnostics().
Definition: AccelStepperI2C.h:85
endstopsCmd
const uint8_t endstopsCmd
Definition: AccelStepperI2C.h:129
setEndstopPinCmd
const uint8_t setEndstopPinCmd
Definition: AccelStepperI2C.h:127
AccelStepperI2C::setSpeed
void setSpeed(float speed)
Definition: AccelStepperI2C.cpp:169
distanceToGoCmd
const uint8_t distanceToGoCmd
Definition: AccelStepperI2C.h:103
maxSpeedCmd
const uint8_t maxSpeedCmd
Definition: AccelStepperI2C.h:99
state_runSpeedToPosition
const uint8_t state_runSpeedToPosition
corresponds to AccelStepper::state_runSpeedToPosition(), will fall back to state_stopped if target po...
Definition: AccelStepperI2C.h:136
AccelStepperI2C::speed
float speed()
Definition: AccelStepperI2C.cpp:177
isRunningResult
const uint8_t isRunningResult
Definition: AccelStepperI2C.h:117
AccelStepperI2C::maxSpeed
float maxSpeed()
Definition: AccelStepperI2C.cpp:150
targetPositionCmd
const uint8_t targetPositionCmd
Definition: AccelStepperI2C.h:104
enablePin
const uint8_t enablePin
Definition: Interrupt_Endstop.ino:31
AccelStepperI2C::attach
void attach(uint8_t interface=AccelStepper::FULL4WIRE, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5, bool enable=true)
Replaces the AccelStepper constructor and takes the same arguments. Will allocate an AccelStepper obj...
Definition: AccelStepperI2C.cpp:32
enableOutputsCmd
const uint8_t enableOutputsCmd
Definition: AccelStepperI2C.h:112
AccelStepperI2C::setCurrentPosition
void setCurrentPosition(long position)
Definition: AccelStepperI2C.cpp:134
AccelStepperI2C::enableInterrupts
void enableInterrupts(bool enable=true)
Start or stop sending interrupts to master for this stepper. An interrupt will be sent whenever a sta...
Definition: AccelStepperI2C.cpp:371
AccelStepperI2C::stop
void stop()
Definition: AccelStepperI2C.cpp:252
AccelStepperI2C::move
void move(long relative)
Definition: AccelStepperI2C.cpp:57
AccelStepperI2C::setEndstopPin
void setEndstopPin(int8_t pin, bool activeLow, bool internalPullup)
Define a new endstop pin. Each stepper can have up to two, so don't call this more than twice per ste...
Definition: AccelStepperI2C.cpp:340
runToPositionCmd
const uint8_t runToPositionCmd
Definition: AccelStepperI2C.h:107
AccelStepperI2C::runToPosition
void runToPosition()
This is a blocking function in the original, it will only return after the target has been reached....
Definition: AccelStepperI2C.cpp:236
setSpeedCmd
const uint8_t setSpeedCmd
Definition: AccelStepperI2C.h:101
AccelStepperI2C::getState
uint8_t getState()
Read the state machine's state (it may have been changed by endstop or target reached condition).
Definition: AccelStepperI2C.cpp:305
setStateCmd
const uint8_t setStateCmd
Definition: AccelStepperI2C.h:125
enableEndstopsCmd
const uint8_t enableEndstopsCmd
Definition: AccelStepperI2C.h:128
runResult
const uint8_t runResult
Definition: AccelStepperI2C.h:96
AccelStepperI2C::setMinPulseWidth
void setMinPulseWidth(unsigned int minWidth)
Definition: AccelStepperI2C.cpp:202
diagnosticsReport::lastRequestTime
uint16_t lastRequestTime
microseconds the slave spent in the most recent onRequest() interrupt
Definition: AccelStepperI2C.h:89
AccelStepperI2C::enableEndstops
void enableEndstops(bool enable=true)
Tell the state machine to check the endstops regularly. If any of the (one or two) stepper's endstops...
Definition: AccelStepperI2C.cpp:352
interruptReason_targetReachedByRun
const uint8_t interruptReason_targetReachedByRun
Definition: AccelStepperI2C.h:142
runSpeedToPositionCmd
const uint8_t runSpeedToPositionCmd
Definition: AccelStepperI2C.h:108
maxSpeedResult
const uint8_t maxSpeedResult
Definition: AccelStepperI2C.h:99
diagnosticsReport::lastReceiveTime
uint16_t lastReceiveTime
microseconds the slave spent in the most recent onReceive() interrupt
Definition: AccelStepperI2C.h:90
distanceToGoResult
const uint8_t distanceToGoResult
Definition: AccelStepperI2C.h:103