uStepper S-lite
uStepperSLite.h
1 /********************************************************************************************
2 * File: uStepperSLite.h *
3 * Version: 1.1.0 *
4 * Date: June 14, 2020 *
5 * Author: Thomas Hørring Olsen *
6 * *
7 *********************************************************************************************
8 * (C) 2020 *
9 * *
10 * uStepper ApS *
11 * www.ustepper.com *
12 * administration@ustepper.com *
13 * *
14 * The code contained in this file is released under the following open source license: *
15 * *
16 * Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International *
17 * *
18 * The code in this file is provided without warranty of any kind - use at own risk! *
19 * neither uStepper ApS nor the author, can be held responsible for any damage *
20 * caused by the use of the code contained in this file ! *
21 * *
22 ********************************************************************************************/
127 #ifndef _USTEPPER_S_LITE_H_
128 #define _USTEPPER_S_LITE_H_
129 
130 #ifndef __AVR_ATmega328PB__
131 #error !!This library only supports the ATmega328pb MCU!!
132 #endif
133 
134 #include <EEPROM.h>
135 
140 typedef union
141 {
142  float f;
143  uint8_t bytes[4];
144 }floatBytes_t;
145 
154 typedef struct
155 {
159  uint8_t invert;
160  uint8_t holdCurrent;
161  uint8_t runCurrent;
162  uint8_t checksum;
164 
168 #define SDA SDA0
170 #define SCL SCL0
171 #define TWSTO TWSTO0
172 #define TWDR TWDR0
173 #define TWSTA TWSTA0
174 #define TWINT TWINT0
175 #define TWEA TWEA0
176 #define TWEN TWEN0
177 #define TWCR TWCR0
178 #define TWIE TWIE0
179 #define TWSR TWSR0
180 #define TWPS0 TWPS00
181 #define TWPS1 TWPS01
182 #define TWBR TWBR0
183 
185 #include <inttypes.h>
186 #include <avr/io.h>
187 #include <util/delay.h>
188 #include <Arduino.h>
189 #include <uStepperServo.h>
190 #include "TMC2208.h"
191 #include "i2cMaster.h"
192 
194 #define STEPGENERATORFREQUENCY 100000.0
195 
196 #define FULL 1
197 
198 #define HALF 2
199 
200 #define QUARTER 4
201 
202 #define EIGHT 8
203 
204 #define SIXTEEN 16
205 
206 #define NORMAL 0
207 
208 #define PWM 1
209 
210 #define DROPIN 1
211 
212 #define PID 2
213 
214 #define STOP 1
215 
216 #define ACCEL 2
217 
218 #define CRUISE 4
219 
220 #define DECEL 8
221 
222 #define INITDECEL 16
223 
224 #define CW 0
225 
226 #define CCW 1
227 
228 #define HARD 1
229 
230 #define SOFT 0
231 
232 #define DELTAANGLETORPM ENCODERINTFREQ*(60.0/4095.0)
233 
234 #define DELTAANGLETOSTEPSPERSECOND ENCODERINTFREQ*(3200.0/4095.0)
235 
236 #define BRAKEON 1
237 
238 #define BRAKEOFF 0
239 
240 #define ENCODERINTFREQ 500.0
241 
242 #define ENCODERINTSAMPLETIME 1.0/ENCODERINTFREQ
243 
244 #define ENCODERADDR 0x36
245 
246 #define ANGLE 0x0E
247 
248 #define STATUS 0x0B
249 
250 #define AGC 0x1A
251 
252 #define MAGNITUDE 0x1B
253 
254 #define PULSEFILTERKP 60.0
255 
256 #define PULSEFILTERKI 500.0*ENCODERINTSAMPLETIME
257 
258 #define SPS 0
259 
260 #define RPM 1
261 
268 extern "C" void TIMER1_COMPA_vect(void) __attribute__ ((signal,used));
269 
275 extern "C" void TIMER3_COMPA_vect(void) __attribute__ ((signal,used,naked));
276 
283 extern "C" void INT0_vect(void) __attribute__ ((signal,used));
284 
291 extern "C" void INT1_vect(void) __attribute__ ((signal,used));
292 
304 {
305 public:
308  volatile int32_t angleMoved;
309 
311  uint16_t encoderOffset;
312 
316  volatile uint16_t oldAngle;
317 
320  volatile uint16_t angle;
321 
324  volatile float curSpeed;
330  uStepperEncoder(void);
331 
344  float getAngle(void);
345 
357  float getSpeed(bool unit = SPS);
358 
366  uint16_t getStrength(void);
367 
377  uint8_t getAgc(void);
378 
389  uint8_t detectMagnet(void);
390 
407  float getAngleMoved(void);
408 
414  void setup(void);
415 
422  void setHome(void);
423 
424 private:
425 
426  friend void TIMER1_COMPA_vect(void) __attribute__ ((signal,used));
427 };
428 
438 {
439 public:
440 
446  volatile int32_t stepsSinceReset; //offset 0
450  volatile uint32_t cntSinceLastStep; //offset 4
453  volatile uint32_t stepDelay; //offset 8
456  volatile uint8_t stepGeneratorDirection;//offset 12
460  volatile int32_t decelToStopThreshold; //offset 13
461 
465  bool continous; //offset 17
466 
468  volatile uint8_t pidError = 0; //offset 18
469 
473  volatile uint8_t state;
474 
477  uint8_t mode;
478 
481  volatile int32_t stepCnt;
482 
484  volatile uint8_t direction;
485 
489  float velocity;
490 
497  float acceleration;
498 
501  volatile float stepConversion;
502 
505  float pTerm;
506 
509 
512 
514  float iTerm;
515 
517  float dTerm;
518 
520  float stallSensitivity = 0.992;
521 
524  float angleToStep;
525 
528  float stepToAngle;
529 
532  volatile bool stall;
533 
536  volatile float RPMToStepDelay;
537 
540  volatile int32_t decelToAccelThreshold;
541 
543  volatile int32_t accelToCruiseThreshold;
544 
546  volatile int32_t cruiseToDecelThreshold;
547 
549  volatile float currentPidSpeed;
550 
552  volatile float currentPidAcceleration;
553 
555  volatile float pidStepsSinceReset;
556 
558  volatile int32_t targetPosition;
559 
561  volatile bool pidDisabled;
562 
564  bool brake;
565 
566  friend void TIMER1_COMPA_vect(void) __attribute__ ((signal,used));
567  friend void TIMER3_COMPA_vect(void) __attribute__ ((signal,used,naked));
568  friend void INT0_vect(void) __attribute__ ((signal,used));
569  friend void uStepperEncoder::setHome(void);
570 
571 
581  void enableMotor(void);
582 
583 
591  void disableMotor(void);
592 
597  void pid(float error);
598 
603  void pidDropin(float error);
604 
609  void checkConnectorOrientation(uint8_t mode);
610 
615  float getPidError(void);
616 
620  volatile float currentPidError;
621 
625  volatile float pidTargetPosition;
626 
629 
632 
637 
652  uStepperSLite(float accel = 1000.0, float vel = 1000.0);
653 
654 
666  void setMaxAcceleration(float accel);
667 
678  void setMaxVelocity(float vel);
679 
692  void runContinous(bool dir);
693 
694 
712  void moveSteps(int32_t steps, bool dir, bool holdMode = BRAKEON);
713 
714 
728  void hardStop(bool holdMode = BRAKEON);
729 
730 
745  void softStop(bool holdMode = BRAKEON);
746 
747 
762  void stop(bool brake = BRAKEON);
763 
800  void setup( uint8_t mode = NORMAL,
801  float stepsPerRevolution = 3200.0,
802  float pTerm = 0.75,
803  float iTerm = 3.0,
804  float dTerm = 0.0,
805  bool setHome = true,
806  uint8_t invert = 0,
807  uint8_t runCurrent = 50,
808  uint8_t holdCurrent = 30);
809 
820  bool getCurrentDirection(void);
821 
822 
832  uint8_t getMotorState(void);
833 
834 
856  int32_t getStepsSinceReset(void);
857 
868  void setCurrent(uint8_t runCurrent, uint8_t holdCurrent = 25);
869 
878  void setHoldCurrent(uint8_t holdCurrent);
879 
888  void setRunCurrent(uint8_t runCurrent);
889 
903  float moveToEnd(bool dir, float stallSensitivity = 0.992);
904 
915  void moveToAngle(float angle, bool holdMode = BRAKEON);
916 
926  void moveAngle(float angle, bool holdMode = BRAKEON);
927 
936  bool isStalled(float stallSensitivity = 0.992);
937 
942  void disablePid(void);
943 
948  void enablePid(void);
949 
956  void setProportional(float P);
957 
964  void setIntegral(float I);
965 
972  void setDifferential(float D);
973 
980  void invertDropinDir(bool invert);
981 
997  void dropinCli();
998 
1005  void parseCommand(String *cmd);
1006 
1023  void dropinPrintHelp();
1024 
1025 private:
1026 
1033  bool detectStall(void);
1034 
1038 
1049  bool loadDropinSettings(void);
1050 
1055  void saveDropinSettings(void);
1056 
1066 };
1067 
1069 extern i2cMaster I2C;
1070 
1071 #endif
uStepperSLite::currentPidAcceleration
volatile float currentPidAcceleration
Definition: uStepperSLite.h:552
uStepperSLite::velocity
float velocity
Definition: uStepperSLite.h:489
dropinCliSettings_t::P
floatBytes_t P
Definition: uStepperSLite.h:156
uStepperSLite::stepsPerSecondToRPM
float stepsPerSecondToRPM
Definition: uStepperSLite.h:508
uStepperEncoder::angle
volatile uint16_t angle
Definition: uStepperSLite.h:320
uStepperSLite
Prototype of class for accessing all features of the uStepper S-lite in a single object.
Definition: uStepperSLite.h:438
uStepperSLite::encoder
uStepperEncoder encoder
Definition: uStepperSLite.h:628
uStepperSLite::acceleration
float acceleration
Definition: uStepperSLite.h:497
uStepperSLite::cruiseToDecelThreshold
volatile int32_t cruiseToDecelThreshold
Definition: uStepperSLite.h:546
uStepperSLite::RPMToStepsPerSecond
float RPMToStepsPerSecond
Definition: uStepperSLite.h:511
uStepperSLite::isStalled
bool isStalled(float stallSensitivity=0.992)
This method returns a bool variable indicating wether the motor is stalled or not.
Definition: uStepperSLite.cpp:1522
uStepperSLite::runContinous
void runContinous(bool dir)
Make the motor rotate continuously.
Definition: uStepperSLite.cpp:584
uStepperSLite::invertDropinDir
void invertDropinDir(bool invert)
This method is used to invert the drop-in direction pin interpretation.
Definition: uStepperSLite.cpp:1554
uStepperSLite::accelToCruiseThreshold
volatile int32_t accelToCruiseThreshold
Definition: uStepperSLite.h:543
uStepperEncoder::angleMoved
volatile int32_t angleMoved
Definition: uStepperSLite.h:308
dropinCliSettings_t
Struct to store dropin settings.
Definition: uStepperSLite.h:155
uStepperEncoder::oldAngle
volatile uint16_t oldAngle
Definition: uStepperSLite.h:316
uStepperSLite::invertPidDropinDirection
bool invertPidDropinDirection
Definition: uStepperSLite.h:636
uStepperSLite::stepConversion
volatile float stepConversion
Definition: uStepperSLite.h:501
uStepperSLite::dropinPrintHelp
void dropinPrintHelp()
This method is used to print the dropinCli menu explainer:
Definition: uStepperSLite.cpp:1991
uStepperSLite::enableMotor
void enableMotor(void)
Enables the stepper driver output stage.
Definition: uStepperSLite.cpp:1138
uStepperSLite::stallSensitivity
float stallSensitivity
Definition: uStepperSLite.h:520
uStepperSLite::pTerm
float pTerm
Definition: uStepperSLite.h:505
dropinCliSettings_t::D
floatBytes_t D
Definition: uStepperSLite.h:158
uStepperSLite::targetPosition
volatile int32_t targetPosition
Definition: uStepperSLite.h:558
floatBytes_t
Union to easily split a float into its binary representation.
Definition: uStepperSLite.h:141
uStepperSLite::pidError
volatile uint8_t pidError
Definition: uStepperSLite.h:468
TMC2208.h
Function prototypes and definitions for the uStepper TMC2208 driver library.
uStepperSLite::stepDelay
volatile uint32_t stepDelay
Definition: uStepperSLite.h:453
uStepperSLite::pidStepsSinceReset
volatile float pidStepsSinceReset
Definition: uStepperSLite.h:555
uStepperSLite::stepGeneratorDirection
volatile uint8_t stepGeneratorDirection
Definition: uStepperSLite.h:456
uStepperSLite::continous
bool continous
Definition: uStepperSLite.h:465
uStepperEncoder::getAngle
float getAngle(void)
Measure the current shaft angle.
Definition: uStepperSLite.cpp:469
uStepperSLite::dropinSettingsCalcChecksum
uint8_t dropinSettingsCalcChecksum(dropinCliSettings_t *settings)
This method is used internally for stall detection.
Definition: uStepperSLite.cpp:2037
uStepperSLite::RPMToStepDelay
volatile float RPMToStepDelay
Definition: uStepperSLite.h:536
uStepperSLite::setDifferential
void setDifferential(float D)
This method is used to change the PID differential parameter D.
Definition: uStepperSLite.cpp:1549
uStepperSLite::driver
Tmc2208 driver
Definition: uStepperSLite.h:631
uStepperSLite::brake
bool brake
Definition: uStepperSLite.h:564
dropinCliSettings_t::checksum
uint8_t checksum
Definition: uStepperSLite.h:162
uStepperSLite::enablePid
void enablePid(void)
This method enables the PID after being disabled (disablePid).
Definition: uStepperSLite.cpp:1411
uStepperSLite::setMaxAcceleration
void setMaxAcceleration(float accel)
Set the maximum acceleration of the stepper motor.
Definition: uStepperSLite.cpp:534
uStepperSLite::moveAngle
void moveAngle(float angle, bool holdMode=BRAKEON)
Moves the motor to a relative angle.
Definition: uStepperSLite.cpp:1241
uStepperSLite::currentPidSpeed
volatile float currentPidSpeed
Definition: uStepperSLite.h:549
uStepperSLite::getPidError
float getPidError(void)
This method returns the current PID error.
Definition: uStepperSLite.cpp:1422
uStepperEncoder::getAngleMoved
float getAngleMoved(void)
Measure the angle moved from reference position.
Definition: uStepperSLite.cpp:424
uStepperEncoder::getSpeed
float getSpeed(bool unit=SPS)
Measure the current speed of the motor.
Definition: uStepperSLite.cpp:429
floatBytes_t::f
float f
Definition: uStepperSLite.h:142
uStepperSLite::decelToAccelThreshold
volatile int32_t decelToAccelThreshold
Definition: uStepperSLite.h:540
dropinCliSettings_t::invert
uint8_t invert
Definition: uStepperSLite.h:159
uStepperServo.h
Function prototypes and definitions for the uStepper Servo library.
uStepperSLite::detectStall
bool detectStall(void)
This method is used internally for stall detection.
Definition: uStepperSLite.cpp:1485
uStepperSLite::stop
void stop(bool brake=BRAKEON)
Stop the motor with deceleration.
Definition: uStepperSLite.cpp:898
uStepperSLite::getMotorState
uint8_t getMotorState(void)
Get the current state of the motor.
Definition: uStepperSLite.cpp:1153
uStepperSLite::getCurrentDirection
bool getCurrentDirection(void)
Returns the direction the motor is currently configured to rotate.
Definition: uStepperSLite.cpp:1148
uStepperSLite::state
volatile uint8_t state
Definition: uStepperSLite.h:473
uStepperSLite::hardStop
void hardStop(bool holdMode=BRAKEON)
Stop the motor without deceleration.
Definition: uStepperSLite.cpp:873
dropinCliSettings_t::I
floatBytes_t I
Definition: uStepperSLite.h:157
uStepperSLite::angleToStep
float angleToStep
Definition: uStepperSLite.h:524
uStepperSLite::TIMER1_COMPA_vect
friend void TIMER1_COMPA_vect(void) __attribute__((signal
Measures angle and speed of motor.
Definition: uStepperSLite.cpp:139
uStepperEncoder::curSpeed
volatile float curSpeed
Definition: uStepperSLite.h:324
uStepperSLite::moveToEnd
float moveToEnd(bool dir, float stallSensitivity=0.992)
Moves the motor to its physical limit, without limit switch.
Definition: uStepperSLite.cpp:1184
uStepperEncoder::detectMagnet
uint8_t detectMagnet(void)
Detect if magnet is present and within range.
Definition: uStepperSLite.cpp:494
uStepperSLite::mode
uint8_t mode
Definition: uStepperSLite.h:477
dropinCliSettings_t::holdCurrent
uint8_t holdCurrent
Definition: uStepperSLite.h:160
uStepperEncoder::uStepperEncoder
uStepperEncoder(void)
Constructor.
Definition: uStepperSLite.cpp:419
uStepperSLite::iTerm
float iTerm
Definition: uStepperSLite.h:514
uStepperSLite::cntSinceLastStep
volatile uint32_t cntSinceLastStep
Definition: uStepperSLite.h:450
Tmc2208
Prototype of class for accessing all features of the TMC2208 in a single object.
Definition: TMC2208.h:278
uStepperSLite::setIntegral
void setIntegral(float I)
This method is used to change the PID integral parameter I.
Definition: uStepperSLite.cpp:1544
uStepperSLite::checkConnectorOrientation
void checkConnectorOrientation(uint8_t mode)
This method handles the connector orientation check in order to automatically compensate the PID for ...
Definition: uStepperSLite.cpp:949
uStepperSLite::direction
volatile uint8_t direction
Definition: uStepperSLite.h:484
dropinCliSettings_t::runCurrent
uint8_t runCurrent
Definition: uStepperSLite.h:161
uStepperSLite::stepCnt
volatile int32_t stepCnt
Definition: uStepperSLite.h:481
uStepperSLite::INT0_vect
friend void INT0_vect(void) __attribute__((signal
Used by dropin feature to take in step pulses.
Definition: uStepperSLite.cpp:78
uStepperEncoder
Prototype of class for the AS5600 encoder.
Definition: uStepperSLite.h:304
uStepperSLite::currentPidError
volatile float currentPidError
Definition: uStepperSLite.h:620
uStepperSLite::setProportional
void setProportional(float P)
This method is used to change the PID proportional parameter P.
Definition: uStepperSLite.cpp:1539
uStepperEncoder::setup
void setup(void)
Setup the encoder.
Definition: uStepperSLite.cpp:441
i2cMaster
Prototype of class for accessing the TWI (I2C) interface of the AVR (master mode only).
Definition: i2cMaster.h:94
uStepperSLite::loadDropinSettings
bool loadDropinSettings(void)
This method loads the dropin settings stored in EEPROM.
Definition: uStepperSLite.cpp:2010
uStepperSLite::getStepsSinceReset
int32_t getStepsSinceReset(void)
Get the number of steps applied since reset.
Definition: uStepperSLite.cpp:1163
uStepperSLite::pidDropin
void pidDropin(float error)
This method handles the actual PID Drop-in controller calculations, if enabled.
Definition: uStepperSLite.cpp:1427
uStepperSLite::setHoldCurrent
void setHoldCurrent(uint8_t holdCurrent)
Set motor hold current.
Definition: uStepperSLite.cpp:1173
uStepperEncoder::setHome
void setHome(void)
Define new reference(home) position.
Definition: uStepperSLite.cpp:451
uStepperSLite::pid
void pid(float error)
This method handles the actual PID controller calculations, if enabled.
Definition: uStepperSLite.cpp:1257
uStepperSLite::moveSteps
void moveSteps(int32_t steps, bool dir, bool holdMode=BRAKEON)
Make the motor perform a predefined number of steps.
Definition: uStepperSLite.cpp:682
uStepperSLite::decelToStopThreshold
volatile int32_t decelToStopThreshold
Definition: uStepperSLite.h:460
uStepperSLite::setRunCurrent
void setRunCurrent(uint8_t runCurrent)
Set motor run current.
Definition: uStepperSLite.cpp:1178
uStepperSLite::TIMER3_COMPA_vect
friend void TIMER3_COMPA_vect(void) __attribute__((signal
Handles accelerations.
Definition: uStepperSLite.cpp:125
uStepperSLite::dropinSettings
dropinCliSettings_t dropinSettings
Definition: uStepperSLite.h:1037
uStepperSLite::dTerm
float dTerm
Definition: uStepperSLite.h:517
uStepperEncoder::getAgc
uint8_t getAgc(void)
Read the current AGC value of the encoder chip.
Definition: uStepperSLite.cpp:485
uStepperEncoder::getStrength
uint16_t getStrength(void)
Measure the strength of the magnet.
Definition: uStepperSLite.cpp:474
i2cMaster.h
This file contains the implementation of the class methods, used to communicate over the I2C bus.
uStepperSLite::stepsSinceReset
volatile int32_t stepsSinceReset
Definition: uStepperSLite.h:446
uStepperEncoder::encoderOffset
uint16_t encoderOffset
Definition: uStepperSLite.h:311
uStepperSLite::setMaxVelocity
void setMaxVelocity(float vel)
Sets the maximum rotational velocity of the motor.
Definition: uStepperSLite.cpp:551
uStepperSLite::setup
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.
Definition: uStepperSLite.cpp:1020
uStepperSLite::uStepperSLite
uStepperSLite(float accel=1000.0, float vel=1000.0)
Constructor of uStepper S-lite class.
Definition: uStepperSLite.cpp:520
uStepperSLite::parseCommand
void parseCommand(String *cmd)
This method is used for the dropinCli to take in user commands.
Definition: uStepperSLite.cpp:1559
uStepperSLite::softStop
void softStop(bool holdMode=BRAKEON)
Stop the motor with deceleration.
Definition: uStepperSLite.cpp:903
uStepperSLite::stall
volatile bool stall
Definition: uStepperSLite.h:532
uStepperSLite::disablePid
void disablePid(void)
This method disables the PID until calling enablePid.
Definition: uStepperSLite.cpp:1406
uStepperSLite::moveToAngle
void moveToAngle(float angle, bool holdMode=BRAKEON)
Moves the motor to an absolute angle.
Definition: uStepperSLite.cpp:1223
uStepperSLite::saveDropinSettings
void saveDropinSettings(void)
This method stores the current dropin settings in EEPROM.
Definition: uStepperSLite.cpp:2030
uStepperSLite::dropinCli
void dropinCli()
This method is used to tune Drop-in parameters. After tuning uStepper S-lite the parameters are saved...
Definition: uStepperSLite.cpp:1965
uStepperEncoder::TIMER1_COMPA_vect
friend void TIMER1_COMPA_vect(void) __attribute__((signal
Measures angle and speed of motor.
Definition: uStepperSLite.cpp:139
uStepperSLite::stepToAngle
float stepToAngle
Definition: uStepperSLite.h:528
uStepperSLite::setCurrent
void setCurrent(uint8_t runCurrent, uint8_t holdCurrent=25)
Set motor run and hold current.
Definition: uStepperSLite.cpp:1168
uStepperSLite::disableMotor
void disableMotor(void)
Disables the stepper driver output stage.
Definition: uStepperSLite.cpp:1143
uStepperSLite::pidTargetPosition
volatile float pidTargetPosition
Definition: uStepperSLite.h:625
I2C
i2cMaster I2C(1)
uStepperSLite::pidDisabled
volatile bool pidDisabled
Definition: uStepperSLite.h:561