//============= Inclusão de Bibliotecas ============
#include <RotaryEncoder.h>
#include <Wire.h>
#include <digitalWriteFast.h>
#include <limits.h>
#define USE_TIMER_2 true
#include <TimerInterrupt.h>
#include "auxiliar_botao.h"
#include "definicoes.h"
#include "display_controller.h"
#include "variavel_limpa_suja.h"
//================= Criando objetos ================//
RotaryEncoder encoder{ROTARY_ENCODER_DT, ROTARY_ENCODER_CLK};
VariavelLimpaSuja<int> eixo{1}; // Cria variável (inteira) e atribui 1 para valor inicial - Controle do Menu no display LCD
VariavelLimpaSuja<int> feed{5}; // Cria uma variável Avanço anterior (5->180) e atribui 0 como valor inicial
VariavelLimpaSuja<unsigned int> step_motor_steps{0}; // Indicativo de quantos passos o step-motor fez.
//=============== Variáveis Globais ===============//
bool contaEnDi{false}; // Indica se os steppers estão ativados
volatile bool state{false}; // Variável de armazenamento do estado do movimento - volatile to disable some optimizations as we use it in interrupts
unsigned long last_state_change{0}; // Variável de tempo final usada com a função milis()
volatile unsigned long last_on_off_button_interrupt{0};
unsigned long last_on{0}; // Controle de quando foi a última vez que teve movimento
//=============== Variables to control timer and movement ===============//
volatile int timer_feed{0};
void start_axis_movement() {
timer_feed = feed;
ITimer2.attachInterrupt(/*frequency=*/get_frequency(), axis_movement_interrupt);
}
inline float get_frequency() {
return ((float)abs(timer_feed)) * FREQUENCY_PWM; // abs(feed)/PWM (us per mm) * 2 (one high/one low) * 1000000 (f=1/time)
}
//=============== Controle Display ===============//
ControleDisplay controle_display{&state, &contaEnDi, &encoder, &feed, &eixo, &step_motor_steps};
void setup() {
//============== Entradas e saídas ==============//
pinModeFast(butOnOff, INPUT_PULLUP); // Declara o Botão Liga / Desliga como entrada PULL_UP
pinModeFast(butEnDi, INPUT_PULLUP); // Declara o Botão Enable / Disable (Motor X) como entrada PULL_UP
pinModeFast(butDir, INPUT_PULLUP);
pinModeFast(butEncod, INPUT_PULLUP); // Declara o Botão do Encoder como entrada PULL_UP
pinModeFast(ledWhite, OUTPUT); // Declara o LED branco como saída
pinModeFast(ledGreen, OUTPUT); // Declara o LED verde como saída
pinModeFast(ledRed, OUTPUT); // Declara o LED vermelho como saída
pinModeFast(ledBlue, OUTPUT); // Declara o LED azul como saída
pinModeFast(ledYello, OUTPUT); // Declara o pino como saída. LED amarelo como saída
pinModeFast(pulsePinX, OUTPUT); // Declara o pino como saída. Alimenta os pulsos PWM no driver do Motor X
pinModeFast(pulsePinY, OUTPUT); // Declara o pino como saída. Alimenta os pulsos PWM no driver do Motor Y
pinModeFast(pulsePinZ, OUTPUT); // Declara o pino como saída. Alimenta os pulsos PWM no driver do Motor Z
pinModeFast(dirPinX, OUTPUT); // Declara o pino como saída. Controla direção de rotação no driver do Motor X
pinModeFast(dirPinY, OUTPUT); // Declara o pino como saída. Controla direção de rotação no driver do Motor Y
pinModeFast(dirPinZ, OUTPUT); // Declara o pino como saída. Controla direção de rotação no driver do Motor Z
pinModeFast(enPinX, OUTPUT); // Declara o pino como saída. Controla o bloqueio através do driver do Motor X
pinModeFast(enPinY, OUTPUT); // Declara o pino como saída. Controla o bloqueio através do driver do Motor Y
pinModeFast(enPinZ, OUTPUT); // Declara o pino como saída. Controla o bloqueio através do driver do Motor Z
// Serial.begin(9600); // Habilita a comunicação serial com 9600 BPS de velocidade
attachInterrupt(digitalPinToInterrupt(butOnOff), ISR4, LOW); // Habilita a Interrupção externa no Pino 19 quando o botão BotOnOff for pressionado
ITimer2.init(); // start timer for axis movement
// Inicia as configurações do diferentes modos de display:
controle_display.setup();
}
void loop() {
// atual modo atual do display
controle_display.loop();
// Atualiza informações nos led
update_leds();
// Atualiza informações de ativo/desativado e direção dos stepper
update_stepper();
}
void update_leds() {
if (contaEnDi) {
digitalWriteFast(ledGreen, HIGH);
digitalWriteFast(ledRed, LOW);
} else {
digitalWriteFast(ledGreen, LOW);
digitalWriteFast(ledRed, HIGH);
}
if (feed.get() > 0) {
digitalWriteFast(ledBlue, HIGH);
digitalWriteFast(ledYello, LOW);
} else {
digitalWriteFast(ledBlue, LOW);
digitalWriteFast(ledYello, HIGH);
}
digitalWriteFast(ledWhite, state);
}
void update_stepper() {
if (contaEnDi) {
// configuração para testar no site:
digitalWriteFast(enPinX, LOW);
digitalWriteFast(enPinY, LOW);
digitalWriteFast(enPinZ, LOW);
// configuração original:
// digitalWriteFast(enPinX, HIGH);
// digitalWriteFast(enPinY, HIGH);
// digitalWriteFast(enPinZ, HIGH);
} else {
// configuração para testar no site:
digitalWriteFast(enPinX, HIGH);
digitalWriteFast(enPinY, HIGH);
digitalWriteFast(enPinZ, HIGH);
// configuração original:
// digitalWriteFast(enPinX, LOW);
// digitalWriteFast(enPinY, LOW);
// digitalWriteFast(enPinZ, LOW);
}
if (feed.get() < 0) {
digitalWriteFast(dirPinX, LOW);
digitalWriteFast(dirPinY, LOW);
digitalWriteFast(dirPinZ, LOW);
} else {
digitalWriteFast(dirPinX, HIGH);
digitalWriteFast(dirPinY, HIGH);
digitalWriteFast(dirPinZ, HIGH);
}
}
void ISR4() {
if (millis() - last_on_off_button_interrupt > 10) {
last_on_off_button_interrupt = millis();
if ((millis() - last_state_change) > TIME_BUTTON_PRESS) {
// will only activate in a mode where it is possible run!
if (!state && controle_display.runnable()) {
state = true;
start_axis_movement();
} else if (state) {
state = false;
}
last_state_change = millis();
}
digitalWriteFast(ledWhite, state);
}
}
void axis_movement_interrupt() {
if (!state) {
ITimer2.disableTimer();
} else { // active
if (feed != timer_feed) { // speed changed, we need to change interrupt times
timer_feed = feed;
// 2 because we need the up and down parts of the pulse
// 120mm/min : 6.41 kHz
// 1mm/min : 107.5 Hz
float frequency = get_frequency();
if (!ITimer2.setFrequency(frequency, axis_movement_interrupt)) {
// in case we cannot set the frequency we will stop operation
state = false;
return;
}
}
// this triggers any update that must not stop => currently used for automode to check the step
controle_display.interrupt_loop();
update_stepper();
// do not do nothing. if it is manual mode it should stop; if it is automatic mode it should go to next step
if (timer_feed == 0) {
return;
}
// althought this might be a bit more code, it is quicker to us the underlying -Fast api
switch (eixo) {
case X_AXIS:
digitalToggleFast(pulsePinX);
break;
case Y_AXIS:
digitalToggleFast(pulsePinY);
break;
case Z_AXIS:
digitalToggleFast(pulsePinZ);
break;
}
// increment count of steps
step_motor_steps += 1;
}
}