166 #ifndef __AVR_ATmega328P__ 167 #error !!This library only supports the ATmega328p MCU!! 170 #include <inttypes.h> 190 #define INTFREQ 28200.0f 191 #define INTPERIOD 1000000.0/INTFREQ 193 #define INTPIDDELAYCONSTANT 0.028199994 199 #define ENCODERINTFREQ 1000.0 200 #define ENCODERSPEEDCONSTANT ENCODERINTFREQ/10.0/4096.0 202 #define ENCODERADDR 0x36 207 #define MAGNITUDE 0x1B 219 #define REPSTART 0x10 221 #define TXADDRACK 0x18 223 #define TXDATAACK 0x28 225 #define RXADDRACK 0x40 248 #define A 0.001295752996237 249 #define B 0.000237488365866 250 #define C 0.000000083423218 258 extern "C" void interrupt0(void); 294 float getFloatValue(
void);
295 uint64_t getRawValue(
void);
296 void setValue(
float val);
297 float2 & operator=(
const float &value);
298 bool operator==(
const float2 &value);
299 bool operator!=(
const float2 &value);
300 bool operator>=(
const float2 &value);
301 bool operator<=(
const float2 &value);
302 bool operator<=(
const float &value);
303 bool operator<(
const float2 &value);
304 bool operator>(
const float2 &value);
305 float2 & operator*=(
const float2 &value);
306 float2 & operator-=(
const float2 &value);
307 float2 & operator+=(
const float2 &value);
308 float2 & operator+=(
const float &value);
309 float2 & operator/=(
const float2 &value);
310 const float2 operator+(
const float2 &value);
311 const float2 operator-(
const float2 &value);
312 const float2 operator*(
const float2 &value);
313 const float2 operator/(
const float2 &value);
379 volatile uint16_t angle;
400 float getAngle(
void);
412 float getSpeed(
void);
421 uint16_t getStrength(
void);
432 uint8_t getAgc(
void);
444 uint8_t detectMagnet(
void);
462 float getAngleMoved(
void);
472 void setup(uint8_t mode);
499 uint16_t cruiseDelay;
591 volatile uint32_t speedValue[2];
622 void startTimer(
void);
633 void stopTimer(
void);
645 void enableMotor(
void);
655 void disableMotor(
void);
661 void pidDropIn(
void);
687 uStepper(
float accel,
float vel);
712 void setMaxAcceleration(
float accel);
723 float getMaxAcceleration(
void);
736 void setMaxVelocity(
float vel);
748 float getMaxVelocity(
void);
763 void runContinous(
bool dir);
783 void moveSteps(uint32_t steps,
bool dir,
bool holdMode);
799 void hardStop(
bool holdMode);
816 void softStop(
bool holdMode);
852 void setup( uint8_t mode =
NORMAL,
853 uint8_t microStepping =
SIXTEEN,
854 float faultTolerance = 10.0,
855 float faultHysteresis = 5.0,
858 float dterm = 0.006);
870 bool getCurrentDirection(
void);
882 bool getMotorState(
void);
906 int64_t getStepsSinceReset(
void);
919 void pwmD8(
float duty);
932 void pwmD3(
float duty);
943 void updateSetPoint(
float setPoint);
981 void cmd(uint8_t cmd);
1013 bool readByte(
bool ack, uint8_t *data);
1036 bool read(uint8_t slaveAddr, uint8_t regAddr, uint8_t numOfBytes, uint8_t *data);
1055 bool start(uint8_t addr,
bool RW);
1074 bool restart(uint8_t addr,
bool RW);
1086 bool writeByte(uint8_t data);
1108 bool write(uint8_t slaveAddr, uint8_t regAddr, uint8_t numOfBytes, uint8_t *data);
1130 uint8_t getStatus(
void);
Prototype of class for the temperature sensor.
void TIMER1_COMPA_vect(void) __attribute__((signal
Measures angle and speed of motor.
volatile uint16_t counter
Prototype of class for accessing all features of the uStepper in a single object. ...
void TIMER2_COMPA_vect(void) __attribute__((signal
Used to apply step pulses to the motor.
float getTemp(void)
Request a reading of current temperature.
volatile int32_t angleMoved
Prototype of class for accessing the TWI (I2C) interface of the AVR (master mode only).
Prototype of class for the AS5600 encoder.
volatile float hysteresis
void interrupt1(void)
Used by dropin feature to take in enable signal.
Function prototypes and definitions for the uStepper Servo library.
uStepperTemp(void)
Constructor.
volatile float stepConversion
uint32_t initialDecelSteps