I2Cwrapper v0.5.0
Generic framework for Arduino I2C target devices
AccelStepperI2C Class Reference

An I2C wrapper class for the AccelStepper library. More...

Detailed Description

An I2C wrapper class for the AccelStepper library.

This class mimicks the original AccelStepper interface. It replicates most of its methods and transmits each method call via I2C to a target running the AccelStepperI2C firmware. Functions and parameters without documentation will work just as their original, but you need to take the general restrictions into account (e.g. don't take a return value for valid without error handling).

Public Member Functions

 AccelStepperI2C (I2Cwrapper *w)
 Constructor. More...
 
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 object on the target's side and make it ready for use. Does not return an success/error result. Instead check myNum >= 0 to see if the target successfully added the stepper. If not, it's -1. More...
 
void moveTo (long absolute)
 
void move (long relative)
 
bool run ()
 Don't use this, use state machine instead with runState(). More...
 
bool runSpeed ()
 Don't use this, use state machine instead with runSpeedState(). More...
 
void setMaxSpeed (float speed)
 
float maxSpeed ()
 
void setAcceleration (float acceleration)
 
void setSpeed (float speed)
 
float speed ()
 
long distanceToGo ()
 
long targetPosition ()
 
long currentPosition ()
 
void setCurrentPosition (long position)
 
void runToPosition ()
 This is a blocking function in the original, it will only return after the target has been reached. This I2C implementation mimicks the original, but uses the state machine and checks for a target reached condition with a fixed frequency of 100ms to keep the I2C bus uncluttered. More...
 
void runToNewPosition (long position)
 This is a blocking function in the original, it will only return after the new target has been reached. This I2C implementation mimicks the original, but uses the state machine and checks for a target reached condition with a fixed frequency of 100ms to keep the I2C bus uncluttered. More...
 
bool runSpeedToPosition ()
 Don't use this, use state machine instead with runSpeedToPositionState(). More...
 
void stop ()
 
void disableOutputs ()
 
void enableOutputs ()
 
void setMinPulseWidth (unsigned int minWidth)
 
void setEnablePin (uint8_t enablePin=0xff)
 
void setPinsInverted (bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)
 
void setPinsInverted (bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
 
bool isRunning ()
 
void enableInterrupts (bool enable=true)
 Start or stop sending interrupts to controller for this stepper. An interrupt will be sent whenever a state machine change occured which was not triggered by the controller. At the moment, this could either be a target reached condition in runState() or runSpeedToPositionState(), or an endstop reached condition. Before you can use this, you need to define an interrupt pin on you target device with I2Cwrapper::setInterruptPin(). More...
 
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 stepper. More...
 
void enableEndstops (bool enable=true)
 Tell the state machine to check the endstops regularly. If any of the (one or two) stepper's endstops is hit, the state machine will revert to state_stopped. To prevent overshoot, also the stepper's speed is set to 0 and its target to the current position. More...
 
uint8_t endstops ()
 Read current raw, i.e. not debounced state of endstops. It's basically one or two digitalReads() combined in one result. More...
 
void setState (uint8_t newState)
 Set the state machine's state manually. More...
 
uint8_t getState ()
 Read the state machine's state (it may have been changed by endstop or target reached condition). More...
 
void stopState ()
 Will stop any of the above states, i.e. stop polling. It does nothing else, so the controller is solely in command of target, speed, and other settings. More...
 
void runState ()
 Will poll run(), i.e. run to the target with acceleration and stop the state machine upon reaching it. More...
 
void runSpeedState ()
 Will poll runSpeed(), i.e. run at constant speed until told otherwise (see AccelStepperI2C::stopState(). More...
 
void runSpeedToPositionState ()
 Will poll runSpeedToPosition(), i.e. run at constant speed until target has been reached. More...
 

Public Attributes

int8_t myNum = -1
 Stepper number with myNum >= 0 for successfully added steppers. More...
 

Constructor & Destructor Documentation

◆ AccelStepperI2C()

AccelStepperI2C::AccelStepperI2C ( I2Cwrapper w)

Constructor.

Parameters
wWrapper object representing the target the stepper is connected to.

Member Function Documentation

◆ attach()

void AccelStepperI2C::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 object on the target's side and make it ready for use. Does not return an success/error result. Instead check myNum >= 0 to see if the target successfully added the stepper. If not, it's -1.

Parameters
interfaceOnly AccelStepper::DRIVER is tested at the moment, but AccelStepper::FULL2WIRE, AccelStepper::FULL3WIRE, AccelStepper::FULL4WIRE, AccelStepper::HALF3WIRE, and AccelStepper::HALF4WIRE should work as well, AccelStepper::FUNCTION of course not
pin1,pin2,pin3,pin4,enablesee original library
Note
The target's platform pin names might not be known to the controller's platform, if both are different. So it is safer to use integer equivalents as defined in the respective platform's pins_arduino.h, e.g. for ESP8266:
  • static const uint8_t D0 = 16;
  • static const uint8_t D1 = 5;
  • static const uint8_t D2 = 4;
  • static const uint8_t D3 = 0;
  • static const uint8_t D4 = 2;
  • static const uint8_t D5 = 14;
  • static const uint8_t D6 = 12;
  • static const uint8_t D7 = 13;
  • static const uint8_t D8 = 15; or for plain Arduinos:
  • #define PIN_A0 (14)
  • #define PIN_A1 (15)
  • #define PIN_A2 (16)
  • #define PIN_A3 (17)
  • #define PIN_A4 (18)
  • #define PIN_A5 (19)
  • #define PIN_A6 (20)
  • #define PIN_A7 (21)

◆ currentPosition()

long AccelStepperI2C::currentPosition ( )

◆ disableOutputs()

void AccelStepperI2C::disableOutputs ( )

◆ distanceToGo()

long AccelStepperI2C::distanceToGo ( )

◆ enableEndstops()

void AccelStepperI2C::enableEndstops ( bool  enable = true)

Tell the state machine to check the endstops regularly. If any of the (one or two) stepper's endstops is hit, the state machine will revert to state_stopped. To prevent overshoot, also the stepper's speed is set to 0 and its target to the current position.

An interrupt will be triggered, if interrupts are enabled, in that case I2Cwrapper::clearInterrupt() will then inform about the interrupt's cause. Independent of an interrupt, the controller can use endstops() to find out if an endstop was hit and which one it was.

A "hit" condition is defined as an end stop switch becoming active. Nothing happens if it stays active or becomes inactive. A simple debouncing mechanism is in place. After a new flank (switch becoming active or inactive), it will ignore any further flanks for a set interval of 5 milliseconds, which should suffice for most switches to get into a stable state.

Todo:
Find solution for moving a stepper out of an endstop's zone. implemented debounce and active-flank detection so that there's no danger of repeated interrupts being triggered while in an endstop's active zone.
Parameters
enabletrue (default) to enable, false to disable.

◆ enableInterrupts()

void AccelStepperI2C::enableInterrupts ( bool  enable = true)

Start or stop sending interrupts to controller for this stepper. An interrupt will be sent whenever a state machine change occured which was not triggered by the controller. At the moment, this could either be a target reached condition in runState() or runSpeedToPositionState(), or an endstop reached condition. Before you can use this, you need to define an interrupt pin on you target device with I2Cwrapper::setInterruptPin().

Parameters
enabletrue (default) to enable, false to disable.
See also
I2Cwrapper::setInterruptPin()

◆ enableOutputs()

void AccelStepperI2C::enableOutputs ( )

◆ endstops()

uint8_t AccelStepperI2C::endstops ( )

Read current raw, i.e. not debounced state of endstops. It's basically one or two digitalReads() combined in one result.

Returns
One bit for each endstop, LSB is always the last addded endstop. Takes activeLow setting in account, i.e. an activated switch will always return 1.
See also
enableEndstops()

◆ getState()

uint8_t AccelStepperI2C::getState ( )

Read the state machine's state (it may have been changed by endstop or target reached condition).

Returns
one of state_stopped, state_run, state_runSpeed, or state_runSpeedToPosition.

◆ isRunning()

bool AccelStepperI2C::isRunning ( )

◆ maxSpeed()

float AccelStepperI2C::maxSpeed ( )

◆ move()

void AccelStepperI2C::move ( long  relative)

◆ moveTo()

void AccelStepperI2C::moveTo ( long  absolute)

◆ run()

bool AccelStepperI2C::run ( )

Don't use this, use state machine instead with runState().

Returns
If you use it for whatever reason, check sentOK and resultOK to be sure that things are alright and the return value can be trusted.

◆ runSpeed()

bool AccelStepperI2C::runSpeed ( )

Don't use this, use state machine instead with runSpeedState().

Returns
If you use it for whatever reason, check sentOK and resultOK to be sure that things are alright and the return value can be trusted.

◆ runSpeedState()

void AccelStepperI2C::runSpeedState ( )

Will poll runSpeed(), i.e. run at constant speed until told otherwise (see AccelStepperI2C::stopState().

◆ runSpeedToPosition()

bool AccelStepperI2C::runSpeedToPosition ( )

Don't use this, use state machine instead with runSpeedToPositionState().

Returns
If you use it for whatever reason, check sentOK and resultOK to be sure that things are alright and the return value can be trusted.

◆ runSpeedToPositionState()

void AccelStepperI2C::runSpeedToPositionState ( )

Will poll runSpeedToPosition(), i.e. run at constant speed until target has been reached.

◆ runState()

void AccelStepperI2C::runState ( )

Will poll run(), i.e. run to the target with acceleration and stop the state machine upon reaching it.

◆ runToNewPosition()

void AccelStepperI2C::runToNewPosition ( long  position)

This is a blocking function in the original, it will only return after the new target has been reached. This I2C implementation mimicks the original, but uses the state machine and checks for a target reached condition with a fixed frequency of 100ms to keep the I2C bus uncluttered.

Note
Does not check for endstops, implement your own loop if you need them.

◆ runToPosition()

void AccelStepperI2C::runToPosition ( )

This is a blocking function in the original, it will only return after the target has been reached. This I2C implementation mimicks the original, but uses the state machine and checks for a target reached condition with a fixed frequency of 100ms to keep the I2C bus uncluttered.

Note
Does not check for endstops, implement your own loop if you need them.

◆ setAcceleration()

void AccelStepperI2C::setAcceleration ( float  acceleration)

◆ setCurrentPosition()

void AccelStepperI2C::setCurrentPosition ( long  position)

◆ setEnablePin()

void AccelStepperI2C::setEnablePin ( uint8_t  enablePin = 0xff)

◆ setEndstopPin()

void AccelStepperI2C::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 stepper.

Parameters
pinPin the endstop switch is connected to.
activeLowTrue if activated switch will pull pin LOW, false if HIGH.
internalPullupUse internal pullup for this pin.
See also
Use AccelStepperI2C::enableEndstops() to tell the state machine to actually use the endstop(s). Use AccelStepperI2C::endstops() to read their currentl state

◆ setMaxSpeed()

void AccelStepperI2C::setMaxSpeed ( float  speed)

◆ setMinPulseWidth()

void AccelStepperI2C::setMinPulseWidth ( unsigned int  minWidth)

◆ setPinsInverted() [1/2]

void AccelStepperI2C::setPinsInverted ( bool  directionInvert = false,
bool  stepInvert = false,
bool  enableInvert = false 
)

◆ setPinsInverted() [2/2]

void AccelStepperI2C::setPinsInverted ( bool  pin1Invert,
bool  pin2Invert,
bool  pin3Invert,
bool  pin4Invert,
bool  enableInvert 
)

◆ setSpeed()

void AccelStepperI2C::setSpeed ( float  speed)

◆ setState()

void AccelStepperI2C::setState ( uint8_t  newState)

Set the state machine's state manually.

Parameters
newStateone of state_stopped, state_run, state_runSpeed, or state_runSpeedToPosition.

◆ speed()

float AccelStepperI2C::speed ( )

◆ stop()

void AccelStepperI2C::stop ( )

◆ stopState()

void AccelStepperI2C::stopState ( )

Will stop any of the above states, i.e. stop polling. It does nothing else, so the controller is solely in command of target, speed, and other settings.

◆ targetPosition()

long AccelStepperI2C::targetPosition ( )

Member Data Documentation

◆ myNum

int8_t AccelStepperI2C::myNum = -1

Stepper number with myNum >= 0 for successfully added steppers.


The documentation for this class was generated from the following files: