uStepper S-lite
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Friends | List of all members
uStepperSLite Class Reference

Prototype of class for accessing all features of the uStepper S-lite in a single object. More...

#include <uStepperSLite.h>

Public Member Functions

void enableMotor (void)
 Enables the stepper driver output stage. More...
 
void disableMotor (void)
 Disables the stepper driver output stage. More...
 
void pid (float error)
 This method handles the actual PID controller calculations, if enabled.
 
void pidDropin (float error)
 This method handles the actual PID Drop-in controller calculations, if enabled.
 
void checkConnectorOrientation (uint8_t mode)
 This method handles the connector orientation check in order to automatically compensate the PID for reversed direction.
 
float getPidError (void)
 This method returns the current PID error. More...
 
 uStepperSLite (float accel=1000.0, float vel=1000.0)
 Constructor of uStepper S-lite class. More...
 
void setMaxAcceleration (float accel)
 Set the maximum acceleration of the stepper motor. More...
 
void setMaxVelocity (float vel)
 Sets the maximum rotational velocity of the motor. More...
 
void runContinous (bool dir)
 Make the motor rotate continuously. More...
 
void moveSteps (int32_t steps, bool dir, bool holdMode=BRAKEON)
 Make the motor perform a predefined number of steps. More...
 
void hardStop (bool holdMode=BRAKEON)
 Stop the motor without deceleration. More...
 
void softStop (bool holdMode=BRAKEON)
 Stop the motor with deceleration. More...
 
void stop (bool brake=BRAKEON)
 Stop the motor with deceleration. More...
 
void setup (uint8_t mode=NORMAL, float stepsPerRevolution=3200.0, float pTerm=0.75, float iTerm=3.0, float dTerm=0.0, bool setHome=true, uint8_t invert=0, uint8_t runCurrent=50, uint8_t holdCurrent=30)
 Initializes the different parts of the uStepper S-lite object. More...
 
bool getCurrentDirection (void)
 Returns the direction the motor is currently configured to rotate. More...
 
uint8_t getMotorState (void)
 Get the current state of the motor. More...
 
int32_t getStepsSinceReset (void)
 Get the number of steps applied since reset. More...
 
void setCurrent (uint8_t runCurrent, uint8_t holdCurrent=25)
 Set motor run and hold current. More...
 
void setHoldCurrent (uint8_t holdCurrent)
 Set motor hold current. More...
 
void setRunCurrent (uint8_t runCurrent)
 Set motor run current. More...
 
float moveToEnd (bool dir, float stallSensitivity=0.992)
 Moves the motor to its physical limit, without limit switch. More...
 
void moveToAngle (float angle, bool holdMode=BRAKEON)
 Moves the motor to an absolute angle. More...
 
void moveAngle (float angle, bool holdMode=BRAKEON)
 Moves the motor to a relative angle. More...
 
bool isStalled (float stallSensitivity=0.992)
 This method returns a bool variable indicating wether the motor is stalled or not. More...
 
void disablePid (void)
 This method disables the PID until calling enablePid. More...
 
void enablePid (void)
 This method enables the PID after being disabled (disablePid). More...
 
void setProportional (float P)
 This method is used to change the PID proportional parameter P. More...
 
void setIntegral (float I)
 This method is used to change the PID integral parameter I. More...
 
void setDifferential (float D)
 This method is used to change the PID differential parameter D. More...
 
void invertDropinDir (bool invert)
 This method is used to invert the drop-in direction pin interpretation. More...
 
void dropinCli ()
 This method is used to tune Drop-in parameters. After tuning uStepper S-lite the parameters are saved in EEPROM. More...
 
void parseCommand (String *cmd)
 This method is used for the dropinCli to take in user commands. More...
 
void dropinPrintHelp ()
 This method is used to print the dropinCli menu explainer: More...
 

Public Attributes

volatile int32_t stepsSinceReset
 
volatile uint32_t cntSinceLastStep
 
volatile uint32_t stepDelay
 
volatile uint8_t stepGeneratorDirection
 
volatile int32_t decelToStopThreshold
 
bool continous
 
volatile uint8_t pidError = 0
 
volatile uint8_t state
 
uint8_t mode
 
volatile int32_t stepCnt
 
volatile uint8_t direction
 
float velocity
 
float acceleration
 
volatile float stepConversion
 
float pTerm
 
float stepsPerSecondToRPM
 
float RPMToStepsPerSecond
 
float iTerm
 
float dTerm
 
float stallSensitivity = 0.992
 
float angleToStep
 
float stepToAngle
 
volatile bool stall
 
volatile float RPMToStepDelay
 
volatile int32_t decelToAccelThreshold
 
volatile int32_t accelToCruiseThreshold
 
volatile int32_t cruiseToDecelThreshold
 
volatile float currentPidSpeed
 
volatile float currentPidAcceleration
 
volatile float pidStepsSinceReset
 
volatile int32_t targetPosition
 
volatile bool pidDisabled
 
bool brake
 
volatile float currentPidError
 
volatile float pidTargetPosition
 
uStepperEncoder encoder
 
Tmc2208 driver
 
bool invertPidDropinDirection
 

Private Member Functions

bool detectStall (void)
 This method is used internally for stall detection. More...
 
bool loadDropinSettings (void)
 This method loads the dropin settings stored in EEPROM. More...
 
void saveDropinSettings (void)
 This method stores the current dropin settings in EEPROM. More...
 
uint8_t dropinSettingsCalcChecksum (dropinCliSettings_t *settings)
 This method is used internally for stall detection. More...
 

Private Attributes

dropinCliSettings_t dropinSettings
 

Friends

void used
 
void naked
 
void TIMER1_COMPA_vect (void) __attribute__((signal
 Measures angle and speed of motor. More...
 
void TIMER3_COMPA_vect (void) __attribute__((signal
 Handles accelerations. More...
 
void INT0_vect (void) __attribute__((signal
 Used by dropin feature to take in step pulses. More...
 
void uStepperEncoder::setHome (void)
 

Detailed Description

Prototype of class for accessing all features of the uStepper S-lite in a single object.

This class enables the user of the library to access all features of the uStepper S-lite board, by use of a single object.

Definition at line 437 of file uStepperSLite.h.

Constructor & Destructor Documentation

◆ uStepperSLite()

uStepperSLite::uStepperSLite ( float  accel = 1000.0,
float  vel = 1000.0 
)

Constructor of uStepper S-lite class.

        This is the constructor of the uStepper S-lite class. This version
        of the constructor takes in two arguments, "accel" and "vel".
        These two arguments lets the programmer set the maximum
        acceleration and velocity, respectively, during instantiation
        of the uStepper S-lite object.
Parameters
accel- Floating point representation of the maximum acceleration allowed in steps/s^2.
vel- Floating point representation of the maximum velocity allowed in steps/s.

Definition at line 520 of file uStepperSLite.cpp.

Member Function Documentation

◆ detectStall()

bool uStepperSLite::detectStall ( void  )
private

This method is used internally for stall detection.

Returns
0 = not stalled, 1 = stalled

Definition at line 1485 of file uStepperSLite.cpp.

◆ disableMotor()

void uStepperSLite::disableMotor ( void  )

Disables the stepper driver output stage.

        This function disables the stepper driver output stage. If
        this function is used, the motor will not brake, and it will
        be possible to turn the motor shaft by hand

Definition at line 1143 of file uStepperSLite.cpp.

◆ disablePid()

void uStepperSLite::disablePid ( void  )

This method disables the PID until calling enablePid.

Definition at line 1406 of file uStepperSLite.cpp.

◆ dropinCli()

void uStepperSLite::dropinCli ( )

This method is used to tune Drop-in parameters. After tuning uStepper S-lite the parameters are saved in EEPROM.

Usage:

Set Proportional constant: 'P=10.002;' Set Integral constant: 'I=10.002;' Set Differential constant: 'D=10.002;' Invert Direction: 'invert;' Get Current PID Error: 'error;' Get Run/Hold Current Settings: 'current;' Set Run Current (percent): 'runCurrent=50.0;' Set Hold Current (percent): 'holdCurrent=50.0;'

Definition at line 1965 of file uStepperSLite.cpp.

◆ dropinPrintHelp()

void uStepperSLite::dropinPrintHelp ( )

This method is used to print the dropinCli menu explainer:

            Usage:
        Show this command list: 'help;'
        Get PID Parameters: 'parameters;'
        Set Proportional constant: 'P=10.002;'
        Set Integral constant: 'I=10.002;'
        Set Differential constant: 'D=10.002;'
        Invert Direction: 'invert;'
        Get Current PID Error: 'error;'
        Get Run/Hold Current Settings: 'current;'
        Set Run Current (percent): 'runCurrent=50.0;'
        Set Hold Current (percent): 'holdCurrent=50.0;' 

Definition at line 1991 of file uStepperSLite.cpp.

◆ dropinSettingsCalcChecksum()

uint8_t uStepperSLite::dropinSettingsCalcChecksum ( dropinCliSettings_t settings)
private

This method is used internally for stall detection.

Parameters
[in]settings- address of the dropin settings object, of which to calculate the checksum
Returns
checksum of dropin settings struct

Definition at line 2037 of file uStepperSLite.cpp.

◆ enableMotor()

void uStepperSLite::enableMotor ( void  )

Enables the stepper driver output stage.

        This function enables the output stage of the stepper driver.
        If no step pulses is applied to the stepper driver, either
        manually or by means of the stepper algorithm of this
        library, this will make the force the motor to brake in the
        current position.

Definition at line 1138 of file uStepperSLite.cpp.

◆ enablePid()

void uStepperSLite::enablePid ( void  )

This method enables the PID after being disabled (disablePid).

Definition at line 1411 of file uStepperSLite.cpp.

◆ getCurrentDirection()

bool uStepperSLite::getCurrentDirection ( void  )

Returns the direction the motor is currently configured to rotate.

This function checks the last configured direction of rotation and returns this.

Returns
0 - Clockwise
1 - Counter Clockwise

Definition at line 1148 of file uStepperSLite.cpp.

◆ getMotorState()

uint8_t uStepperSLite::getMotorState ( void  )

Get the current state of the motor.

        This function returns the current state of the motor, i.e. if
        the motor is rotating or not.
Returns
0 - Motor not rotating
1 - Motor rotating

Definition at line 1153 of file uStepperSLite.cpp.

◆ getPidError()

float uStepperSLite::getPidError ( void  )

This method returns the current PID error.

Returns
PID error (float)

Definition at line 1422 of file uStepperSLite.cpp.

◆ getStepsSinceReset()

int32_t uStepperSLite::getStepsSinceReset ( void  )

Get the number of steps applied since reset.

        This function returns the number of steps applied to the
        motor driver since reset. This function doesn't care if the
        step has actually been performed or not. Steps applied in the
        clockwise direction is added and steps applied in the counter
        clockwise direction is subtracted. This means that a negative
        return value indicates that the motor should have rotated the
        returned amount of steps in the counter clockwise direction,
        with respect to the initial position. Likewise a positive
        value indicate the number of steps the motor should have
        rotated in the clockwise direction, with respect to the
        initial position.
Returns
negative value - number of steps the motor should have rotated in the counter clockwise direction, with respect to the initial position.
positive value - number of steps the motor should have rotated in the clockwise direction, with respect to the initial position.

Definition at line 1163 of file uStepperSLite.cpp.

◆ hardStop()

void uStepperSLite::hardStop ( bool  holdMode = BRAKEON)

Stop the motor without deceleration.

        This function will stop any ongoing motor movement, without
        any deceleration phase. If the motor is rotation at a
        significant speed, the motor might not stop instantaneously,
        due to build up inertia. The argument "holdMode" can be used
        to define whether the motor should brake or freewheel after
        the function has been called.
Parameters
holdMode- can be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 873 of file uStepperSLite.cpp.

◆ invertDropinDir()

void uStepperSLite::invertDropinDir ( bool  invert)

This method is used to invert the drop-in direction pin interpretation.

Parameters
[in]invert- 0 = not inverted, 1 = inverted

Definition at line 1554 of file uStepperSLite.cpp.

◆ isStalled()

bool uStepperSLite::isStalled ( float  stallSensitivity = 0.992)

This method returns a bool variable indicating wether the motor is stalled or not.

Parameters
[in]stallSensitivity- Sensitivity of stall detection (0.0 - 1.0), low is more sensitive
Returns
0 = not stalled, 1 = stalled

Definition at line 1522 of file uStepperSLite.cpp.

◆ loadDropinSettings()

bool uStepperSLite::loadDropinSettings ( void  )
private

This method loads the dropin settings stored in EEPROM.

        This method loads the dropin settings stored in EEPROM. If the data stored in EEPROM
        is valid, the settings are applied. If the data is not valid, the data loaded from
        EEPROM is discarded, and the default data specifed at compile time are used isntead.
Returns
0 = stored settings NOT valid, 1 = stored settings valid

Definition at line 2010 of file uStepperSLite.cpp.

◆ moveAngle()

void uStepperSLite::moveAngle ( float  angle,
bool  holdMode = BRAKEON 
)

Moves the motor to a relative angle.

Parameters
[in]angleRelative angle from current position. A positive angle makes the motor turn clockwise, and a negative angle, counterclockwise.
[in]holdModecan be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 1241 of file uStepperSLite.cpp.

◆ moveSteps()

void uStepperSLite::moveSteps ( int32_t  steps,
bool  dir,
bool  holdMode = BRAKEON 
)

Make the motor perform a predefined number of steps.

        This function makes the motor perform a predefined number of
        steps, using the acceleration profile implemented in this
        library. The motor will accelerate at the rate set by
        setMaximumAcceleration(), and eventually reach the speed set
        by setMaximumVelocity() function. The direction of rotation
        is set by the argument "dir". The argument "holdMode",
        defines whether the motor should brake or let the motor
        freewheel after the steps has been performed.
Parameters
steps- Number of steps to be performed.
dir- Can be set to "CCW" or "CW" (without the quotes).
holdMode- can be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 682 of file uStepperSLite.cpp.

◆ moveToAngle()

void uStepperSLite::moveToAngle ( float  angle,
bool  holdMode = BRAKEON 
)

Moves the motor to an absolute angle.

Parameters
[in]angleAbsolute angle. A positive angle makes the motor turn clockwise, and a negative angle, counterclockwise.
[in]holdModecan be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 1223 of file uStepperSLite.cpp.

◆ moveToEnd()

float uStepperSLite::moveToEnd ( bool  dir,
float  stallSensitivity = 0.992 
)

Moves the motor to its physical limit, without limit switch.

         This function, makes the motor run continously, untill the
        encoder detects a stall, at which point the motor is assumed
        to be at it's limit.
Parameters
[in]dirDirection to search for limit
[in]stallSensitivitySensitivity of stall detection (0.0 - 1.0), low is more sensitive
Returns
Degrees turned from calling the function, till end was reached

Definition at line 1184 of file uStepperSLite.cpp.

◆ parseCommand()

void uStepperSLite::parseCommand ( String *  cmd)

This method is used for the dropinCli to take in user commands.

Parameters
[in]cmd- input from terminal for dropinCli

Definition at line 1559 of file uStepperSLite.cpp.

◆ runContinous()

void uStepperSLite::runContinous ( bool  dir)

Make the motor rotate continuously.

        This function makes the motor rotate continuously, using the
        acceleration profile implemented in this library. The motor
        will accelerate at the rate set by setMaximumAcceleration(),
        and eventually reach the speed set by setMaximumVelocity()
        function. The direction of rotation is set by the argument
        "dir".
Parameters
dir- Can be set to "CCW" or "CW" (without the quotes)

Definition at line 584 of file uStepperSLite.cpp.

◆ saveDropinSettings()

void uStepperSLite::saveDropinSettings ( void  )
private

This method stores the current dropin settings in EEPROM.

Definition at line 2030 of file uStepperSLite.cpp.

◆ setCurrent()

void uStepperSLite::setCurrent ( uint8_t  runCurrent,
uint8_t  holdCurrent = 25 
)

Set motor run and hold current.

        This function allows the user to change the run and hold current setting of the motor
        driver.
Parameters
[in]runCurrentDesired run current setting in percent (0% - 100%)
[in]holdCurrentDesired brake current setting in percent (0% - 100%)

Definition at line 1168 of file uStepperSLite.cpp.

◆ setDifferential()

void uStepperSLite::setDifferential ( float  D)

This method is used to change the PID differential parameter D.

Parameters
[in]D- PID differential part D

Definition at line 1549 of file uStepperSLite.cpp.

◆ setHoldCurrent()

void uStepperSLite::setHoldCurrent ( uint8_t  holdCurrent)

Set motor hold current.

        This function allows the user to change the hold current setting of the motor
        driver.
Parameters
[in]holdCurrentDesired brake current setting in percent (0% - 100%)

Definition at line 1173 of file uStepperSLite.cpp.

◆ setIntegral()

void uStepperSLite::setIntegral ( float  I)

This method is used to change the PID integral parameter I.

Parameters
[in]I- PID integral part I

Definition at line 1544 of file uStepperSLite.cpp.

◆ setMaxAcceleration()

void uStepperSLite::setMaxAcceleration ( float  accel)

Set the maximum acceleration of the stepper motor.

        This function lets the user of this library set the
        acceleration used by the stepper algorithm. The algorithm is
        a second order acceleration profile, meaning that the
        acceleration only assumes three values; -a, 0 and a, with a
        being the acceleration set by this function.
Parameters
accel- Maximum acceleration in steps/s^2

Definition at line 534 of file uStepperSLite.cpp.

◆ setMaxVelocity()

void uStepperSLite::setMaxVelocity ( float  vel)

Sets the maximum rotational velocity of the motor.

        This function sets the maximum velocity at which the motor is
        allowed to run. The rotational velocity of the motor will
        gradually be ramped up to the value set by this function, by
        the stepper acceleration profile implemented in this library.
Parameters
vel- Maximum rotational velocity of the motor in steps/s

Definition at line 551 of file uStepperSLite.cpp.

◆ setProportional()

void uStepperSLite::setProportional ( float  P)

This method is used to change the PID proportional parameter P.

Parameters
[in]P- PID proportional part P

Definition at line 1539 of file uStepperSLite.cpp.

◆ setRunCurrent()

void uStepperSLite::setRunCurrent ( uint8_t  runCurrent)

Set motor run current.

        This function allows the user to change the run current setting of the motor
        driver.
Parameters
[in]runCurrentDesired run current setting in percent (0% - 100%)

Definition at line 1178 of file uStepperSLite.cpp.

◆ setup()

void uStepperSLite::setup ( uint8_t  mode = NORMAL,
float  stepsPerRevolution = 3200.0,
float  pTerm = 0.75,
float  iTerm = 3.0,
float  dTerm = 0.0,
bool  setHome = true,
uint8_t  invert = 0,
uint8_t  runCurrent = 50,
uint8_t  holdCurrent = 30 
)

Initializes the different parts of the uStepper S-lite object.

        This function initializes the different parts of the uStepper S-lite
        object, and should be called in the setup() function of the
        arduino sketch. This function is needed as some things, like
        the timer can not be setup in the constructor, since arduino
        for some strange reason, resets a lot of the AVR registers
        just before entering the setup() function.
Parameters
[in]modeDefault is normal mode. Pass the constant "DROPIN" to configure the uStepper S-lite to act as dropin compatible to the stepstick. Pass the constant "PID", to enable PID feature for regular movement functions, such as moveSteps()
[in]stepsPerRevolutionThis parameter should be set to the steps/revolution which is 16 * steppper steps/revolution. For a 1.8deg stepper this is 16 * 200 = 3200. In Drop-in this number should be set to the microstep setting of the controller (e.g. 16).
[in]pTermThe proportional coefficent of the PID controller
[in]iTermThe integral coefficent of the PID controller
[in]dTermThe differential coefficent of the PID controller
[in]setHomeWhen set to true, the encoder position is Reset. When set to false, the encoder position is not reset.
[in]invertInverts the motor direction for dropin feature. 0 = NOT invert, 1 = invert. this has no effect for other modes than dropin
[in]runCurrentSets the current (in percent) to use while motor is running.
[in]holdCurrentSets the current (in percent) to use while motor is NOT running

Definition at line 1020 of file uStepperSLite.cpp.

◆ softStop()

void uStepperSLite::softStop ( bool  holdMode = BRAKEON)

Stop the motor with deceleration.

        This function stops any ongoing motor movement, with a
        deceleration phase. This will take longer for the motor to
        stop, however the mechanical vibrations related to the
        stopping of the motor can be significantly reduced compared
        to the hardStop() function. The argument "holdMode" can be
        used to define whether the motor should brake or freewheel
        after the function has been called.
Parameters
holdMode- can be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 903 of file uStepperSLite.cpp.

◆ stop()

void uStepperSLite::stop ( bool  brake = BRAKEON)

Stop the motor with deceleration.

        This function stops any ongoing motor movement, with a
        deceleration phase. This will take longer for the motor to
        stop, however the mechanical vibrations related to the
        stopping of the motor can be significantly reduced compared
        to the hardStop() function. The argument "holdMode" can be
        used to define whether the motor should brake or freewheel
        after the function has been called.
Parameters
brake- can be set to "HARD" for brake mode or "SOFT" for freewheel mode (without the quotes).

Definition at line 898 of file uStepperSLite.cpp.

Friends And Related Function Documentation

◆ INT0_vect

void INT0_vect ( void  )
friend

Used by dropin feature to take in step pulses.

        This interrupt routine is used by the dropin feature to keep
        track of step and direction pulses from main controller

Definition at line 78 of file uStepperSLite.cpp.

◆ TIMER1_COMPA_vect

void TIMER1_COMPA_vect ( void  )
friend

Measures angle and speed of motor.

        This interrupt routine is in charge of sampling the encoder and
        measure the current speed of the motor. 

Definition at line 139 of file uStepperSLite.cpp.

◆ TIMER3_COMPA_vect

void TIMER3_COMPA_vect ( void  )
friend

Handles accelerations.

        This interrupt routine is in charge of acceleration and deceleration.

Definition at line 125 of file uStepperSLite.cpp.

Member Data Documentation

◆ acceleration

float uStepperSLite::acceleration

This variable contains the maximum acceleration to be used. The can be set and read by the user of the library using the functions setMaxAcceleration() and getMaxAcceleration() respectively. Since this library uses a second order acceleration curve, the acceleration applied will always be either +/- this value (acceleration/deceleration)or zero (cruise).

Definition at line 497 of file uStepperSLite.h.

◆ accelToCruiseThreshold

volatile int32_t uStepperSLite::accelToCruiseThreshold

This Variable holds the number of steps to issue during the acceleration phase

Definition at line 543 of file uStepperSLite.h.

◆ angleToStep

float uStepperSLite::angleToStep

This variable converts an angle in degrees into a corresponding number of steps

Definition at line 524 of file uStepperSLite.h.

◆ brake

bool uStepperSLite::brake

This variable holds the bool telling if the motor should brake or not

Definition at line 564 of file uStepperSLite.h.

◆ cntSinceLastStep

volatile uint32_t uStepperSLite::cntSinceLastStep

Counter used by the stepgeneration algorithm to check how many interrupt ticks has passed since last step was issued

Definition at line 450 of file uStepperSLite.h.

◆ continous

bool uStepperSLite::continous

This variable tells the algorithm whether the motor should rotated continuous or only a limited number of steps. If set to 1, the motor will rotate continous.

Definition at line 465 of file uStepperSLite.h.

◆ cruiseToDecelThreshold

volatile int32_t uStepperSLite::cruiseToDecelThreshold

This Variable holds the number of steps to issue during the cruise phase

Definition at line 546 of file uStepperSLite.h.

◆ currentPidAcceleration

volatile float uStepperSLite::currentPidAcceleration

This variable holds the current PID algorithm acceleration

Definition at line 552 of file uStepperSLite.h.

◆ currentPidError

volatile float uStepperSLite::currentPidError

This variable contains the current PID errror.

Definition at line 620 of file uStepperSLite.h.

◆ currentPidSpeed

volatile float uStepperSLite::currentPidSpeed

This variable holds the current PID algorithm speed

Definition at line 549 of file uStepperSLite.h.

◆ decelToAccelThreshold

volatile int32_t uStepperSLite::decelToAccelThreshold

This Variable holds the number of steps to issue during the initial deceleration phase, which is issued if the motor velocity is higher than the desired velocity of a new move

Definition at line 540 of file uStepperSLite.h.

◆ decelToStopThreshold

volatile int32_t uStepperSLite::decelToStopThreshold

This variable holds the number of steps to issue during the deceleration phase.

Definition at line 460 of file uStepperSLite.h.

◆ direction

volatile uint8_t uStepperSLite::direction

This variable contains the direction commanded by the last issued move

Definition at line 484 of file uStepperSLite.h.

◆ driver

Tmc2208 uStepperSLite::driver

Instantiate object for the Stepper Driver

Definition at line 631 of file uStepperSLite.h.

◆ dropinSettings

dropinCliSettings_t uStepperSLite::dropinSettings
private

This variable holds the dropin settings.

See also
dropinCliSettings_t

Definition at line 1037 of file uStepperSLite.h.

◆ dTerm

float uStepperSLite::dTerm

This variable contains the differential coefficient used by the PID

Definition at line 517 of file uStepperSLite.h.

◆ encoder

uStepperEncoder uStepperSLite::encoder

Instantiate object for the encoder

Definition at line 628 of file uStepperSLite.h.

◆ invertPidDropinDirection

bool uStepperSLite::invertPidDropinDirection

This variable is used to invert the drop-in motor direction.

Definition at line 636 of file uStepperSLite.h.

◆ iTerm

float uStepperSLite::iTerm

This variable contains the integral coefficient used by the PID

Definition at line 514 of file uStepperSLite.h.

◆ mode

uint8_t uStepperSLite::mode

This variable is used to indicate which mode the uStepper S-lite is running in (Normal, Drop-in or PID)

Definition at line 477 of file uStepperSLite.h.

◆ pidDisabled

volatile bool uStepperSLite::pidDisabled

This variable holds the bool telling if the PID is enabled or not

Definition at line 561 of file uStepperSLite.h.

◆ pidError

volatile uint8_t uStepperSLite::pidError = 0

This variable contains the current PID error.

Definition at line 468 of file uStepperSLite.h.

◆ pidStepsSinceReset

volatile float uStepperSLite::pidStepsSinceReset

This variable holds the steps done in the PID since last reset

Definition at line 555 of file uStepperSLite.h.

◆ pidTargetPosition

volatile float uStepperSLite::pidTargetPosition

This variable contains the current PID target position.

Definition at line 625 of file uStepperSLite.h.

◆ pTerm

float uStepperSLite::pTerm

This variable contains the proportional coefficient used by the PID

Definition at line 505 of file uStepperSLite.h.

◆ RPMToStepDelay

volatile float uStepperSLite::RPMToStepDelay

This variable is used to convert a desired velocity in RPM to the corresponding delay between step pulses in interrupt ticks

Definition at line 536 of file uStepperSLite.h.

◆ RPMToStepsPerSecond

float uStepperSLite::RPMToStepsPerSecond

This variable contains the value for converting RPM to steps per second

Definition at line 511 of file uStepperSLite.h.

◆ stall

volatile bool uStepperSLite::stall

This variable holds information on wether the motor is stalled or not. 0 = OK, 1 = stalled

Definition at line 532 of file uStepperSLite.h.

◆ stallSensitivity

float uStepperSLite::stallSensitivity = 0.992

This variable contains the sensitivity of the stall function, and is set to a value between 0.0 and 1.0

Definition at line 520 of file uStepperSLite.h.

◆ state

volatile uint8_t uStepperSLite::state

This variable is used by the stepper algorithm to keep track of which part of the acceleration profile the motor is currently operating at.

Definition at line 473 of file uStepperSLite.h.

◆ stepCnt

volatile int32_t uStepperSLite::stepCnt

This variable contains the number of steps commanded by external controller, in case of dropin feature

Definition at line 481 of file uStepperSLite.h.

◆ stepConversion

volatile float uStepperSLite::stepConversion

This variable contains the conversion coefficient from raw encoder data to number of steps

Definition at line 501 of file uStepperSLite.h.

◆ stepDelay

volatile uint32_t uStepperSLite::stepDelay

This variable holds the delay needed between each step pulse, in interrupt ticks.

Definition at line 453 of file uStepperSLite.h.

◆ stepGeneratorDirection

volatile uint8_t uStepperSLite::stepGeneratorDirection

This variable tells the algorithm the direction of rotation for the commanded move.

Definition at line 456 of file uStepperSLite.h.

◆ stepsPerSecondToRPM

float uStepperSLite::stepsPerSecondToRPM

This variable contains the value for converting steps per second to RPM

Definition at line 508 of file uStepperSLite.h.

◆ stepsSinceReset

volatile int32_t uStepperSLite::stepsSinceReset

This variable contains an open-loop number of steps moved from the position the motor had when powered on (or reset). A negative value represents a rotation in the counter clock wise direction and a positive value corresponds to a rotation in the clock wise direction.

Definition at line 446 of file uStepperSLite.h.

◆ stepToAngle

float uStepperSLite::stepToAngle

This variable converts a number of steps into a corresponding angle in degrees

Definition at line 528 of file uStepperSLite.h.

◆ targetPosition

volatile int32_t uStepperSLite::targetPosition

This variable holds the target position

Definition at line 558 of file uStepperSLite.h.

◆ velocity

float uStepperSLite::velocity

This variable contains the maximum velocity, the motor is allowed to reach at any given point. The user of the library can set this by use of the setMaxVelocity() function

Definition at line 489 of file uStepperSLite.h.


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