#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#include <AccelStepper.h>
#include <EEPROM.h>
/*
Almoxarifado - Versão final ajustada (com controle de ocupação)
- Aceita senha mestre no login
- "Guardar" aparece só para mestre; "Devolver" para não-mestre
- Fluxo de confirmação para Devolver (Deseja devolver? Sim/Não)
- Após devolução, pergunta "Deseja continuar? Sim/Não" (Sim -> menu, Não -> tela de senha)
- Relé para fechadura eletrônica em RELAY_PIN (GP14)
- Controle de posições ocupadas, persistido na EEPROM
- Sistema de inatividade: apaga backlight e volta para tela de senha se sem atividade e sem motores em movimento
- Variáveis configuráveis no topo
- Comentários em Português
*/
// ======================== VARIÁVEIS CONFIGURÁVEIS (TOPO) ========================
// ======== CONFIGURAÇÕES DE POSIÇÃO DE DESCANSO / ONDE SERÁ PEGO OU DESCARREGADO ITENS ========
// Distância em centímetros para a posição segura
const float POS_DESCANSO_X_CM = 5.0;
const float POS_DESCANSO_Y_CM = 5.0;
const float POS_DESCANSO_Z_CM = 5.0;
// ======== CONFIGURAÇÃO DE ALTURA EXTRA ========
// Altura extra no eixo Z para segurança/desgrudar (cm)
const float Z_EXTRA_DESGRUDAR_CM = 2.0;
// ======== CONFIGURAÇÃO DE HOMING EM DOIS ESTÁGIOS ========
// Velocidade rápida inicial (cm/s)
const float HOMING_VEL_RAPIDA = 2.0;
// Velocidade lenta de precisão (cm/s)
const float HOMING_VEL_LENTA = 0.50;
// Distância de recuo entre as etapas (cm)
const float HOMING_RECUO_CM = 1.0;
// ======================== INATIVIDADE ========================
unsigned long ultimoTempoAtividade = 0;
bool telaBloqueada = false;
const unsigned long TEMPO_BLOQUEIO_MS = 5000; // 5 segundos
bool motoresEmMovimento = false;
// --- Pinos ---
const int Y_DIR = 6, Y_STEP = 7;
const int Z_DIR = 10, Z_STEP = 11;
const int X_DIR = 14, X_STEP = 15;
const int MICRO_Y = 0;
const int MICRO_Z = 1;
const int MICRO_X = 2;
const int RELE_SIRENE = 3;
const int botaoSirenePin = 28; // externo pull-down
const int RELAY_PIN = 4; // Relé para fechadura eletrônica (GP4)
// I2C LCD
const int LCD_SDA = 16, LCD_SCL = 17;
LiquidCrystal_I2C lcd(0x27, 16, 2);
// Teclado matricial 4×3
const byte ROWS = 4, COLS = 3;
const byte rowPins[ROWS] = {27, 26, 22, 21};
const byte colPins[COLS] = {20, 19, 18};
const char keysMap[ROWS][COLS] = {
{'1','2','3'},
{'4','5','6'},
{'7','8','9'},
{'*','0','#'}
};
// --- Movimento / Mecânica ---
const float DIST_COLUNAS_CM = 10.0;
const float DIST_LINHAS_CM = 10.0;
const float AVANCO_GARFO_CM = 10.0;
const float ALT_DESGRUDAR_CM = 2.0;
const float POS_X_APROX_CM = 10.0;
const float POS_Z_APROX_CM = 10.0;
const float POS_Y_APROX_CM = 0.0;
const float PASSOS_POR_CM_X = 509.0;
const float PASSOS_POR_CM_Y = 2560.0;
const float PASSOS_POR_CM_Z = 800.0;
const float VEL_MAX_X = 10.0, VEL_MAX_Y = 5.0, VEL_MAX_Z = 8.0;
const float ACEL_X = 50.0, ACEL_Y = 30.0, ACEL_Z = 40.0;
const int NUM_LINHAS = 3;
const int NUM_COLUNAS = 3;
const int MAX_POS = NUM_LINHAS * NUM_COLUNAS;
const int MAX_DIG = 3;
// Exemplo: const int posicoesOcupadasInicial[] = {2,5,7};
const int posicoesOcupadasInicial[] = {2,7,8}; // posição inicial ocupada (apenas no primeiro uso)
// ======================== STATES ========================
enum EstadoGlobal { AGUARDANDO_LOGIN, OPERANDO_MAQUINA };
EstadoGlobal estadoGlobal = AGUARDANDO_LOGIN;
enum StateAcesso { ST_IDLE, ST_ADMIN_PASS, ST_ADMIN_MENU, ST_NEWCPF, ST_DELCPF };
StateAcesso stateAcesso = ST_IDLE;
enum EstadoSistema {
CALIBRANDO_Y, CALIBRANDO_Z, CALIBRANDO_X,
MENU_PRINCIPAL, DIGITANDO_NUMERO,
MOSTRANDO_COORDENADAS, EXECUTANDO_ACAO,
VOLTANDO_Y, VOLTANDO_Z, VOLTANDO_X,
CONFIRMANDO_CONTINUAR, CONFIRMANDO_DEVOLVER
};
EstadoSistema estadoAtual = CALIBRANDO_Y;
// ======================== STORAGE (EEPROM) ========================
#define EEPROM_SIZE 1024
#define MAX_USERS 10
struct {
char master_pass[5]; // 4 dígitos + \0
uint8_t num_users;
char users[MAX_USERS][12];
} storage;
// Definiremos o endereço de ocupação logo após a struct (para usar sizeof(storage))
const int EEPROM_ADDR_OCUPACAO = sizeof(storage); // endereco onde começa array de ocupacao na EEPROM
// ======================== OBJETOS ========================
AccelStepper motorY(AccelStepper::DRIVER, Y_STEP, Y_DIR);
AccelStepper motorZ(AccelStepper::DRIVER, Z_STEP, Z_DIR);
AccelStepper motorX(AccelStepper::DRIVER, X_STEP, X_DIR);
// ======================== CONFIGURAÇÃO DE POSIÇÕES OCUPADAS ========================
// Lista de posições que devem começar ocupadas APENAS no primeiro uso (EEPROM zerada)
const int qtdPosicoesOcupadasInicial = sizeof(posicoesOcupadasInicial) / sizeof(posicoesOcupadasInicial[0]);
// Array que indica se cada posição está ocupada (true) ou vazia (false)
bool posOcupada[MAX_POS]; // Será carregada/salva no EEPROM
int adminOption = 0;
int lastOption = 0;
String inputBuf;
int opcaoMenu = 1; // 1 = cima, 2 = baixo
String numeroDigitado;
bool calibrado = false;
bool menuDesenhado = false;
int eixoX = 0, eixoZ = 0;
bool sireneHabilitada = false;
bool sireneLigada = true;
int confirmOption = 0; // 0 = Sim, 1 = Nao
int lastConfirmOption = 0;
bool confirmMenuDesenhado = false;
String currentUser = ""; // CPF logado
bool currentIsMestre = false;
// ======================== PROTÓTIPOS ========================
void loadStorage();
void carregarOcupacao();
void salvarOcupacao();
void saveStorage();
bool isRegistered(const String &cpf);
void showAdminMenuInit();
void updateAdminArrow();
void updateMenuPrincipalArrow();
void handleAcesso();
void handleMaquina();
void ligarSirene() { digitalWrite(RELE_SIRENE, HIGH); }
void desligarSirene(){ digitalWrite(RELE_SIRENE, LOW); }
void handleBotaoSirene();
void delayComBotao(unsigned long ms);
long cmToPassos(float cm, char eixo);
void configurarVelocidadeAceleracao();
void moverEixoPara(AccelStepper &motor, long posAlvo);
char lerTecla();
void limparNumeroDigitado();
void mostrarMenuPrincipal();
void mostrarNumeroDigitado();
void mostrarErro(const char *msg);
void mostrarExecucao();
void mostrarCoordenadas();
void processoCalibracaoVoltarOrigem();
void pegarItem(float px, float pz, float py);
void guardarItem(float px, float pz, float py);
void showConfirmInit();
void updateConfirmArrow();
void showDevolverInit();
void updateDevolverArrow();
void mostrarBarraProgresso(int etapa, int totalEtapas);
void registrarAtividade();
void verificarInatividade();
// ----- EEPROM HELPERS -----
void loadStorage() {
EEPROM.begin(EEPROM_SIZE);
EEPROM.get(0, storage);
// Se EEPROM estiver vazia (0xFF), inicializa
if ((uint8_t)storage.master_pass[0] == 0xFF) {
strcpy(storage.master_pass, "1234");
storage.num_users = 0;
EEPROM.put(0, storage);
EEPROM.commit();
}
}
void saveStorage() {
EEPROM.put(0, storage);
EEPROM.commit();
}
// ----- FUNÇÕES DE OCUPAÇÃO -----
// Salva o estado atual das posições no EEPROM
void salvarOcupacao() {
for (int i = 0; i < MAX_POS; i++) {
EEPROM.update(EEPROM_ADDR_OCUPACAO + i, posOcupada[i] ? 1 : 0);
}
EEPROM.commit();
}
// Carrega o estado das posições do EEPROM ou inicializa
void carregarOcupacao() {
bool eepromVazia = true;
for (int i = 0; i < MAX_POS; i++) {
byte val = EEPROM.read(EEPROM_ADDR_OCUPACAO + i);
if (val != 0xFF) { // EEPROM já possui dados
eepromVazia = false;
break;
}
}
if (eepromVazia) {
// Inicializa todas vazias
for (int i = 0; i < MAX_POS; i++) posOcupada[i] = false;
// Marca as posições iniciais ocupadas
for (int j = 0; j < qtdPosicoesOcupadasInicial; j++) {
int pos = posicoesOcupadasInicial[j] - 1; // Ajuste para índice
if (pos >= 0 && pos < MAX_POS) posOcupada[pos] = true;
}
salvarOcupacao();
} else {
for (int i = 0; i < MAX_POS; i++) {
byte val = EEPROM.read(EEPROM_ADDR_OCUPACAO + i);
posOcupada[i] = (val == 1);
}
}
}
bool isRegistered(const String &cpf) {
for (uint8_t i = 0; i < storage.num_users; i++) {
if (cpf == storage.users[i]) return true;
}
return false;
}
// ----- MENU ADMIN -----
void showAdminMenuInit() {
lcd.clear();
lcd.setCursor(1,0); lcd.print("Novo CPF");
lcd.setCursor(1,1); lcd.print("Apagar CPF");
lastOption = adminOption;
lcd.setCursor(0, adminOption);
lcd.print(">");
}
void updateAdminArrow() {
lcd.setCursor(0, lastOption);
lcd.print(" ");
lcd.setCursor(0, adminOption);
lcd.print(">");
lastOption = adminOption;
}
// ----- MENU PRINCIPAL (sem flicker) -----
void updateMenuPrincipalArrow() {
// Remove seta antiga de forma segura
lcd.setCursor(0, (opcaoMenu == 1) ? 1 : 0);
lcd.print(" ");
// Adiciona seta nova
lcd.setCursor(0, (opcaoMenu == 1) ? 0 : 1);
lcd.print(">");
}
void mostrarMenuPrincipal() {
lcd.clear();
lcd.setCursor(1,0);
lcd.print("Pegar item");
lcd.setCursor(1,1);
if (currentIsMestre) lcd.print("Guardar item");
else lcd.print("Devolver item");
// Mostra seta inicial
lcd.setCursor(0, (opcaoMenu == 1) ? 0 : 1);
lcd.print(">");
}
// ----- TECLADO -----
char lerTecla() {
static char lastKey = '\0';
static unsigned long db = 0;
const unsigned long dbt = 25;
unsigned long now = millis();
// Se passou o tempo de debounce, libera a tecla anterior
if (now - db > dbt) lastKey = '\0';
for (byte r = 0; r < ROWS; r++) {
digitalWrite(rowPins[r], LOW);
for (byte c = 0; c < COLS; c++) {
if (digitalRead(colPins[c]) == LOW) {
char tecla = keysMap[r][c];
if (tecla != lastKey || now - db > dbt) {
lastKey = tecla;
db = now;
// Aguarda soltar a tecla para evitar múltiplas leituras
while (digitalRead(colPins[c]) == LOW);
digitalWrite(rowPins[r], HIGH);
// Atualiza tempo da última atividade
ultimoTempoAtividade = millis();
// Se a tela estava bloqueada, desbloqueia e volta pro login
if (telaBloqueada) {
telaBloqueada = false;
lcd.backlight();
// --- Força voltar para a tela de login ---
estadoGlobal = AGUARDANDO_LOGIN;
stateAcesso = ST_IDLE;
inputBuf = "";
currentUser = "";
currentIsMestre = false;
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0, 1);
}
return tecla;
}
}
}
digitalWrite(rowPins[r], HIGH);
}
// Nenhuma tecla pressionada
return '\0';
}
// ----- LCD HELPERS -----
void limparNumeroDigitado() {
numeroDigitado = "";
}
void mostrarNumeroDigitado() {
lcd.clear();
lcd.setCursor(0,0);
if (opcaoMenu==1) lcd.print("Pegar item:");
else {
if (currentIsMestre) lcd.print("Guardar item:");
else lcd.print("Devolver item:");
}
lcd.setCursor(0,1);
lcd.print(numeroDigitado);
for (int i=numeroDigitado.length(); i<16; i++) lcd.print(' ');
}
void mostrarErro(const char *msg) {
lcd.clear();
lcd.setCursor(0,0); lcd.print("Erro:");
lcd.setCursor(0,1); lcd.print(msg);
delayComBotao(2000);
mostrarNumeroDigitado();
}
void mostrarExecucao() {
lcd.clear();
lcd.setCursor(0,0);
if (opcaoMenu==1) lcd.print("Pegando item...");
else {
if (currentIsMestre) lcd.print("Guardando item...");
else lcd.print("Devolvendo...");
}
}
void mostrarCoordenadas() {
lcd.clear();
lcd.setCursor(0,0); lcd.print("Coordenadas:");
lcd.setCursor(0,1);
lcd.print("X:"); lcd.print(eixoX+1);
lcd.print(" Z:"); lcd.print(eixoZ+1);
}
// ----- BARRA DE PROGRESSO (otimizada) -----
void mostrarBarraProgresso(int etapa, int totalEtapas) {
static int lastBlocos = -1;
int blocos = map(etapa, 0, totalEtapas, 0, 16);
if (blocos == lastBlocos) return; // nada mudou -> não redesenhar
lastBlocos = blocos;
lcd.setCursor(0, 1);
for (int i = 0; i < 16; i++) {
lcd.print(i < blocos ? (char)0xFF : ' ');
}
}
// ----- HANDLER DE ACESSO -----
void handleAcesso() {
char key = lerTecla();
if (!key) return;
switch (stateAcesso) {
case ST_IDLE:
if (key == '#') {
if (inputBuf.length() == 0) {
stateAcesso = ST_ADMIN_PASS;
inputBuf = "";
lcd.clear();
lcd.print("Senha mestra:");
lcd.setCursor(0,1);
} else {
inputBuf.remove(inputBuf.length()-1);
lcd.setCursor(0,1); lcd.print(" ");
lcd.setCursor(0,1); lcd.print(inputBuf);
}
}
else if (key == '*') {
if (inputBuf.length() == 0) {
// nada
} else {
// aceitamos CPF cadastrado ou senha mestre para login
if (isRegistered(inputBuf) || inputBuf == String(storage.master_pass)) {
lcd.clear();
lcd.print("Bem-vindo!");
delay(800);
estadoGlobal = OPERANDO_MAQUINA;
if (inputBuf == String(storage.master_pass)) {
currentUser = String(storage.master_pass);
currentIsMestre = true;
} else {
currentUser = inputBuf;
currentIsMestre = false;
}
lcd.clear();
lcd.print("OK p/ calibrar.");
lcd.setCursor(0,1); lcd.print("Esperando...");
while (lerTecla() != '*') delay(10);
lcd.clear();
lcd.print("Calibrando Y");
ligarSirene();
estadoAtual = CALIBRANDO_Y;
calibrado = false;
menuDesenhado = false;
// registramos atividade quando o usuário entra no sistema
ultimoTempoAtividade = millis();
} else {
lcd.print("Senha invalida");
delay(1200);
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
inputBuf = "";
}
}
else if (key >= '0' && key <= '9' && inputBuf.length() < 11) {
inputBuf += key;
lcd.setCursor(inputBuf.length()-1,1);
lcd.print(key);
}
break;
case ST_ADMIN_PASS:
if (key == '#') {
if (inputBuf.length() == 0) {
stateAcesso = ST_IDLE;
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
} else {
inputBuf.remove(inputBuf.length()-1);
lcd.setCursor(0,1); lcd.print(" ");
lcd.setCursor(0,1);
for (uint8_t i=0; i<inputBuf.length(); i++) lcd.print('*');
}
}
else if (key == '*') {
if (inputBuf == storage.master_pass) {
stateAcesso = ST_ADMIN_MENU;
adminOption = 0;
showAdminMenuInit();
} else {
lcd.clear(); lcd.print("Senha errada");
delay(1200);
stateAcesso = ST_IDLE;
lcd.clear(); lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
inputBuf = "";
}
else if (key >= '0' && key <= '9' && inputBuf.length() < 4) {
inputBuf += key;
lcd.setCursor(inputBuf.length()-1,1);
lcd.print('*');
}
break;
case ST_ADMIN_MENU:
if (key == '#') {
adminOption = 1 - adminOption;
updateAdminArrow();
}
else if (key == '*') {
if (adminOption == 0) {
stateAcesso = ST_NEWCPF;
inputBuf = "";
lcd.clear(); lcd.print("Novo CPF:");
lcd.setCursor(0,1);
} else {
stateAcesso = ST_DELCPF;
inputBuf = "";
lcd.clear(); lcd.print("Apagar CPF:");
lcd.setCursor(0,1);
}
}
break;
case ST_NEWCPF:
if (key == '#') {
if (inputBuf.length() == 0) {
stateAcesso = ST_ADMIN_MENU;
showAdminMenuInit();
} else {
inputBuf.remove(inputBuf.length()-1);
lcd.setCursor(0,1); lcd.print(" ");
lcd.setCursor(0,1); lcd.print(inputBuf);
}
}
else if (key == '*') {
lcd.clear();
if (inputBuf.length()==11 &&
storage.num_users<MAX_USERS &&
!isRegistered(inputBuf))
{
inputBuf.toCharArray(storage.users[storage.num_users++], 12);
saveStorage();
lcd.print("Cadastrado!");
} else {
lcd.print("Erro cadastro");
}
delay(1200);
stateAcesso = ST_IDLE;
inputBuf = "";
lcd.clear(); lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
else if (key >= '0' && key <= '9' && inputBuf.length()<11) {
inputBuf += key;
lcd.setCursor(inputBuf.length()-1,1);
lcd.print(key);
}
break;
case ST_DELCPF:
if (key == '#') {
if (inputBuf.length()==0) {
stateAcesso = ST_ADMIN_MENU;
showAdminMenuInit();
} else {
inputBuf.remove(inputBuf.length()-1);
lcd.setCursor(0,1); lcd.print(" ");
lcd.setCursor(0,1); lcd.print(inputBuf);
}
}
else if (key == '*') {
lcd.clear();
int idx = -1;
for (uint8_t i=0; i<storage.num_users; i++) {
if (inputBuf == storage.users[i]) { idx = i; break; }
}
if (idx >= 0) {
for (uint8_t j=idx; j<storage.num_users-1; j++)
strcpy(storage.users[j], storage.users[j+1]);
storage.num_users--;
saveStorage();
lcd.print("Apagado!");
} else {
lcd.print("Nao encontrado");
}
delay(1200);
stateAcesso = ST_IDLE;
inputBuf = "";
lcd.clear(); lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
else if (key >= '0' && key <= '9' && inputBuf.length()<11) {
inputBuf += key;
lcd.setCursor(inputBuf.length()-1,1);
lcd.print(key);
}
break;
}
}
// ----- LOOP DA MÁQUINA -----
void handleMaquina() {
handleBotaoSirene();
if (sireneLigada);
// Verifica inatividade aqui (em todos os estados da máquina)
verificarInatividade();
// Se a verificação mudou o estado global para AGUARDANDO_LOGIN, sai do handler.
if (estadoGlobal == AGUARDANDO_LOGIN) return;
if (!calibrado) {
processoCalibracaoVoltarOrigem();
return;
}
// Estado de confirmação após ações (Continuar?)
if (estadoAtual == CONFIRMANDO_CONTINUAR) {
if (!confirmMenuDesenhado) {
showConfirmInit();
confirmMenuDesenhado = true;
}
char k = lerTecla();
if (k == '#') {
confirmOption = 1 - confirmOption;
updateConfirmArrow();
}
else if (k == '*') {
if (confirmOption == 0) {
estadoAtual = MENU_PRINCIPAL;
menuDesenhado = false;
} else {
estadoGlobal = AGUARDANDO_LOGIN;
stateAcesso = ST_IDLE;
inputBuf = "";
currentUser = "";
currentIsMestre = false;
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
confirmMenuDesenhado = false;
}
return;
}
// Estado de confirmação para devolução (Deseja devolver?)
if (estadoAtual == CONFIRMANDO_DEVOLVER) {
if (!confirmMenuDesenhado) {
showDevolverInit();
confirmMenuDesenhado = true;
}
char k = lerTecla();
if (k == '#') {
confirmOption = 1 - confirmOption;
updateDevolverArrow();
}
else if (k == '*') {
if (confirmOption == 0) {
// Usuário confirmou a devolução -> aciona relé
digitalWrite(RELAY_PIN, HIGH);
lcd.clear(); lcd.setCursor(0,0); lcd.print("Fechadura aberta");
delayComBotao(800);
digitalWrite(RELAY_PIN, LOW);
// Depois da devolução, pergunta se quer continuar
confirmMenuDesenhado = false;
confirmOption = 0; // reset
estadoAtual = CONFIRMANDO_CONTINUAR;
// Reinicia o timer de inatividade para que a tela "Deseja continuar?" apareça
registrarAtividade();
return;
} else {
// Não deseja devolver -> volta para menu principal
estadoAtual = MENU_PRINCIPAL;
menuDesenhado = false;
confirmMenuDesenhado = false;
// registrarAtividade para evitar timeout imediato
registrarAtividade();
}
}
return;
}
// Menu principal
if (estadoAtual == MENU_PRINCIPAL) {
if (!menuDesenhado) {
mostrarMenuPrincipal();
menuDesenhado = true;
}
char t = lerTecla();
if (t == '#') {
opcaoMenu = (opcaoMenu == 1) ? 2 : 1;
updateMenuPrincipalArrow(); // sem flicker
}
else if (t == '*') {
// Quando o usuário confirma a opção
// Se a opção inferior for "Devolver" para não-mestre, pedir confirmação primeiro
if (opcaoMenu == 2 && !currentIsMestre) {
estadoAtual = CONFIRMANDO_DEVOLVER;
confirmOption = 0;
confirmMenuDesenhado = false;
} else {
// Pegar ou Guardar (para mestre)
estadoAtual = DIGITANDO_NUMERO;
limparNumeroDigitado();
mostrarNumeroDigitado();
}
}
}
else if (estadoAtual == DIGITANDO_NUMERO) {
char t = lerTecla();
if (t == '*') {
if (numeroDigitado.length() == 0) {
mostrarErro("Num vazio");
} else {
int pos = numeroDigitado.toInt();
if (pos <= 0 || pos > MAX_POS) {
mostrarErro("Pos invalida");
} else {
int posIndex = pos - 1;
eixoX = (pos - 1) % NUM_COLUNAS;
eixoZ = (pos - 1) / NUM_COLUNAS;
mostrarCoordenadas();
delayComBotao(800);
float px = POS_X_APROX_CM + eixoX * DIST_COLUNAS_CM;
float pz = POS_Z_APROX_CM + eixoZ * DIST_LINHAS_CM;
// Verificações de ocupação ANTES de executar movimentos
if (opcaoMenu == 1) { // PEGAR
if (!posOcupada[posIndex]) {
mostrarErro("Local vazio");
// permanece em DIGITANDO_NUMERO para novo input
mostrarNumeroDigitado();
return;
} else {
// marcar vazio após pegar
pegarItem(px, pz, AVANCO_GARFO_CM);
posOcupada[posIndex] = false;
salvarOcupacao();
}
} else { // GUARDAR (apenas mestre chega aqui)
if (posOcupada[posIndex]) {
mostrarErro("Local ocupado");
mostrarNumeroDigitado();
return;
} else {
guardarItem(px, pz, AVANCO_GARFO_CM);
posOcupada[posIndex] = true;
salvarOcupacao();
}
}
}
}
}
else if (t == '#') {
if (numeroDigitado.length() == 0) {
estadoAtual = MENU_PRINCIPAL;
menuDesenhado = false;
lcd.clear(); lcd.print("Cancelado!");
delayComBotao(600);
} else {
numeroDigitado.remove(numeroDigitado.length() - 1);
mostrarNumeroDigitado();
}
}
else if (t >= '0' && t <= '9') {
if (numeroDigitado.length() < MAX_DIG) {
numeroDigitado += t;
mostrarNumeroDigitado();
}
}
}
}
void handleBotaoSirene() {
static bool lastRead = LOW, btnState = LOW;
static unsigned long db = 0;
const unsigned long dbt = 10;
bool leitura = digitalRead(botaoSirenePin);
if (leitura != lastRead) db = millis();
if ((millis() - db > dbt) && leitura != btnState) {
btnState = leitura;
if (btnState == HIGH) {
sireneHabilitada = !sireneHabilitada;
if (sireneHabilitada) ligarSirene();
else desligarSirene();
}
}
lastRead = leitura;
}
void delayComBotao(unsigned long ms) {
unsigned long t0 = millis();
while (millis() - t0 < ms) {
handleBotaoSirene();
if (sireneLigada) ;
// chamar verificarInatividade aqui poderia causar logout durante movimento;
// então NÃO chamamos verificarInatividade() dentro desse delay bloqueante.
}
}
// ======================== MOVIMENTO ========================
long cmToPassos(float cm, char eixo) {
if (eixo == 'X') return cm * PASSOS_POR_CM_X;
if (eixo == 'Y') return cm * PASSOS_POR_CM_Y;
if (eixo == 'Z') return cm * PASSOS_POR_CM_Z;
return 0;
}
void configurarVelocidadeAceleracao() {
motorX.setMaxSpeed(VEL_MAX_X * PASSOS_POR_CM_X);
motorX.setAcceleration(ACEL_X * PASSOS_POR_CM_X);
motorY.setMaxSpeed(VEL_MAX_Y * PASSOS_POR_CM_Y);
motorY.setAcceleration(ACEL_Y * PASSOS_POR_CM_Y);
motorZ.setMaxSpeed(VEL_MAX_Z * PASSOS_POR_CM_Z);
motorZ.setAcceleration(ACEL_Z * PASSOS_POR_CM_Z);
}
void moverEixoPara(AccelStepper &motor, long posAlvo) {
motoresEmMovimento = true; // indica que motor está em movimento
motor.moveTo(posAlvo);
while (motor.distanceToGo() != 0) {
motor.run();
handleBotaoSirene();
if (sireneLigada) ;
// enquanto estiver movendo, garantimos que inatividade não desligue a tela
ultimoTempoAtividade = millis();
}
motoresEmMovimento = false; // movimento finalizado
}
// ======================== CALIBRAÇÃO ========================
void homingDoisEstagios(AccelStepper &motor, char eixo, int pinoMicro) {
// Etapa 1 – aproximação rápida até acionar o microswitch
motor.setMaxSpeed(HOMING_VEL_RAPIDA * cmToPassos(1, eixo));
motor.setSpeed(-HOMING_VEL_RAPIDA * cmToPassos(1, eixo));
while (digitalRead(pinoMicro) == LOW) { // Continua até acionar
motor.runSpeed();
handleBotaoSirene();
if (sireneLigada) ;
ultimoTempoAtividade = millis();
}
motor.stop();
delay(50); // evita falsos acionamentos
// Recuo
moverEixoPara(motor, motor.currentPosition() + cmToPassos(HOMING_RECUO_CM, eixo));
// Etapa 2 – aproximação lenta até acionar novamente
motor.setSpeed(-HOMING_VEL_LENTA * cmToPassos(1, eixo)); // Velocidade lenta real
while (digitalRead(pinoMicro) == LOW) {
motor.runSpeed();
handleBotaoSirene();
if (sireneLigada) ;
ultimoTempoAtividade = millis();
}
motor.stop();
delay(50);
motor.setCurrentPosition(0);
}
void processoCalibracaoVoltarOrigem() {
handleBotaoSirene();
if (sireneLigada) ;
static char ultimoEixo = '\0';
char eixoAtual = '\0';
switch (estadoAtual) {
case CALIBRANDO_Y:
case VOLTANDO_Y:
eixoAtual = 'Y';
if (eixoAtual != ultimoEixo) {
lcd.setCursor(0, 0);
lcd.print((estadoAtual == CALIBRANDO_Y) ? "Calibrando Y" : "Voltando Y");
lcd.print(" ");
ultimoEixo = eixoAtual;
}
homingDoisEstagios(motorY, 'Y', MICRO_Y);
estadoAtual = (estadoAtual == CALIBRANDO_Y ? CALIBRANDO_Z : VOLTANDO_Z);
break;
case CALIBRANDO_Z:
case VOLTANDO_Z:
eixoAtual = 'Z';
if (eixoAtual != ultimoEixo) {
lcd.setCursor(0, 0);
lcd.print((estadoAtual == CALIBRANDO_Z) ? "Calibrando Z" : "Voltando Z");
lcd.print(" ");
ultimoEixo = eixoAtual;
}
homingDoisEstagios(motorZ, 'Z', MICRO_Z);
estadoAtual = (estadoAtual == CALIBRANDO_Z ? CALIBRANDO_X : VOLTANDO_X);
break;
case CALIBRANDO_X:
case VOLTANDO_X:
eixoAtual = 'X';
if (eixoAtual != ultimoEixo) {
lcd.setCursor(0, 0);
lcd.print((estadoAtual == CALIBRANDO_X) ? "Calibrando X" : "Voltando X");
lcd.print(" ");
ultimoEixo = eixoAtual;
}
homingDoisEstagios(motorX, 'X', MICRO_X);
// >>> Vai para posição de descanso após homing X
moverParaPosicaoDescansoComExtra();
if (estadoAtual == CALIBRANDO_X) {
calibrado = true;
desligarSirene();
lcd.clear();
lcd.print("Calibrado!");
delayComBotao(500);
}
estadoAtual = MENU_PRINCIPAL;
menuDesenhado = false;
break;
}
}
// ======================== AÇÕES ========================
void pegarItem(float px, float pz, float py) {
mostrarExecucao();
ligarSirene();
int etapa = 0;
const int totalEtapas = 8;
// Garante aproximação (Y -> X -> Z) + pausa para verificação
moverEixoPara(motorY, cmToPassos(POS_Y_APROX_CM, 'Y'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorX, cmToPassos(POS_X_APROX_CM, 'X'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(POS_Z_APROX_CM, 'Z'));
mostrarBarraProgresso(++etapa, totalEtapas);
delayComBotao(2000); // pausa de segurança
mostrarBarraProgresso(++etapa, totalEtapas);
// >>> Sequência correta a partir da APROXIMACAO: X -> Z -> Y -> Z+extra
moverEixoPara(motorX, cmToPassos(px, 'X'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(pz, 'Z'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorY, cmToPassos(py, 'Y'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(pz + ALT_DESGRUDAR_CM, 'Z')); // levantar
mostrarBarraProgresso(++etapa, totalEtapas);
desligarSirene();
// Retorno para descanso (seu fluxo atual volta via estados/homing)
estadoAtual = VOLTANDO_Y;
while (estadoAtual != MENU_PRINCIPAL) {
processoCalibracaoVoltarOrigem();
}
desligarSirene();
estadoAtual = CONFIRMANDO_CONTINUAR;
confirmOption = 0;
confirmMenuDesenhado = false;
registrarAtividade();
}
void guardarItem(float px, float pz, float py) {
mostrarExecucao();
ligarSirene();
int etapa = 0;
const int totalEtapas = 8;
// Garante aproximação (Y -> X -> Z) + pausa para verificação
moverEixoPara(motorY, cmToPassos(POS_Y_APROX_CM, 'Y'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorX, cmToPassos(POS_X_APROX_CM, 'X'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(POS_Z_APROX_CM, 'Z'));
mostrarBarraProgresso(++etapa, totalEtapas);
delayComBotao(2000); // pausa de segurança
mostrarBarraProgresso(++etapa, totalEtapas);
// >>> Sequência correta a partir da APROXIMACAO: X -> Z+extra -> Y -> Z
moverEixoPara(motorX, cmToPassos(px, 'X'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(pz + ALT_DESGRUDAR_CM, 'Z')); // sobe um pouco
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorY, cmToPassos(py, 'Y'));
mostrarBarraProgresso(++etapa, totalEtapas);
moverEixoPara(motorZ, cmToPassos(pz, 'Z')); // desce para guardar
mostrarBarraProgresso(++etapa, totalEtapas);
desligarSirene();
// Retorno para descanso (seu fluxo atual volta via estados/homing)
estadoAtual = VOLTANDO_Y;
while (estadoAtual != MENU_PRINCIPAL) {
processoCalibracaoVoltarOrigem();
}
desligarSirene();
estadoAtual = CONFIRMANDO_CONTINUAR;
confirmOption = 0;
confirmMenuDesenhado = false;
registrarAtividade();
}
// ======================== CONFIRMAÇÃO ========================
void showConfirmInit() {
lcd.clear();
lcd.setCursor(0,0); lcd.print("Deseja continuar?");
lcd.setCursor(0,1);
lcd.print(">Sim Nao");
lastConfirmOption = confirmOption;
}
void updateConfirmArrow() {
// Remove setas antigas
lcd.setCursor(0, 1); lcd.print(" ");
lcd.setCursor(5, 1); lcd.print(" ");
// Adiciona nova seta
if (confirmOption == 0) {
lcd.setCursor(0, 1); // Seta antes do "Sim"
lcd.print(">");
} else {
lcd.setCursor(5, 1); // Seta antes do "Nao"
lcd.print(">");
}
}
void showDevolverInit() {
lcd.clear();
lcd.setCursor(0,0); lcd.print("Deseja devolver?");
lcd.setCursor(0,1);
lcd.print(">Sim Nao");
lastConfirmOption = confirmOption;
}
void updateDevolverArrow() {
// Remove setas antigas
lcd.setCursor(0, 1); lcd.print(" ");
lcd.setCursor(5, 1); lcd.print(" ");
// Adiciona nova seta
if (confirmOption == 0) {
lcd.setCursor(0, 1); // Seta antes do "Sim"
lcd.print(">");
} else {
lcd.setCursor(5, 1); // Seta antes do "Nao"
lcd.print(">");
}
}
// ======== SAIR DA POSIÇÃO DE DESCANSO COM ALTURA EXTRA (Guardar) ========
// Sequência: Z sobe altura extra -> Y -> X -> Z aproximação
void sairDaPosicaoDescansoComExtra() {
moverEixoPara(motorZ, cmToPassos(POS_DESCANSO_Z_CM + ALT_DESGRUDAR_CM, 'Z'));
moverEixoPara(motorY, cmToPassos(POS_DESCANSO_Y_CM, 'Y'));
moverEixoPara(motorX, cmToPassos(POS_DESCANSO_X_CM, 'X'));
moverEixoPara(motorZ, cmToPassos(POS_DESCANSO_Z_CM,'Z')); // aproximação final
}
// ======== VOLTAR PARA POSIÇÃO DE DESCANSO COM ALTURA EXTRA (Pegar/padrão) ========
// Sequência: X -> Z+extra -> Y -> Z descanso
void moverParaPosicaoDescansoComExtra() {
moverEixoPara(motorX, cmToPassos(POS_DESCANSO_X_CM, 'X'));
moverEixoPara(motorZ, cmToPassos(POS_DESCANSO_Z_CM + ALT_DESGRUDAR_CM, 'Z'));
moverEixoPara(motorY, cmToPassos(POS_DESCANSO_Y_CM, 'Y'));
moverEixoPara(motorZ, cmToPassos(POS_DESCANSO_Z_CM, 'Z'));
}
void moverParaPosicaoComAproximacao(float destinoX, float destinoY, float destinoZ) {
// 1. Vai para posição de aproximação (Y -> X -> Z)
moverEixoPara(motorY, cmToPassos(POS_Y_APROX_CM, 'Y'));
while (motorY.distanceToGo() != 0) motorY.run();
moverEixoPara(motorX, cmToPassos(POS_X_APROX_CM, 'X'));
while (motorX.distanceToGo() != 0) motorX.run();
moverEixoPara(motorZ, cmToPassos(POS_Z_APROX_CM, 'Z'));
while (motorZ.distanceToGo() != 0) motorZ.run();
// 2. Espera 2 segundos
delay(2000);
// 3. Vai para posição final (Y -> X -> Z)
moverEixoPara(motorY, cmToPassos(destinoY, 'Y'));
while (motorY.distanceToGo() != 0) motorY.run();
moverEixoPara(motorX, cmToPassos(destinoX, 'X'));
while (motorX.distanceToGo() != 0) motorX.run();
moverEixoPara(motorZ, cmToPassos(destinoZ, 'Z'));
while (motorZ.distanceToGo() != 0) motorZ.run();
}
// ======================== SETUP ========================
void setup() {
Serial.begin(9600);
Wire.setSDA(LCD_SDA);
Wire.setSCL(LCD_SCL);
lcd.init();
lcd.backlight();
for (byte i = 0; i < ROWS; i++) {
pinMode(rowPins[i], OUTPUT);
digitalWrite(rowPins[i], HIGH);
}
for (byte j = 0; j < COLS; j++) {
pinMode(colPins[j], INPUT_PULLUP);
}
pinMode(MICRO_Y, INPUT);
pinMode(MICRO_Z, INPUT);
pinMode(MICRO_X, INPUT);
pinMode(botaoSirenePin, INPUT);
pinMode(RELE_SIRENE, OUTPUT);
digitalWrite(RELE_SIRENE, LOW); // sirene desligada no boot
pinMode(RELAY_PIN, OUTPUT);
digitalWrite(RELAY_PIN, LOW);
configurarVelocidadeAceleracao();
loadStorage();
carregarOcupacao();
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
// inicializa timer de atividade para evitar timeout imediato
ultimoTempoAtividade = millis();
telaBloqueada = false;
}
// ======================== INATIVIDADE (implementação) ========================
// --- NUNCA bloquear por inatividade durante calibração/retorno ---
static inline bool emCalibracaoOuRetorno() {
return (estadoAtual == CALIBRANDO_Y || estadoAtual == CALIBRANDO_Z || estadoAtual == CALIBRANDO_X ||
estadoAtual == VOLTANDO_Y || estadoAtual == VOLTANDO_Z || estadoAtual == VOLTANDO_X);
}
void registrarAtividade() {
ultimoTempoAtividade = millis();
if (telaBloqueada) {
telaBloqueada = false;
lcd.backlight();
lcd.clear();
lcd.print("Desbloqueado");
delay(500);
lcd.clear();
// Redesenhar menu/tela na próxima iteração
menuDesenhado = false;
}
}
void verificarInatividade() {
// Durante MOVIMENTO ou CALIBRAÇÃO/VOLTA, não bloquear nem apagar backlight
if (motoresEmMovimento || emCalibracaoOuRetorno()) {
ultimoTempoAtividade = millis();
return;
}
if (!telaBloqueada && millis() - ultimoTempoAtividade >= TEMPO_BLOQUEIO_MS) {
telaBloqueada = true;
lcd.noBacklight();
estadoGlobal = AGUARDANDO_LOGIN;
stateAcesso = ST_IDLE;
inputBuf = "";
currentUser = "";
currentIsMestre = false;
lcd.clear();
lcd.print("Tela bloqueada");
delay(500);
lcd.clear();
lcd.print("Senha (CPF):");
lcd.setCursor(0,1);
}
} // <– Aqui termina verificarInatividade()
// ======================== LOOP ========================
void loop() {
if (estadoGlobal == AGUARDANDO_LOGIN) {
handleAcesso();
} else {
handleMaquina();
}
// checa inatividade sempre (aplicável em login e operando)
verificarInatividade();
}
Y
Y