Compare commits

..

8 commits

10 changed files with 554 additions and 131 deletions

1
.gitignore vendored Normal file
View file

@ -0,0 +1 @@
.clangd

View file

@ -16,6 +16,35 @@ Compile through Arduino IDE or equivalent.
> Add [kissStepper](https://github.com/risitt/kissStepper) to your project > Add [kissStepper](https://github.com/risitt/kissStepper) to your project
> librairies. > librairies.
## Development
Required dependeinces if not using
[Arduino IDE](https://www.arduino.cc/en/software/):
- [Arduino CLI](https://docs.arduino.cc/arduino-cli/):
- Install:
```sh
# linux
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | sh
# macos
brew update
brew install arduino-cli
# windows
winget install --id=ArduinoSA.CLI -e
```
- Configure:
```sh
arduino-cli config init
arduino-cli core update-index
arduino-cli core install arduino:avr
```
If you use `clangd` as lsp run `python ./generate_clangd.py` to load arduino
config and libraries.
## Contributing ## Contributing
Before `git commit`, run `git clang-format` to format stagged files. Before `git commit`, run `git clang-format --staged` to format stagged files and
then `git add` to commit formatting.

View file

@ -26,4 +26,13 @@
#define PIN_LASER (PIN_PD2) #define PIN_LASER (PIN_PD2)
// Magic numbers
#define STEP_RATIO_X (7020)
#define STEP_RATIO_Y (7020)
// Offset [cm]
#define OFFSET_X (0)
#define OFFSET_Y (21)
#define OFFSET_Z (166)
#endif #endif

48
generate_clangd.py Normal file
View file

@ -0,0 +1,48 @@
#!/usr/bin/env python3
import os
import platform
import yaml
def write_clangd_file(flags):
clangd_config = {
"CompileFlags": {
"Add": flags
}
}
with open(".clangd", "w") as f:
yaml.dump(clangd_config, f, default_flow_style=False)
def main():
arduino_base_path = os.path.expanduser("~/AppData/Local") if platform.system() == "Windows" else os.path.expanduser('~')
flags = [
"-x", "c++",
"-std=gnu++11",
"-fpermissive",
"-fno-exceptions",
"-ffunction-sections",
"-fdata-sections",
"-fno-threadsafe-statics",
"-Wno-error=narrowing",
"-flto",
"-E",
"-CC",
"-D__AVR__",
"-D__AVR_ATmega328P__",
"-DF_CPU=16000000L",
"-DARDUINO=10607",
"-DARDUINO_AVR_UNO",
"-DARDUINO_ARCH_AVR",
"-I./include",
f"-I{arduino_base_path}/Arduino15/packages/arduino/hardware/avr/1.8.6/cores/arduino",
f"-I{arduino_base_path}/Arduino15/packages/arduino/hardware/avr/1.8.6/variants/standard",
f"-I{arduino_base_path}/Arduino15/packages/arduino/tools/avr-gcc/7.3.0-atmel3.6.1-arduino7/avr/include",
f"-I{arduino_base_path}/Arduino15/packages/arduino/tools/avr-gcc/7.3.0-atmel3.6.1-arduino7/lib/gcc/avr/7.3.0/include",
]
write_clangd_file(flags)
if __name__ == "__main__":
main()

312
include/kissStepper.h Normal file
View file

@ -0,0 +1,312 @@
/*
kissStepper - a lightweight library for the Easy Driver, Big Easy Driver, Allegro stepper motor drivers and others that use a Step/Dir interface
Written by Rylee Isitt. September 21, 2015
License: GNU Lesser General Public License (LGPL) V2.1
Despite the existence of several excellent libraries for driving stepper motors, I created this one to fulfill the following needs:
- Simplicity
- Handling of enable, step, and dir pins
- Based around an external loop
- Approximately linear acceleration using a fast algorithm
- High step frequency (or reasonably so, given the overhead involved)
- Use AVR/ARM libraries and port access to increase performance while keeping the API Arduino-friendly
- Teensy (Teensyduino) compatibility
Acceleration approximation math is based on Aryeh Eiderman's "Real Time Stepper Motor Linear Ramping Just by Addition and Multiplication", available at http://hwml.com/LeibRamp.pdf
*/
#ifndef kissStepper_H
#define kissStepper_H
#include <Arduino.h>
// determine port register size
#if defined(__AVR__) || defined(__avr__)
typedef uint8_t regint;
#elif defined(TEENSYDUINO)
#if defined(__AVR_ATmega32U4__) || defined(__AVR_AT90USB1286__) || defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
typedef uint8_t regint;
#else
typedef uint32_t regint;
#endif
#else
typedef uint32_t regint;
#endif
// the order of enums allows some simple tests:
// if > STATE_STARTING, motor is in motion
// if > STATE_RUN, motor is accelerating or decelerating
enum kissState_t: uint8_t
{
STATE_STOPPED = 0,
STATE_STARTING = 1,
STATE_RUN = 2,
STATE_ACCEL = 3,
STATE_DECEL = 4
};
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// kissStepper without acceleration
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
class kissStepperNoAccel
{
public:
kissStepperNoAccel(uint8_t PIN_DIR, uint8_t PIN_STEP, uint8_t PIN_ENABLE = 255, bool invertDir = false);
kissStepperNoAccel(uint8_t PIN_DIR, uint8_t PIN_STEP, bool invertDir = false);
~kissStepperNoAccel(void) {};
bool prepareMove(int32_t target);
kissState_t move(void);
void stop(void);
uint16_t getCurSpeed(void)
{
if (m_kissState == STATE_RUN)
return m_maxSpeed;
else
return 0;
}
kissState_t getState(void)
{
return m_kissState;
}
int32_t getPos(void)
{
if (m_forwards)
return m_pos + m_distMoved;
else
return m_pos - m_distMoved;
}
bool isEnabled(void)
{
return m_enabled;
}
bool isMovingForwards(void)
{
return m_forwards;
}
void begin(void);
void enable(void);
void disable(void);
void setPos(int32_t pos)
{
if (m_kissState == STATE_STOPPED)
m_pos = constrain(pos, m_reverseLimit, m_forwardLimit);
}
int32_t getTarget(void)
{
if (m_kissState == STATE_STOPPED)
return m_pos;
else if (m_forwards)
return m_pos + m_distTotal;
else
return m_pos - m_distTotal;
}
uint32_t getDistRemaining(void)
{
return m_distTotal - m_distMoved;
}
void setForwardLimit(int32_t forwardLimit)
{
m_forwardLimit = forwardLimit;
}
void setReverseLimit(int32_t reverseLimit)
{
m_reverseLimit = reverseLimit;
}
int32_t getForwardLimit(void)
{
return m_forwardLimit;
}
int32_t getReverseLimit(void)
{
return m_reverseLimit;
}
void setMaxSpeed(uint16_t maxSpeed)
{
if (m_kissState == STATE_STOPPED) m_maxSpeed = maxSpeed;
}
uint16_t getMaxSpeed(void)
{
return m_maxSpeed;
}
protected:
void setDir(bool forwards)
{
m_forwards = forwards;
digitalWrite(PIN_DIR, forwards == m_invertDir);
}
void updatePos(void)
{
if (m_forwards)
m_pos += m_distMoved;
else
m_pos -= m_distMoved;
m_distMoved = 0;
}
static const uint32_t ONE_SECOND = 1000000UL;
static const uint8_t PULSE_WIDTH_US = 2; // desired width of step pulse (high) in us
static const int32_t DEFAULT_FORWARD_LIMIT = 2147483647L;
static const int32_t DEFAULT_REVERSE_LIMIT = -2147483648L;
static const uint16_t DEFAULT_SPEED = 1600;
static const uint16_t INTERVAL_CORRECTION_INCREMENT = 255;
int32_t m_forwardLimit;
int32_t m_reverseLimit;
uint16_t m_maxSpeed;
const uint8_t PIN_DIR;
const uint8_t PIN_STEP;
const uint8_t PIN_ENABLE;
kissState_t m_kissState;
uint32_t m_distTotal, m_distMoved;
bool m_forwards;
int32_t m_pos;
const regint m_stepBit;
regint volatile * const m_stepOut;
uint32_t m_stepIntervalWhole;
uint16_t m_stepIntervalRemainder;
uint16_t m_stepIntervalCorrectionCounter;
bool m_enabled;
uint32_t m_lastStepTime;
bool m_invertDir;
bool m_init;
};
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// kissStepper WITH acceleration
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
// ----------------------------------------------------------------------------------------------------
class kissStepper: public kissStepperNoAccel
{
public:
kissStepper(uint8_t PIN_DIR, uint8_t PIN_STEP, uint8_t PIN_ENABLE = 255, bool invertDir = false);
kissStepper(uint8_t PIN_DIR, uint8_t PIN_STEP, bool invertDir = false);
~kissStepper(void) {};
bool prepareMove(int32_t target);
kissState_t move(void);
void stop(void);
uint16_t getCurSpeed(void)
{
if (m_kissState == STATE_RUN)
return m_maxSpeed;
else if (m_kissState > STATE_STARTING)
{
uint32_t curSpeed = ONE_SECOND / m_stepIntervalWhole;
if (curSpeed > m_maxSpeed) curSpeed = m_maxSpeed;
return curSpeed;
}
else
return 0;
}
void decelerate(void);
uint32_t calcMaxAccelDist(void)
{
if (m_accel > 0)
return ((uint32_t)m_maxSpeed * m_maxSpeed) / (2UL * m_accel);
else
return 0;
}
uint32_t getAccelDist(void)
{
return m_distAccel;
}
uint32_t getRunDist(void)
{
return m_distRun - m_distAccel;
}
uint32_t getDecelDist(void)
{
return m_distTotal - m_distRun;
}
void setAccel(uint16_t accel)
{
if (m_kissState == STATE_STOPPED) m_accel = accel;
}
uint16_t getAccel(void)
{
return m_accel;
}
uint16_t getTopSpeed(void);
protected:
static const uint16_t DEFAULT_ACCEL = 1600;
uint32_t m_distAccel, m_distRun;
uint32_t m_topSpeedStepInterval;
uint32_t m_minSpeedStepInterval;
float m_stepInterval;
float m_constMult;
uint16_t m_accel;
private:
/*
----------------------------------------------------------------------------------------------------
To strike a balance between accuracy and performance, this library uses a set of approximations
for calculating stepInterval when accelerating/decelerating. Although this does use floating point
math, it is a drastic improvement over exact calculations and better than anything else I've tried.
There is probably room for further improvement (fixed point or integer math?) but this is good enough.
exact:
stepInterval = ONE_SECOND / newSpeed
curSpeed = ONE_SECOND / stepInterval
newSpeed = sqrt(curSpeed^2 + 2a)
stepInterval = ONE_SECOND / sqrt(curSpeed^2 + 2a)
approximations:
constMult = accel / (ONE_SECOND * ONE_SECOND)
q = constMult*stepInterval*stepInterval
set q to negative if accelerating
good precision, fast: stepInterval *= 1.0 + q
better precision, slower: stepInterval *= 1.0 + q + q*q
best precision, slowest: stepInterval *= 1.0 + q + 1.5*q*q
----------------------------------------------------------------------------------------------------
*/
float accelStep(float stepInterval, float constMult)
{
float newStepInterval;
float q = -constMult*stepInterval*stepInterval;
newStepInterval = stepInterval * (1.0 + q);
// newStepInterval = stepInterval * (1.0 + q + q*q); // better accuracy
// newStepInterval = stepInterval * (1.0 + q + 1.5*q*q); // best accuracy
if (newStepInterval < m_topSpeedStepInterval) newStepInterval = m_topSpeedStepInterval;
return newStepInterval;
}
float decelStep(float stepInterval, float constMult)
{
float newStepInterval;
float q = constMult*stepInterval*stepInterval;
newStepInterval = stepInterval * (1.0 + q);
// newStepInterval = stepInterval * (1.0 + q + q*q); // better accuracy
// newStepInterval = stepInterval * (1.0 + q + 1.5*q*q); // best accuracy
if (newStepInterval > m_minSpeedStepInterval) newStepInterval = m_minSpeedStepInterval;
return newStepInterval;
}
};
#endif

View file

@ -1,33 +1,26 @@
#include "math.h" #include "math.h"
#include "turret.h"
double degToRad(double deg) { return deg * M_PI / 180.0; } double degToRad(double deg) { return deg * M_PI / 180.0; }
double radToDeg(double rad) { return rad * 180.0 / M_PI; } double radToDeg(double rad) { return rad * 180.0 / M_PI; }
void angleToStep(long &stepX, long &stepY, double angleX, double angleY) { void angleToStep(Turret::StepRatio stepRatio, vec2<double> angle,
// TODO remove magic numbers vec2<long> &step) {
double stepRatioX = 6000 / M_PI; step.x = angle.x * stepRatio.x;
double stepRatioY = 6500 / M_PI; step.y = angle.y * stepRatio.y;
stepX = angleX * stepRatioX;
stepY = angleY * stepRatioY;
} }
void cartesianToPolar(long &stepX, long &stepY, double zeroX, double zeroY, void cartesianToPolar(Turret::StepRatio stepRatio, Turret::Offset offset,
double x, double y, double z) { vec2<long> zero, vec3<double> position,
// TODO remove magic numbers vec2<long> &step) {
double distance = 166.0; // turret to screen
double offsetY = 21.0; // laser to stand
double offsetX = 0.0; // unused
// x = -x; // natural axis direction // x = -x; // natural axis direction
y = -y; // natural axis direction position.y = -position.y; // natural axis direction
double dX = x + offsetX; double dX = position.x + offset.x;
double dY = y + offsetY; double dY = position.y + offset.y;
double dZ = z + distance; double dZ = position.z + offset.z;
double angleY = atan2(dZ, dY) - M_PI / 2; vec2<double> angle(atan2(dZ, dY) - M_PI / 2, atan2(dZ, dX) - M_PI / 2);
double angleX = atan2(dZ, dX) - M_PI / 2;
angleToStep(stepX, stepY, angleX, angleY); angleToStep(stepRatio, angle, step);
} }

View file

@ -1,5 +1,8 @@
#include "turret.h"
double degToRad(double deg); double degToRad(double deg);
double radToDeg(double rad); double radToDeg(double rad);
void angleToStep(long &stepX, long &stepY, double angleX, double angleY); void angleToStep(Turret::StepRatio stepRatio, vec2<double> angle,
void cartesianToPolar(long &stepX, long &stepY, double zeroX, double zeroY, vec2<long> &step);
double x, double y, double z); void cartesianToPolar(Turret::StepRatio stepRatio, Turret::Offset offset,
vec2<long> zero, vec3<double> position, vec2<long> &step);

View file

@ -1,42 +1,38 @@
#include "turret.h" #include "turret.h"
#include "config.h"
#include "maths.h" #include "maths.h"
#include <kissStepper.h> #include <kissStepper.h>
Turret::Turret(int pin_x_direction, int pin_x_pulse, int pin_x_enable, Turret::Turret(StepRatio step_ratio, Offset offset, PinMap pin_map_x,
int pin_x_home, int pin_y_direction, int pin_y_pulse, PinMap pin_map_y)
int pin_y_enable, int pin_y_home, int pin_laser) : _stepper(kissStepper(static_cast<uint8_t>(pin_map_x.direction),
: _stepperX(pin_x_direction, pin_x_pulse, pin_x_enable), static_cast<uint8_t>(pin_map_x.pulse),
_stepperY(pin_y_direction, pin_y_pulse, pin_y_enable) { static_cast<uint8_t>(pin_map_x.enable)),
kissStepper(static_cast<uint8_t>(pin_map_y.direction),
static_cast<uint8_t>(pin_map_y.pulse),
static_cast<uint8_t>(pin_map_y.enable))) {
_pin_x_direction = pin_x_direction; _pin.x = pin_map_x;
_pin_x_pulse = pin_x_pulse; _pin.y = pin_map_y;
_pin_x_enable = pin_x_enable; _step_ratio = step_ratio;
_offset = offset;
_pin_y_direction = pin_y_direction;
_pin_y_pulse = pin_y_pulse;
_pin_y_enable = pin_y_enable;
_pin_x_home = pin_x_home;
_pin_y_home = pin_y_home;
_pin_laser = pin_laser;
} }
Turret &Turret::init() { Turret &Turret::init() {
pinMode(_pin_laser, OUTPUT); pinMode(_pin.x.laser, OUTPUT);
pinMode(_pin.y.laser, OUTPUT);
pinMode(_pin_x_direction, OUTPUT); pinMode(_pin.x.direction, OUTPUT);
pinMode(_pin_x_pulse, OUTPUT); pinMode(_pin.x.pulse, OUTPUT);
pinMode(_pin_x_enable, OUTPUT); pinMode(_pin.x.enable, OUTPUT);
pinMode(_pin_x_home, INPUT_PULLUP); pinMode(_pin.x.home, INPUT_PULLUP);
pinMode(_pin_y_direction, OUTPUT); pinMode(_pin.y.direction, OUTPUT);
pinMode(_pin_y_pulse, OUTPUT); pinMode(_pin.y.pulse, OUTPUT);
pinMode(_pin_y_enable, OUTPUT); pinMode(_pin.y.enable, OUTPUT);
pinMode(_pin_y_home, INPUT_PULLUP); pinMode(_pin.y.home, INPUT_PULLUP);
_stepperX.begin(); _stepper.x.begin();
_stepperY.begin(); _stepper.y.begin();
return *this; return *this;
} }
@ -45,27 +41,27 @@ Turret &Turret::gotoHome() {
long xStop = 0; long xStop = 0;
long yStop = 0; long yStop = 0;
_stepperX.prepareMove(-1000000l); _stepper.x.prepareMove(-1000000l);
_stepperY.prepareMove(-1000000l); _stepper.y.prepareMove(-1000000l);
while (true) { while (true) {
_stepperX.move(); _stepper.x.move();
_stepperY.move(); _stepper.y.move();
if (xStop == 2 && yStop == 2) { if (xStop == 2 && yStop == 2) {
_homeX = _stepperX.getPos(); _home.x = _stepper.x.getPos();
_homeY = _stepperY.getPos(); _home.y = _stepper.y.getPos();
break; break;
} }
if (xStop < 2 && digitalRead(_pin_x_home)) { if (xStop < 2 && digitalRead(_pin.x.home)) {
xStop++; xStop++;
_stepperX.stop(); _stepper.x.stop();
} }
if (yStop < 2 && digitalRead(_pin_y_home)) { if (yStop < 2 && digitalRead(_pin.y.home)) {
yStop++; yStop++;
_stepperY.stop(); _stepper.y.stop();
} }
} }
@ -74,8 +70,8 @@ Turret &Turret::gotoHome() {
Turret &Turret::gotoZero() { Turret &Turret::gotoZero() {
// TODO remove magic numbers // TODO remove magic numbers
_stepperX.prepareMove(_homeX + 0); _stepper.x.prepareMove(_home.x + 0);
_stepperY.prepareMove(_homeY + 2500); _stepper.y.prepareMove(_home.y + 2500);
bool xStop = false; bool xStop = false;
bool yStop = false; bool yStop = false;
@ -84,13 +80,13 @@ Turret &Turret::gotoZero() {
if (xStop && yStop) if (xStop && yStop)
break; break;
if (!xStop) if (!xStop)
xStop = _stepperY.move() == STATE_STOPPED; xStop = _stepper.y.move() == STATE_STOPPED;
if (!yStop) if (!yStop)
yStop = _stepperX.move() == STATE_STOPPED; yStop = _stepper.x.move() == STATE_STOPPED;
} }
_zeroX = _stepperX.getPos(); _zero.x = _stepper.x.getPos();
_zeroY = _stepperY.getPos(); _zero.y = _stepper.y.getPos();
return *this; return *this;
} }
@ -102,39 +98,39 @@ Turret &Turret::calibrate() {
} }
Turret &Turret::moveTo(double x, double y, double z, Unit unit) { Turret &Turret::moveTo(double x, double y, double z, Unit unit) {
long stepX; vec2<long> step;
long stepY;
if (unit == Unit::MM) { if (unit == Unit::MM) {
cartesianToPolar(stepX, stepY, _zeroX, _zeroY, x / 10.0, y / 10.0, vec3<double> position(x / 10.0, y / 10.0, z / 10.0);
z / 10.0); cartesianToPolar(_step_ratio, _offset, _zero, position, step);
} }
if (unit == Unit::CM) { if (unit == Unit::CM) {
cartesianToPolar(stepX, stepY, _zeroX, _zeroY, x, y, z); vec3<double> position(x, y, z);
cartesianToPolar(_step_ratio, _offset, _zero, position, step);
} }
if (unit == Unit::M) { if (unit == Unit::M) {
cartesianToPolar(stepX, stepY, _zeroX, _zeroY, x * 100.0, y * 100.0, vec3<double> position(x * 100.0, y * 100.0, z * 100.0);
z * 100.0); cartesianToPolar(_step_ratio, _offset, _zero, position, step);
} }
if (unit == Unit::STEP) { if (unit == Unit::STEP) {
stepX = x; step.x = x;
stepY = y; step.y = y;
} }
if (unit == Unit::RAD) { if (unit == Unit::RAD) {
angleToStep(stepX, stepY, x, y); angleToStep(_step_ratio, vec2<double>(x, y), step);
} }
if (unit == Unit::DEG) { if (unit == Unit::DEG) {
angleToStep(stepX, stepY, degToRad(x), degToRad(y)); angleToStep(_step_ratio, vec2<double>(degToRad(x), degToRad(y)), step);
} }
// TODO min(valueI, -_homeI); // TODO min(valueI, -_homeI);
_stepperX.prepareMove(_zeroX + stepX); _stepper.x.prepareMove(_zero.x + step.x);
_stepperY.prepareMove(_zeroY + stepY); _stepper.y.prepareMove(_zero.y + step.y);
bool xStop = false; bool xStop = false;
bool yStop = false; bool yStop = false;
@ -143,47 +139,47 @@ Turret &Turret::moveTo(double x, double y, double z, Unit unit) {
if (xStop && yStop) if (xStop && yStop)
break; break;
if (!xStop) if (!xStop)
xStop = _stepperX.move() == STATE_STOPPED; xStop = _stepper.x.move() == STATE_STOPPED;
if (!yStop) if (!yStop)
yStop = _stepperY.move() == STATE_STOPPED; yStop = _stepper.y.move() == STATE_STOPPED;
} }
_currentX = x; _current.x = x;
_currentY = y; _current.y = y;
_currentZ = z; _current.z = z;
return *this; return *this;
} }
Turret &Turret::moveBy(double x, double y, double z, Unit unit) { Turret &Turret::moveBy(double x, double y, double z, Unit unit) {
long zeroXStored = _zeroX; long zeroXStored = _zero.x;
long zeroYStored = _zeroY; long zeroYStored = _zero.y;
_zeroX += _stepperX.getPos(); _zero.x += _stepper.x.getPos();
_zeroY += _stepperY.getPos(); _zero.y += _stepper.y.getPos();
moveTo(x, y, z, unit); moveTo(x, y, z, unit);
_zeroX = zeroXStored; _zero.x = zeroXStored;
_zeroY = zeroYStored; _zero.y = zeroYStored;
_currentX = x; _current.x = x;
_currentY = y; _current.y = y;
_currentZ = z; _current.z = z;
return *this; return *this;
} }
Turret &Turret::moveToX(double x, Unit unit) { Turret &Turret::moveToX(double x, Unit unit) {
return moveTo(x, _currentY, _currentZ, unit); return moveTo(x, _current.y, _current.z, unit);
} }
Turret &Turret::moveToY(double y, Unit unit) { Turret &Turret::moveToY(double y, Unit unit) {
return moveTo(_currentX, y, _currentZ, unit); return moveTo(_current.x, y, _current.z, unit);
} }
Turret &Turret::moveToZ(double z, Unit unit) { Turret &Turret::moveToZ(double z, Unit unit) {
return moveTo(_currentX, _currentY, z, unit); return moveTo(_current.x, _current.y, z, unit);
} }
Turret &Turret::moveByX(double x, Unit unit) { return moveBy(x, 0, 0, unit); } Turret &Turret::moveByX(double x, Unit unit) { return moveBy(x, 0, 0, unit); }
@ -208,11 +204,13 @@ Turret &Turret::getZero(double &x, double &y, double &z, Unit unit) {
} }
Turret &Turret::laserOn() { Turret &Turret::laserOn() {
digitalWrite(_pin_laser, HIGH); digitalWrite(_pin.x.laser, HIGH);
digitalWrite(_pin.y.laser, HIGH);
return *this; return *this;
} }
Turret &Turret::laserOff() { Turret &Turret::laserOff() {
digitalWrite(_pin_laser, LOW); digitalWrite(_pin.x.laser, LOW);
digitalWrite(_pin.y.laser, LOW);
return *this; return *this;
} }

View file

@ -3,13 +3,43 @@
#include <kissStepper.h> #include <kissStepper.h>
template <typename T> struct vec3 {
T x;
T y;
T z;
vec3() : x(T()), y(T()), z(T()) {}
vec3(T _x, T _y, T _z) : x(_x), y(_y), z(_z) {}
};
template <typename T> struct vec2 {
T x;
T y;
vec2() : x(T()), y(T()) {}
vec2(T _x, T _y) : x(_x), y(_y) {}
};
class Turret { class Turret {
public: public:
enum Unit { MM, CM, M, RAD, DEG, STEP }; enum Unit { MM, CM, M, RAD, DEG, STEP };
Turret(int pin_x_direction, int pin_x_pulse, int pin_x_enable, int pin_x_home, using StepRatio = vec2<double>;
int pin_y_direction, int pin_y_pulse, int pin_y_enable, int pin_y_home, using Offset = vec3<double>;
int pin_laser); // x -> turret to screen
// y -> laser to stand
// z -> unused
struct PinMap {
int home;
int direction;
int pulse;
int enable;
int laser;
};
Turret(StepRatio step_ratio, Offset offset, PinMap pin_map_x,
PinMap pin_map_y);
Turret &init(); Turret &init();
Turret &gotoHome(); Turret &gotoHome();
@ -36,30 +66,13 @@ public:
Turret &laserOff(); Turret &laserOff();
private: private:
kissStepper _stepperX; vec2<kissStepper> _stepper;
kissStepper _stepperY; vec2<long> _home;
vec2<long> _zero;
int _homeX; vec3<long> _current;
int _homeY; vec2<PinMap> _pin;
StepRatio _step_ratio;
int _zeroX; Offset _offset;
int _zeroY;
int _currentX;
int _currentY;
int _currentZ;
int _pin_x_direction;
int _pin_x_pulse;
int _pin_x_enable;
int _pin_y_direction;
int _pin_y_pulse;
int _pin_y_enable;
int _pin_x_home;
int _pin_y_home;
int _pin_laser;
}; };
#endif #endif

View file

@ -1,9 +1,26 @@
#include "config.h" #include "config.h"
#include "turret.h" #include "turret.h"
Turret turret(PIN_X_DIRECTION, PIN_X_PULSE, PIN_X_ENABLE, PIN_X_HOME, Turret::PinMap pinX = {
PIN_Y_DIRECTION, PIN_Y_PULSE, PIN_Y_ENABLE, PIN_Y_HOME, .home = PIN_X_HOME,
PIN_LASER); .direction = PIN_X_DIRECTION,
.pulse = PIN_X_PULSE,
.enable = PIN_X_ENABLE,
.laser = PIN_LASER,
};
Turret::PinMap pinY = {
.home = PIN_Y_HOME,
.direction = PIN_Y_DIRECTION,
.pulse = PIN_Y_PULSE,
.enable = PIN_Y_ENABLE,
.laser = PIN_LASER,
};
Turret::StepRatio stepRatio(STEP_RATIO_X, STEP_RATIO_Y);
Turret::Offset offset(OFFSET_X, OFFSET_Y, OFFSET_Z);
Turret turret(stepRatio, offset, pinX, pinY);
void setup() { void setup() {
turret.init(); turret.init();