Compare commits
19 Commits
0c3dd769bc
...
42f5c3cbd7
Author | SHA1 | Date |
---|---|---|
radex | 42f5c3cbd7 | |
radex | d478fe34ea | |
radex | 1914c026d2 | |
radex | d006b7a457 | |
radex | 5febbecb99 | |
radex | fb540562b7 | |
radex | 56de397afb | |
radex | 7f08e847a1 | |
radex | 0edfbe6a50 | |
radex | 53d28add10 | |
radex | 0938fe70b1 | |
radex | 7955846d86 | |
radex | a6d9ad9817 | |
radex | e342d6f684 | |
radex | 91543a4a3d | |
radex | 3170a046b7 | |
radex | ef859d4c8e | |
radex | d191795902 | |
radex | 4eed439f26 |
Binary file not shown.
File diff suppressed because one or more lines are too long
|
@ -12,9 +12,11 @@
|
|||
platform = atmelavr
|
||||
board = uno
|
||||
framework = arduino
|
||||
|
||||
lib_deps =
|
||||
Wire
|
||||
blackhack/LCD_I2C@^2.3.0
|
||||
luisllamasbinaburo/I2CScanner@^1.0.1
|
||||
robtillaart/PCF8574@^0.4.1
|
||||
Wire
|
||||
blackhack/LCD_I2C@^2.3.0
|
||||
luisllamasbinaburo/I2CScanner@^1.0.1
|
||||
robtillaart/PCF8574@^0.4.1
|
||||
robtillaart/AS5600@^0.6.0
|
||||
|
||||
monitor_speed = 1500000
|
||||
|
|
|
@ -3,6 +3,7 @@
|
|||
// --- debug config
|
||||
|
||||
#define DEBUG_I2C 0
|
||||
#define DEBUG_PRINT_EVENTS 1
|
||||
|
||||
// --- pinout
|
||||
|
||||
|
@ -26,10 +27,21 @@
|
|||
#define KBD_I2C_ADDR 0x21
|
||||
|
||||
// Used by keyboard and encoder switch
|
||||
#define DEBOUNCE_MS 10
|
||||
#define DEBOUNCE_MS 5
|
||||
|
||||
// --- Z axis motor
|
||||
|
||||
#define STEPPER_ENABLE A0
|
||||
#define STEPPER_STEP A1
|
||||
#define STEPPER_STEP_PORT PORTC
|
||||
#define STEPPER_STEP_BIT 1 << 1
|
||||
#define STEPPER_DIR A2
|
||||
|
||||
#define STEPPER_STEPS_PER_REV 200
|
||||
#define STEPPER_MICROSTEPS 2
|
||||
#define STEPPER_MM_PER_REV 0.5 // TODO: measure this
|
||||
|
||||
#define MICROS_PER_TICK 16 // 16MHz / 256 = 62.5kHz = 16us per tick
|
||||
#define STEPPER_MIN_CADANCE 50 // speed measured in timer ticks per step (less is faster)
|
||||
#define STEPPER_MAX_CADANCE 12
|
||||
#define STEPPER_CADENCE_ACCEL_MS 3 // acceleration measured in ms per cadence increment/decrement
|
||||
|
|
|
@ -1,18 +1,19 @@
|
|||
#include <Arduino.h>
|
||||
#if DEBUG_I2C
|
||||
#include <I2CScanner.h>
|
||||
I2CScanner scanner;
|
||||
#endif
|
||||
#include "constants.h"
|
||||
#include "buzzer.h"
|
||||
|
||||
#if DEBUG_I2C
|
||||
I2CScanner scanner;
|
||||
#endif
|
||||
#include "screen.h"
|
||||
#include "keyboard.h"
|
||||
#include "stepper.h"
|
||||
#include "input.h"
|
||||
|
||||
void setupDebug() {
|
||||
pinMode(LED_BUILTIN, OUTPUT);
|
||||
|
||||
Serial.begin(9600);
|
||||
Serial.begin(1500000);
|
||||
Serial.println("it's cewk-o-mator, hello!");
|
||||
#if DEBUG_I2C
|
||||
scanner.Init();
|
||||
|
@ -40,3 +41,86 @@ void fatal() {
|
|||
digitalWrite(LED_BUILTIN, LOW);
|
||||
}
|
||||
}
|
||||
|
||||
char getDebugKey() {
|
||||
if (Serial.available() > 0) {
|
||||
return Serial.read();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void handleDebugFunctions(char key) {
|
||||
if (key == 'h') {
|
||||
Serial.println("Debug functions:");
|
||||
Serial.println(" h - print this help");
|
||||
Serial.println(" s - play sounds");
|
||||
Serial.println(" i - timing test");
|
||||
Serial.println(" l - change stepper direction to left");
|
||||
Serial.println(" r - change stepper direction to right");
|
||||
Serial.println(" - - toggle stepper timer");
|
||||
Serial.println(" q - quick accelerate");
|
||||
} else if (key == 's') {
|
||||
happyBuzz();
|
||||
delay(500);
|
||||
sadBuzz();
|
||||
delay(500);
|
||||
beep();
|
||||
delay(500);
|
||||
tick();
|
||||
} else if (key == 'i') {
|
||||
auto micros1 = micros();
|
||||
Serial.println("Hello, world!");
|
||||
auto micros2 = micros();
|
||||
Serial.print("Serial print time (microseconds): ");
|
||||
Serial.println(micros2 - micros1);
|
||||
|
||||
micros1 = micros();
|
||||
lcd.print("Hello, world!");
|
||||
micros2 = micros();
|
||||
Serial.print("LCD print time (microseconds): ");
|
||||
Serial.println(micros2 - micros1);
|
||||
|
||||
micros1 = micros();
|
||||
handleKeyboard();
|
||||
micros2 = micros();
|
||||
Serial.print("Keyboard scan time (microseconds): ");
|
||||
Serial.println(micros2 - micros1);
|
||||
} else if (key == 'l') {
|
||||
setStepperDirection(LEFT);
|
||||
} else if (key == 'r') {
|
||||
setStepperDirection(RIGHT);
|
||||
} else if (key == '-') {
|
||||
setTimerEnabled(!isTimerEnabled());
|
||||
} else if (key == 'q') {
|
||||
quickAccelerate();
|
||||
}
|
||||
}
|
||||
|
||||
void debugHandleInput(Input input) {
|
||||
handleDebugFunctions(input.debugKey);
|
||||
|
||||
#if DEBUG_PRINT_EVENTS
|
||||
if (input.key) {
|
||||
Serial.print("Key pressed: ");
|
||||
Serial.print(allKeys[input.key]);
|
||||
|
||||
auto digit = getPressedDigit(input.key);
|
||||
if (digit != KEY_NONE) {
|
||||
Serial.print(", digit: ");
|
||||
Serial.print(digit);
|
||||
} else {
|
||||
Serial.print(" (Not a digit)");
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
if (input.switchEvent) {
|
||||
Serial.println(input.switchEvent == SWITCH_PRESSED ? "Pressed" : "Released");
|
||||
}
|
||||
|
||||
if (input.encoderEvent) {
|
||||
Serial.println(input.encoderEvent == ENCODER_CLOCKWISE ? "Clockwise" : "Counter-clockwise");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -1,5 +1,22 @@
|
|||
#pragma once
|
||||
struct Input;
|
||||
|
||||
void setupDebug();
|
||||
void debugScanI2C();
|
||||
void fatal();
|
||||
|
||||
/**
|
||||
* Via serial:
|
||||
*
|
||||
* Keyboard:
|
||||
* 01232456789
|
||||
* abcd (ABCD)
|
||||
* * / .
|
||||
* # / Backspace
|
||||
*
|
||||
* Encoder: [ / ]
|
||||
* Encoder switch: Space
|
||||
*/
|
||||
char getDebugKey();
|
||||
|
||||
void debugHandleInput(Input input);
|
||||
|
|
|
@ -51,6 +51,23 @@ SwitchEvent handleSwitch() {
|
|||
return isPressed ? SWITCH_PRESSED : SWITCH_RELEASED;
|
||||
}
|
||||
|
||||
bool shouldReleaseDebugSwitch = false;
|
||||
SwitchEvent handleDebugSwitch(char key) {
|
||||
if (auto event = handleSwitch()) {
|
||||
return event;
|
||||
}
|
||||
|
||||
if (shouldReleaseDebugSwitch) {
|
||||
shouldReleaseDebugSwitch = false;
|
||||
return SWITCH_RELEASED;
|
||||
} else if (key == ' ') {
|
||||
shouldReleaseDebugSwitch = true;
|
||||
return SWITCH_PRESSED;
|
||||
} else {
|
||||
return SWITCH_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
unsigned long lastEncoderChangeAt = 0;
|
||||
|
||||
EncoderEvent handleEncoder() {
|
||||
|
@ -87,3 +104,17 @@ EncoderEvent handleEncoder() {
|
|||
// return event
|
||||
return event;
|
||||
}
|
||||
|
||||
EncoderEvent handleDebugEncoder(char key) {
|
||||
if (auto event = handleEncoder()) {
|
||||
return event;
|
||||
}
|
||||
|
||||
if (key == '[') {
|
||||
return ENCODER_COUNTER_CLOCKWISE;
|
||||
} else if (key == ']') {
|
||||
return ENCODER_CLOCKWISE;
|
||||
} else {
|
||||
return ENCODER_NONE;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -13,4 +13,6 @@ typedef int8_t EncoderEvent;
|
|||
void setupEncoder();
|
||||
|
||||
SwitchEvent handleSwitch();
|
||||
SwitchEvent handleDebugSwitch(char key);
|
||||
EncoderEvent handleEncoder();
|
||||
EncoderEvent handleDebugEncoder(char key);
|
||||
|
|
|
@ -0,0 +1,12 @@
|
|||
#include "debug.h"
|
||||
#include "input.h"
|
||||
|
||||
Input getInput() {
|
||||
auto debugKey = getDebugKey();
|
||||
auto key = handleDebugKeyboard(debugKey);
|
||||
auto switchEvent = handleDebugSwitch(debugKey);
|
||||
auto encoderEvent = handleDebugEncoder(debugKey);
|
||||
bool hasInput = debugKey || key || switchEvent || encoderEvent;
|
||||
|
||||
return {debugKey, key, switchEvent, encoderEvent, hasInput};
|
||||
}
|
|
@ -0,0 +1,15 @@
|
|||
#pragma once
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "keyboard.h"
|
||||
#include "encoder.h"
|
||||
|
||||
struct Input {
|
||||
char debugKey;
|
||||
Key key;
|
||||
SwitchEvent switchEvent;
|
||||
EncoderEvent encoderEvent;
|
||||
bool hasInput;
|
||||
};
|
||||
|
||||
Input getInput();
|
|
@ -19,10 +19,11 @@ row/col 0 1 2 3
|
|||
3 * 0 # D
|
||||
*/
|
||||
|
||||
const char *allKeys = "123A456B789C*0#D";
|
||||
const char *allKeys = " 123A456B789C*0#D";
|
||||
|
||||
const uint8_t digits[16] =
|
||||
{ 1, 2, 3, KEY_NONE,
|
||||
const uint8_t digits[17] =
|
||||
{ KEY_NONE,
|
||||
1, 2, 3, KEY_NONE,
|
||||
4, 5, 6, KEY_NONE,
|
||||
7, 8, 9, KEY_NONE,
|
||||
KEY_NONE, 0, KEY_NONE, KEY_NONE};
|
||||
|
@ -122,10 +123,60 @@ Key getPressedKey() {
|
|||
}
|
||||
|
||||
// return key
|
||||
return (rowPressed * 4) + colPressed;
|
||||
return (rowPressed * 4) + colPressed + 1;
|
||||
}
|
||||
|
||||
uint8_t getPressedDigit(Key key) {
|
||||
if (key == KEY_NONE) return KEY_NONE;
|
||||
return digits[key];
|
||||
}
|
||||
|
||||
Key handleDebugKeyboard(char key) {
|
||||
if (auto keyboardKey = handleKeyboard()) {
|
||||
return keyboardKey;
|
||||
}
|
||||
|
||||
if (!key) {
|
||||
return KEY_NONE;
|
||||
}
|
||||
|
||||
// keyboard: 123A 456B 789C *0#D
|
||||
// debug keys: 1234567890, abcd, ABCD, *, #
|
||||
// . -> *
|
||||
// Backspace -> #
|
||||
|
||||
if (key == '1') {
|
||||
return 1;
|
||||
} else if (key == '2') {
|
||||
return 2;
|
||||
} else if (key == '3') {
|
||||
return 3;
|
||||
} else if (key == 'a' || key == 'A') {
|
||||
return 4;
|
||||
} else if (key == '4') {
|
||||
return 5;
|
||||
} else if (key == '5') {
|
||||
return 6;
|
||||
} else if (key == '6') {
|
||||
return 7;
|
||||
} else if (key == 'b' || key == 'B') {
|
||||
return 8;
|
||||
} else if (key == '7') {
|
||||
return 9;
|
||||
} else if (key == '8') {
|
||||
return 10;
|
||||
} else if (key == '9') {
|
||||
return 11;
|
||||
} else if (key == 'c' || key == 'C') {
|
||||
return 12;
|
||||
} else if (key == '*' || key == '.') {
|
||||
return 13;
|
||||
} else if (key == '0') {
|
||||
return 14;
|
||||
} else if (key == '#' || (int) key == 8 /* Backspace */) {
|
||||
return 15;
|
||||
} else if (key == 'd' || key == 'D') {
|
||||
return 16;
|
||||
}
|
||||
|
||||
return KEY_NONE;
|
||||
}
|
||||
|
|
|
@ -1,17 +1,19 @@
|
|||
#pragma once
|
||||
|
||||
/*
|
||||
Keys, in order:
|
||||
Keys, in order (counting from 1):
|
||||
123A 456B 789C *0#D
|
||||
|
||||
value 0 indicates no key
|
||||
*/
|
||||
typedef uint8_t Key;
|
||||
#define KEY_NONE 255
|
||||
#define KEY_A 3
|
||||
#define KEY_B 7
|
||||
#define KEY_C 11
|
||||
#define KEY_D 15
|
||||
#define KEY_ASTERISK 12
|
||||
#define KEY_HASH 14
|
||||
#define KEY_NONE 0
|
||||
#define KEY_A 4
|
||||
#define KEY_B 8
|
||||
#define KEY_C 12
|
||||
#define KEY_D 16
|
||||
#define KEY_ASTERISK 13
|
||||
#define KEY_HASH 15
|
||||
|
||||
extern const char *allKeys;
|
||||
|
||||
|
@ -30,3 +32,5 @@ Key handleKeyboard();
|
|||
* Returns pressed digit or KEY_NONE if the key is not a digit
|
||||
*/
|
||||
uint8_t getPressedDigit(Key key);
|
||||
|
||||
Key handleDebugKeyboard(char key);
|
||||
|
|
|
@ -7,68 +7,41 @@
|
|||
#include "keyboard.h"
|
||||
#include "encoder.h"
|
||||
#include "debug.h"
|
||||
#include "timer.h"
|
||||
#include "stepper.h"
|
||||
#include "memes.h"
|
||||
#include "input.h"
|
||||
#include "spindle.h"
|
||||
|
||||
void setup() {
|
||||
setupDebug();
|
||||
setupEncoder();
|
||||
setupTimer();
|
||||
setupStepper();
|
||||
if (!setupStepper()) {
|
||||
fatal();
|
||||
}
|
||||
|
||||
Wire.begin();
|
||||
Wire.setClock(800000);
|
||||
|
||||
if (!setupScreen() || !setupKeyboard()) {
|
||||
if (!setupScreen()) {
|
||||
fatal();
|
||||
}
|
||||
if (!setupKeyboard()) {
|
||||
fatal();
|
||||
}
|
||||
if (!setupSpindle()) {
|
||||
fatal();
|
||||
}
|
||||
|
||||
splashScreen();
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
debugScanI2C();
|
||||
demoTimer();
|
||||
|
||||
auto key = handleKeyboard();
|
||||
if (key != KEY_NONE) {
|
||||
Serial.print("Key pressed: ");
|
||||
Serial.print(allKeys[key]);
|
||||
|
||||
auto digit = getPressedDigit(key);
|
||||
if (digit != KEY_NONE) {
|
||||
Serial.print(", digit: ");
|
||||
Serial.print(digit);
|
||||
} else {
|
||||
Serial.print(" (Not a digit)");
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
|
||||
if (key == KEY_A) {
|
||||
happyBuzz();
|
||||
} else if (key == KEY_B) {
|
||||
sadBuzz();
|
||||
} else if (key == KEY_C) {
|
||||
beep();
|
||||
} else if (digit == 4) {
|
||||
demo_moveBy(-8000);
|
||||
} else if (digit == 5) {
|
||||
demo_moveBy(8000);
|
||||
} else {
|
||||
tick();
|
||||
}
|
||||
}
|
||||
|
||||
if (auto event = handleSwitch()) {
|
||||
auto input = getInput();
|
||||
if (input.hasInput) {
|
||||
tick();
|
||||
Serial.println(event == SWITCH_PRESSED ? "Pressed" : "Released");
|
||||
}
|
||||
|
||||
if (auto event = handleEncoder()) {
|
||||
tick();
|
||||
Serial.println(event == ENCODER_CLOCKWISE ? "Clockwise" : "Counter-clockwise");
|
||||
demo_moveBy(event == ENCODER_CLOCKWISE ? 800 : -800);
|
||||
}
|
||||
debugHandleInput(input);
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,27 @@
|
|||
#include <AS5600.h>
|
||||
#include <Wire.h>
|
||||
#include "spindle.h"
|
||||
|
||||
AS5600 spindle(&Wire);
|
||||
|
||||
bool setupSpindle() {
|
||||
if (!spindle.begin()) {
|
||||
Serial.println("Could not initialize spindle encoder");
|
||||
return false;
|
||||
} else if (!spindle.detectMagnet()) {
|
||||
Serial.println("Could not detect magnet");
|
||||
return false;
|
||||
} else if (spindle.magnetTooWeak()) {
|
||||
Serial.println("Magnet too weak");
|
||||
return false;
|
||||
} else if (spindle.magnetTooStrong()) {
|
||||
Serial.println("Magnet too strong");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t getSpindlePosition() {
|
||||
return spindle.readAngle();
|
||||
}
|
|
@ -0,0 +1,5 @@
|
|||
#pragma once
|
||||
|
||||
bool setupSpindle();
|
||||
/** 0..4095 (12-bit) */
|
||||
uint16_t getSpindlePosition();
|
|
@ -1,29 +1,107 @@
|
|||
#include <Arduino.h>
|
||||
#include "constants.h"
|
||||
#include "debug.h"
|
||||
#include "stepper.h"
|
||||
|
||||
/*
|
||||
|
||||
A4988 Stepper Motor Driver.
|
||||
|
||||
NOTE: minimum pulse width 1us high, 1us low
|
||||
|
||||
*/
|
||||
|
||||
void setupStepper() {
|
||||
#if F_CPU != 16000000
|
||||
#error "Unsupported F_CPU"
|
||||
#endif
|
||||
|
||||
bool setupStepper() {
|
||||
pinMode(STEPPER_ENABLE, OUTPUT);
|
||||
pinMode(STEPPER_DIR, OUTPUT);
|
||||
pinMode(STEPPER_STEP, OUTPUT);
|
||||
|
||||
// low = enabled
|
||||
digitalWrite(STEPPER_ENABLE, LOW);
|
||||
setStepperEnabled(false);
|
||||
|
||||
// sanity check
|
||||
if (!((int) portOutputRegister(digitalPinToPort(STEPPER_STEP)) == (int) &STEPPER_STEP_PORT
|
||||
&& digitalPinToBitMask(STEPPER_STEP) == STEPPER_STEP_BIT
|
||||
)) {
|
||||
Serial.println("Stepper step pin is misconfigured");
|
||||
return false;
|
||||
}
|
||||
|
||||
// set up the timer
|
||||
noInterrupts();
|
||||
// reset timer settings
|
||||
TCCR1A = 0;
|
||||
TCCR1B = 0;
|
||||
TCNT1 = 0;
|
||||
TIMSK1 &= ~(1 << OCIE1A);
|
||||
// 256 prescaler (16MHz / 256 = 62.5kHz)
|
||||
TCCR1B |= (1 << CS12);
|
||||
// CTC mode (Clear Timer on Compare Match)
|
||||
TCCR1B |= (1 << WGM12);
|
||||
// interrupt at 62.5kHz / (OCR1A + 1)
|
||||
OCR1A = 39;
|
||||
interrupts();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void demoStepper(bool dir) {
|
||||
digitalWrite(STEPPER_DIR, dir);
|
||||
for (int i = 0; i < 3200; i++) {
|
||||
digitalWrite(STEPPER_STEP, HIGH);
|
||||
delayMicroseconds(25);
|
||||
digitalWrite(STEPPER_STEP, LOW);
|
||||
delayMicroseconds(25);
|
||||
bool isTimerEnabled() {
|
||||
return TIMSK1 & (1 << OCIE1A);
|
||||
}
|
||||
|
||||
void setTimerEnabled(bool enabled) {
|
||||
if (enabled) {
|
||||
TIMSK1 |= (1 << OCIE1A);
|
||||
} else {
|
||||
TIMSK1 &= ~(1 << OCIE1A);
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t getTimerCadence() {
|
||||
return OCR1A;
|
||||
}
|
||||
|
||||
void setTimerCadence(uint16_t cadence) {
|
||||
noInterrupts();
|
||||
// if TCNT1 > OCR1A, it won't be reset until it reaches uint16_t's max value
|
||||
TCNT1 = min(TCNT1, cadence - 1);
|
||||
// interrupt at 62.5kHz / (OCR1A + 1)
|
||||
OCR1A = cadence;
|
||||
interrupts();
|
||||
}
|
||||
|
||||
void setStepperEnabled(bool enabled) {
|
||||
digitalWrite(STEPPER_ENABLE, !enabled);
|
||||
}
|
||||
|
||||
bool getStepperDirection() {
|
||||
return !digitalRead(STEPPER_DIR);
|
||||
}
|
||||
|
||||
void setStepperDirection(bool dir) {
|
||||
digitalWrite(STEPPER_DIR, !dir);
|
||||
}
|
||||
|
||||
inline void step() {
|
||||
// NOTE: minimum pulse width 1us high, 1us low
|
||||
STEPPER_STEP_PORT |= STEPPER_STEP_BIT;
|
||||
delayMicroseconds(1);
|
||||
STEPPER_STEP_PORT &= ~STEPPER_STEP_BIT;
|
||||
}
|
||||
|
||||
ISR(TIMER1_COMPA_vect) {
|
||||
step();
|
||||
}
|
||||
|
||||
void quickAccelerate() {
|
||||
setStepperEnabled(true);
|
||||
uint16_t cadence = STEPPER_MIN_CADANCE;
|
||||
setTimerCadence(cadence);
|
||||
setTimerEnabled(true);
|
||||
while (cadence > STEPPER_MAX_CADANCE) {
|
||||
delay(STEPPER_CADENCE_ACCEL_MS);
|
||||
cadence--;
|
||||
setTimerCadence(cadence);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,4 +1,19 @@
|
|||
#pragma once
|
||||
|
||||
void setupStepper();
|
||||
void demoStepper(bool dir);
|
||||
#define RIGHT 1
|
||||
#define LEFT 0
|
||||
|
||||
bool setupStepper();
|
||||
|
||||
bool isTimerEnabled();
|
||||
void setTimerEnabled(bool enabled);
|
||||
uint16_t getTimerCadence();
|
||||
void setTimerCadence(uint16_t cadence);
|
||||
|
||||
void setStepperEnabled(bool enabled);
|
||||
bool getStepperDirection();
|
||||
void setStepperDirection(bool dir);
|
||||
inline void step();
|
||||
|
||||
/** Accelerates from 0 to max speed as quickly as possible, synchronously */
|
||||
void quickAccelerate();
|
||||
|
|
|
@ -1,74 +0,0 @@
|
|||
#include <Arduino.h>
|
||||
#include "constants.h"
|
||||
|
||||
#define DEMO_REPORT_SECONDS 2
|
||||
#define DEMO_TRIGGER_MS DEMO_REPORT_SECONDS * 1000
|
||||
|
||||
#if F_CPU != 16000000
|
||||
#error "Unsupported F_CPU"
|
||||
#endif
|
||||
|
||||
void setupTimer() {
|
||||
noInterrupts();
|
||||
// reset timer settings
|
||||
TCCR1A = 0;
|
||||
TCCR1B = 0;
|
||||
TCNT1 = 0;
|
||||
// 256 prescaler (16MHz / 256 = 62.5kHz)
|
||||
TCCR1B |= (1 << CS12);
|
||||
// CTC mode (Clear Timer on Compare Match)
|
||||
TCCR1B |= (1 << WGM12);
|
||||
// interrupt at 62.5kHz / (OCR1A + 1)
|
||||
OCR1A = 19;
|
||||
// enable timer
|
||||
TIMSK1 |= (1 << OCIE1A);
|
||||
interrupts();
|
||||
}
|
||||
|
||||
// incremented every DEMO_TRIGGER_MS by interrupt,
|
||||
// read and decremented by main loop
|
||||
volatile uint8_t timerEvents = 0;
|
||||
uint8_t demoCounter = 0;
|
||||
|
||||
void demoTimer() {
|
||||
bool shouldTrigger = false;
|
||||
|
||||
noInterrupts();
|
||||
if (timerEvents > 0) {
|
||||
timerEvents--;
|
||||
shouldTrigger = true;
|
||||
}
|
||||
interrupts();
|
||||
|
||||
if (shouldTrigger) {
|
||||
demoCounter += DEMO_REPORT_SECONDS;
|
||||
Serial.print("Uptime: ");
|
||||
Serial.print(demoCounter);
|
||||
Serial.println("s");
|
||||
}
|
||||
}
|
||||
|
||||
volatile int16_t stepsLeft = 0;
|
||||
|
||||
void demo_moveBy(int16_t steps) {
|
||||
bool dir;
|
||||
|
||||
noInterrupts();
|
||||
stepsLeft += steps;
|
||||
dir = steps > 0 ? LOW : HIGH;
|
||||
digitalWrite(STEPPER_DIR, dir);
|
||||
interrupts();
|
||||
}
|
||||
|
||||
volatile uint16_t timerTicks = 0;
|
||||
volatile uint16_t timerMillis = 0;
|
||||
|
||||
ISR(TIMER1_COMPA_vect) {
|
||||
if (stepsLeft != 0) {
|
||||
stepsLeft += stepsLeft > 0 ? -1 : 1;
|
||||
|
||||
// pulse STEP
|
||||
PORTC |= 1<<1;
|
||||
PORTC &= ~(1<<1);
|
||||
}
|
||||
}
|
|
@ -1,4 +0,0 @@
|
|||
void setupTimer();
|
||||
void demoTimer();
|
||||
|
||||
void demo_moveBy(int16_t steps);
|
Loading…
Reference in New Issue