Week summary
Our group developed BIOCRUSHER, a semi-automated bio-machine designed to process Amazonian fibers for bio-paper and biomaterial experimentation. The machine includes a controlled iris inlet, a safety door interlock, a counter-rotating blade mechanism, DC motor actuation, NEMA stepper motors for material collection movement, an ESP32 control system and a Nextion touchscreen interface.
The project began with collaborative brainstorming and workflow definition. The team identified local fibers such as cassava, coconut, banana and pineapple as potential materials for bio-paper production. The machine focuses on the first step of the process: cutting and reducing fibers into smaller pieces before cooking, blending, sheet formation, pressing and drying.
Quick data
- Machine: BIOCRUSHER / BIO SHREDDER
- Topic: Mechanical Design + Machine Design
- Application: Amazonian fibers for bio-paper production
- Mechanism: Iris inlet + counter-rotating shredding blades, DC motor and NEMA stepper motors, ESP32, sensors, motor drivers and Nextion HMI
- Student: Carmen Elena Gutierrez Apolinario, Esteban M. Valladares, Jianfranco Bazan J., Mario Chong, Rocio Maravi, Grace Schwan, Cindy Marilyn Crispin.
General Flyer
General Video
Assignment requirements and evidence
| Fab Academy requirement | How BIOCRUSHER addresses it | Evidence to include |
|---|---|---|
| Design a machine with mechanism | Counter-rotating shredding blade matrix, iris inlet, rails and container displacement system. | CAD screenshots, exploded view and blade assembly photos. |
| Include actuation | DC motor drives the shredding blades; NEMA motors move the rails and receiving container. | Motor tests, driver wiring and motion videos. |
| Include automation | ESP32 controls motors, sensors, timing, HMI commands and safety conditions. | Code, serial monitor, HMI screen and system tests. |
| Include application | Processing Amazonian fibers for biomaterials and bio-paper production. | Fiber tests, shredded material and bio-paper workflow. |
| Build mechanical parts and operate manually | The blade system, chassis, iris mechanism and container movement were assembled and first tested manually. | Manual operation photos and videos. |
| Actuate and automate the machine | The machine was integrated with drivers, sensors, Nextion interface and control logic. | Automated test videos and final demo. |
Team planning and task allocation
The team divided responsibilities according to mechanical design, electronics, programming, material testing and documentation. Each member contributed to the group result and linked their individual page to the group page.
| Team member | Main responsibility | Design thinking focus | Individual page link |
|---|---|---|---|
| Esteban Valladares | Mechanical design, modeling, machine operability and fabrication | Ideate, Prototype, Test | link |
| Carmen Gutierrez | Mechanical design, modeling and CAD support | Ideate, Prototype | Link |
| Jianfranco Bazan | Electronics, PCB, drivers and programming | Ideate, Prototype, Test | Link |
| Rocio Maravi | Electronics, stepper motor tests, Nextion HMI interface and documentation support | All phases: record, log, prototype and test | Link |
| Cindy Crispin | Research, local fiber selection and material testing | Empathize, Define, Test | Link |
| Grace Schwan | Technical documentation, photography and project log | All phases: record and log | Add link |
| Mario Chong | Technical documentation, photography and VS Code documentation | All phases: record and log | Link |
Inspiration
The BIOCRUSHER project was inspired by the traditional knowledge and practices of local communities that work with natural fibers and biomaterials. These communities transform organic resources into useful products such as handmade paper, crafts and sustainable materials, demonstrating a strong connection between technology, nature and culture.
From a technical perspective, the design was also influenced by different mechanical systems. The shredding mechanism was inspired by paper shredders, which use interlocking blades to reduce material size efficiently. Additionally, the idea of continuous material flow and controlled feeding was influenced by industrial food machines, such as pizza preparation systems, where materials move in a guided and organized process.
Another important aspect of this project was the collaborative nature of the team. For this assignment, team members came together from different cities and regions of Peru, including Satipo, Madre de Dios, Lima and Huaral. This diversity enriched the design process by bringing different perspectives, experiences and ideas into the development of the machine.
The combination of traditional inspiration, industrial references and collaborative work allowed the team to develop a machine that connects local knowledge with digital fabrication and modern engineering.
Sources of inspiration
Figure 1. Local communities working with natural fibers and biomaterials.
Figure 2. Traditional fiber processing techniques used for handmade materials.
Figure 3. Paper shredder mechanism inspiring the cutting system design.
Figure 4. Industrial pizza machine inspiring continuous material flow.
Figure 5. Mechanical systems with guided motion used as reference.
Figure 6. Team collaboration across regions: Satipo, Madre de Dios, Lima and Huaral.
Five-phase design thinking process
1. Empathize
We researched local fibers and sustainable fabrication needs for accessible biomaterial production.
2. Define
We defined the machine as a fiber shredder for the bio-paper workflow and safety-driven operation.
3. Ideate
We sketched mechanisms, discussed blade geometry, and planned electronics and HMI interaction.
4. Prototype
We fabricated the chassis, blade supports, gears, interface, PCB and rail motion system.
5. Test
We validated motion, safety logic, sensor response, material shredding and improvement opportunities.
Goal
The goal was to build a semi-automated bio-machine capable of cutting and reducing Amazonian fibers into smaller particles for bio-paper and biomaterial experimentation. The system had to be safe, modular, replicable and suitable for digital fabrication.
Application
BIOCRUSHER supports the first stage of bio-paper production by cutting fibers into small pieces. After shredding, the fibers can be cooked with ash or alkaline solution, blended with water, formed into sheets, pressed and dried.
System design
The machine integrates a controlled material inlet, safety door, shredding chamber, motor actuation, axis movement, receiving container and HMI interface.
Fiber input
↓
Iris inlet mechanism
↓
Safety door verification
↓
Counter-rotating shredding blades
↓
Receiving container
↓
Rail movement using NEMA motors
↓
Material delivery
↓
Bio-paper processNextion HMI
↓ Serial UART
ESP32 controller
↓
Motor drivers
↓
DC motor + NEMA motors
↓
Sensors feedback
↓
Safe automated operationMachine operation
The BIOCRUSHER works as a semi-automated fiber processing system. The user places the biomaterial into the input area. The machine has an iris mechanism that opens and closes to regulate the amount of material entering the shredding chamber. This iris system is connected to the safety logic of the machine, because the machine is allowed to operate only when the protective door is closed.
When the door sensor confirms that the door is closed, the ESP32 enables the operating sequence. The DC motor activates the blade shafts, which cut and shred the fiber. The speed can be adjusted according to the selected fiber type. Softer fibers can use a lower voltage or lower PWM value, while harder fibers can use a higher value to increase shaft speed and torque response.
After the fiber is shredded, the material falls into a receiving container. This container is moved by a rail system controlled by NEMA stepper motors. The system moves the container downward to receive the shredded material and then forward to deliver the processed output. Sensors can indicate whether the container is full or empty, and the Nextion screen displays the current process time, machine status, safety status and container condition.
Nextion HMI Interface
Crusher Control Screen
The Nextion HMI interface was designed as the main control panel of the BIOCRUSHER machine. It allows the user to monitor the machine status and control the main operating elements in a simple and visual way.
The screen includes indicators for the motor, safety door, iris mechanism and receiving cup. The motor section displays the current motor value and percentage, while the door section shows if the safety door is closed or open. The machine is programmed to operate only when the door is closed.
The iris section shows the opening state of the feeding mechanism, which controls how much biomaterial enters the shredding chamber. The cup indicator helps the operator know when the container must be removed or replaced after receiving shredded material.
- Motor: shows motor activity and speed percentage.
- Door: displays the safety door condition.
- Iris: monitors the biomaterial inlet mechanism.
- Cup: indicates when the receiving container must be removed.
Electronic components and estimated cost
The electronics subsystem includes the controller, HMI display, motor drivers, sensors, power supply and communication modules used to actuate and monitor the machine. The cost table is shown in US dollars as an estimated reference.
| ID | Category | Component | Qty | Estimated unit cost (USD) | Description |
|---|---|---|---|---|---|
| ITM-001 | Electronics / HMI | Nextion 3.5" touchscreen display | 1 | $86.50 | Serial HMI touchscreen used as the main interface of the machine. |
| ITM-002 | Electronics / HMI | FT232BL Mini USB converter 3.3V / 5V | 1 | $3.65 | USB-to-serial adapter used to program or communicate with the Nextion display. |
| ITM-003 | Electronics / Communication | Bidirectional logic level converter 5V to 3.3V | 2 | $1.10 | TTL level converter used to adapt serial communication levels. |
| ITM-004 | Power / DC Motor | IBT-2 / BTS7960 driver | 1 | $13.00 | High-current H-bridge driver for DC motor speed and direction control. |
| ITM-005 | Power | 12V 15A power supply | 1 | $39.20 | Main power supply for actuators and peripherals. |
| ITM-006 | Controller | ESP32 development board | 1 | $8.00 | Main controller for sensors, motors, HMI communication and automation logic. |
| ITM-007 | Motion | NEMA stepper motor | 2 | $12.00 | Stepper motors used for the rail and receiving container displacement system. |
| ITM-008 | Motion driver | DRV8825 stepper driver | 2 | $3.00 | Driver modules for stepper motor speed, direction and microstepping control. |
| ITM-009 | Actuation | DC motor | 1 | $10.00 | Motor used to drive the shredding shafts and blade system. |
| ITM-010 | Safety | Door safety sensor | 1 | $2.00 | Sensor used to allow operation only when the protective door is closed. |
| ITM-011 | Motion / Safety | Limit switches | 4 | $1.00 | Detect end positions of axes, rails and moving mechanisms. |
| ITM-012 | Detection | Container full / empty sensor | 1 | $2.00 | Detects whether the receiving container is empty or full. |
| ITM-013 | Wiring | Wires, terminals and connectors | Various | $5.00 | Electrical interconnection between the controller, drivers, sensors and actuators. |
Mechanical design and fabrication
The mechanical system is based on two counter-rotating blade shafts. Each shaft contains repeated blade units arranged as a modular matrix to cut fibers efficiently. The team modeled the parts in CAD, validated the assembly and fabricated structural supports using digital fabrication processes such as 3D printing, laser cutting and CNC machining.
Shredding blade matrix
The cutting mechanism uses intermeshed blade stacks assembled on shafts. This system reduces fiber size by pulling and cutting the material as the shafts rotate.
Chassis and supports
The main structure includes MDF or acrylic panels, aluminum profiles, 3D printed supports, bearing blocks and motor mounting parts.
Mechanical fabrication gallery
Defining the product and determining the critical steps in the production of biomaterials.
We chose the critical step, which is the crushing of the fiber for the production of biomaterials.
A modular design is chosen with the idea that each floor fulfills a function for a critical step in the production of biomaterials.
Dual-shaft shredding system composed of intermeshing blade discs mounted on parallel shafts. This mechanism enables efficient cutting and size reduction of fibrous biomaterials through continuous rotation and shear action.
Mecanismo de engranajes impreso en 3D utilizado para transmitir movimiento rotacional dentro de la máquina..
Linear motion system using two stepper motors: one controls vertical movement along the Z-axis, while the second moves the collection tray along the X-axis.
Demonstration of the use of gears for rotating the shredding blades.
Operation of the DC motor that will rotate the shredding blades.
Functional test of the door security magnetic sensor.
Programming and control logic
The control logic was programmed using Arduino IDE for the ESP32. The code manages the safety door, material selection, motor speed, iris mechanism, shredding time, container movement and status messages sent to the Nextion HMI.
#include
#include
// =====================================================
// PROTOCOLO NEXTION / ESP32
// =====================================================
// Nextion -> ESP32
// \n
// motorPct: 0..100
// dir: 0 = CRUSH, 1 = REVERSE
// irisPct: 0..100
//
// \n -> REMOVE CUP (pulso/evento)
// \n -> RETURN CUP (pulso/evento)
//
// ESP32 -> Nextion
// SOLO comandos válidos de Nextion ASCII + 0xFF 0xFF 0xFF
// Ejemplo mínimo:
// vaDoor.val=0 -> puerta cerrada
// vaDoor.val=1 -> puerta abierta
// =====================================================
// PINES
// =====================================================
// --- Motor DC con IBT-2 ---
const uint8_t PIN_RPWM = 13;
const uint8_t PIN_LPWM = 14;
// --- Sensor de puerta ---
const uint8_t PIN_PUERTA = 27;
const bool PUERTA_CERRADA_NIVEL = LOW;
// --- Servo compuerta / iris ---
const uint8_t PIN_SERVO = 26;
// --- Stepper 1 (DRV8825) ---
// Eje Z (recorrido corto, final de carrera 1)
const uint8_t M1_STEP_PIN = 18;
const uint8_t M1_DIR_PIN = 19;
const uint8_t M1_LIMIT_PIN = 32;
// --- Stepper 2 (DRV8825) ---
// Eje Y (recorrido largo, final de carrera 2)
const uint8_t M2_STEP_PIN = 21;
const uint8_t M2_DIR_PIN = 22;
const uint8_t M2_LIMIT_PIN = 33;
// --- Nextion UART ---
const uint8_t NEXTION_RX_PIN = 23; // ESP32 RX <- TX Nextion
const uint8_t NEXTION_TX_PIN = 25; // ESP32 TX -> RX Nextion
const uint32_t NEXTION_BAUD = 9600;
// UART2 para Nextion
HardwareSerial NextionSerial(2);
// =====================================================
// CALIBRACION FINAL
// =====================================================
bool SERVO_AUMENTAR_ANGULO_ABRE = false;
int SERVO_ANGULO_CERRADO = 180;
int SERVO_ANGULO_ABIERTO = 0;
const bool LIMIT1_ACTIVE_LEVEL = LOW;
const bool LIMIT2_ACTIVE_LEVEL = LOW;
int8_t M1_HOME_DIR = 1;
int8_t M2_HOME_DIR = 1;
// =====================================================
// MICROSTEPPING 1/16
// =====================================================
const long MICROSTEP_FACTOR = 16;
// Valores calibrados originalmente en paso completo
const long M1_RANGE_STEPS_FULL_BASE = 700;
const long M2_RANGE_STEPS_FULL_BASE = 3600;
const long M2_RETURN_CUP_Y_STEPS_FULL_BASE = 300;
// Escalados
long M1_RANGE_STEPS = M1_RANGE_STEPS_FULL_BASE * MICROSTEP_FACTOR; // 11200
long M2_RANGE_STEPS = M2_RANGE_STEPS_FULL_BASE * MICROSTEP_FACTOR; // 57600
long M2_RETURN_CUP_Y_STEPS = M2_RETURN_CUP_Y_STEPS_FULL_BASE * MICROSTEP_FACTOR; // 5760
// =====================================================
// CONFIG PWM MOTOR DC
// =====================================================
const uint32_t PWM_FREQ_MOTOR = 20000;
const uint8_t PWM_RES_MOTOR = 8;
const uint16_t PWM_MAX_MOTOR = (1 << PWM_RES_MOTOR) - 1;
// =====================================================
// CONFIG PWM SERVO
// =====================================================
const uint32_t PWM_FREQ_SERVO = 50;
const uint8_t PWM_RES_SERVO = 16;
const uint32_t PWM_MAX_SERVO = (1UL << PWM_RES_SERVO) - 1;
const uint32_t SERVO_PERIODO_US = 20000;
int SERVO_MIN_US = 500;
int SERVO_MAX_US = 2500;
// Servo un poco más rápido que antes, pero aún suave
unsigned long INTERVALO_SERVO_MS = 25;
int PASO_SERVO = 1;
// =====================================================
// MOTOR DC / PUERTA
// =====================================================
unsigned long TIEMPO_CAMBIO_SENTIDO_MS = 1000;
unsigned long INTERVALO_RAMPA_MS = 20;
uint8_t PASO_RAMPA = 2;
unsigned long DEBOUNCE_PUERTA_MS = 60;
unsigned long INTERVALO_REPORTE_MS = 1000;
// =====================================================
// CONFIG STEPPERS CON ACCELSTEPPER
// MÁS LENTO PARA EVITAR PÉRDIDA DE PASOS
// =====================================================
const float M1_MAX_SPEED = 400.0f * MICROSTEP_FACTOR; // 6400
const float M2_MAX_SPEED = 400.0f * MICROSTEP_FACTOR; // 6400
const float M1_ACCEL = 700.0f * MICROSTEP_FACTOR; // 11200
const float M2_ACCEL = 700.0f * MICROSTEP_FACTOR; // 11200
// Homing normal
const float M1_HOME_FAST_SPEED = 120.0f * MICROSTEP_FACTOR; // 1920
const float M2_HOME_FAST_SPEED = 120.0f * MICROSTEP_FACTOR; // 1920
const float M1_HOME_SLOW_SPEED = 40.0f * MICROSTEP_FACTOR; // 640
const float M2_HOME_SLOW_SPEED = 40.0f * MICROSTEP_FACTOR; // 640
const float M1_HOME_BACKOFF_SPEED = 80.0f * MICROSTEP_FACTOR; // 1280
const float M2_HOME_BACKOFF_SPEED = 80.0f * MICROSTEP_FACTOR; // 1280
// Homing de arranque aún más silencioso
const float STARTUP_HOME_FAST_SPEED = 90.0f * MICROSTEP_FACTOR; // 1440
const float STARTUP_HOME_SLOW_SPEED = 30.0f * MICROSTEP_FACTOR; // 480
const float STARTUP_HOME_BACKOFF_SPEED = 60.0f * MICROSTEP_FACTOR; // 960
const long HOME_SEARCH_STEPS = 200000L;
const long HOME_RELEASE_MAX_STEPS = 5000L;
// Si inviertes esto, recalibra homeDir
bool M1_INVERT_DIR = false;
bool M2_INVERT_DIR = false;
// =====================================================
// NEXTION RX BUFFER
// =====================================================
char nextionRxBuf[80];
uint8_t nextionRxIdx = 0;
// =====================================================
// SERIAL USB BUFFER
// =====================================================
char bufferRx[40];
uint8_t idxRx = 0;
// =====================================================
// SOLICITUDES Y ESTADOS APLICADOS (HMI / CONTROL)
// =====================================================
uint8_t requestedMotorPct = 0;
uint8_t requestedDir = 0; // 0=CRUSH, 1=REVERSE
uint8_t requestedIrisPct = 0;
uint8_t appliedMotorPct = 0;
uint8_t appliedDir = 0;
uint8_t appliedIrisPct = 0;
bool cupRemovePulse = false;
bool cupReturnPulse = false;
uint8_t lastIssuedMotorPct = 255;
uint8_t lastIssuedDir = 255;
uint8_t lastIssuedIrisPct = 255;
// feedback Nextion
int lastDoorFeedbackSent = -1;
unsigned long tNextionFeedback = 0;
unsigned long INTERVALO_NEXTION_FEEDBACK_MS = 250;
// =====================================================
// ESTADOS MOTOR DC
// =====================================================
enum Direccion {
DIR_STOP = 0,
DIR_D,
DIR_I
};
Direccion dirActual = DIR_STOP;
uint8_t velocidadActual = 0;
uint8_t velocidadObjetivo = 0;
Direccion dirPendiente = DIR_STOP;
uint8_t velocidadPendiente = 0;
bool inversionEnProceso = false;
bool esperandoPausaInversion = false;
Direccion dirUsuario = DIR_STOP;
uint8_t velocidadUsuario = 0;
unsigned long tRampa = 0;
unsigned long tEsperaInversion = 0;
// =====================================================
// ESTADO PUERTA
// =====================================================
bool puertaCerradaRaw = false;
bool puertaCerradaRawAnterior = false;
bool puertaCerradaEstable = false;
unsigned long tCambioPuerta = 0;
unsigned long tReporte = 0;
// =====================================================
// ESTADO SERVO
// =====================================================
int servoAnguloActual = 0;
int servoAnguloObjetivo = 0;
unsigned long tServo = 0;
// =====================================================
// STEPPERS
// =====================================================
AccelStepper stepper1(AccelStepper::DRIVER, M1_STEP_PIN, M1_DIR_PIN);
AccelStepper stepper2(AccelStepper::DRIVER, M2_STEP_PIN, M2_DIR_PIN);
enum HomePhase {
HOME_IDLE = 0,
HOME_RELEASE,
HOME_SEEK_FAST,
HOME_BACKOFF,
HOME_SEEK_SLOW
};
struct StepperAxis {
AccelStepper* stepper;
uint8_t stepPin;
uint8_t dirPin;
uint8_t limitPin;
bool limitActiveLevel;
bool invertDir;
int8_t homeDir; // +1 significa que DIR lógico positivo va hacia home
long rangeSteps; // 0..range en coordenada máquina
bool jogMode = false;
bool homed = false;
long targetMachinePos = 0;
float maxSpeed = 1000.0f;
float accel = 1000.0f;
// homing silencioso
HomePhase homePhase = HOME_IDLE;
float homeFastSpeed = 1000.0f;
float homeSlowSpeed = 300.0f;
float homeBackoffSpeed = 600.0f;
long homePhaseStartPos = 0;
};
StepperAxis axis1;
StepperAxis axis2;
// =====================================================
// SECUENCIAS AUTOMATICAS
// =====================================================
enum AutoSequenceState {
AUTOSEQ_NONE = 0,
AUTOSEQ_STARTUP_HOME_Z,
AUTOSEQ_STARTUP_HOME_Y,
AUTOSEQ_REMOVE_HOME_Z,
AUTOSEQ_REMOVE_HOME_Y,
AUTOSEQ_REMOVE_MOVE_Y_MAX,
AUTOSEQ_RETURN_HOME_Z,
AUTOSEQ_RETURN_MOVE_Y_NEAR_HOME,
AUTOSEQ_RETURN_MOVE_Z_MAX
};
AutoSequenceState autoSeqState = AUTOSEQ_STARTUP_HOME_Z;
bool autoSeqStepStarted = false;
bool startupHomingDone = false;
// =====================================================
// UTILS
// =====================================================
uint8_t minU8(uint8_t a, uint8_t b) {
return (a < b) ? a : b;
}
int clampInt(int x, int lo, int hi) {
if (x < lo) return lo;
if (x > hi) return hi;
return x;
}
long clampLong(long x, long lo, long hi) {
if (x < lo) return lo;
if (x > hi) return hi;
return x;
}
const char* textoDireccion(Direccion d) {
switch (d) {
case DIR_D: return "D";
case DIR_I: return "I";
case DIR_STOP: return "STOP";
default: return "?";
}
}
bool esSentidoValido(Direccion d) {
return (d == DIR_D || d == DIR_I);
}
void toUpperInPlace(char* s) {
for (size_t i = 0; s[i] != '\0'; i++) {
s[i] = (char)toupper((unsigned char)s[i]);
}
}
long mapLongClamped(long x, long in_min, long in_max, long out_min, long out_max) {
if (in_max == in_min) return out_min;
if (in_min < in_max) {
if (x < in_min) x = in_min;
if (x > in_max) x = in_max;
} else {
if (x > in_min) x = in_min;
if (x < in_max) x = in_max;
}
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
bool autoSequenceActive() {
return autoSeqState != AUTOSEQ_NONE;
}
// =====================================================
// NEXTION HELPERS
// =====================================================
void sendNextionCommand(const String &cmd) {
NextionSerial.print(cmd);
NextionSerial.write(0xFF);
NextionSerial.write(0xFF);
NextionSerial.write(0xFF);
}
void updateHmiFeedback() {
unsigned long ahora = millis();
if (ahora - tNextionFeedback < INTERVALO_NEXTION_FEEDBACK_MS) return;
tNextionFeedback = ahora;
int doorVal = puertaCerradaEstable ? 0 : 1;
if (doorVal != lastDoorFeedbackSent) {
sendNextionCommand(String("vaDoor.val=") + String(doorVal));
lastDoorFeedbackSent = doorVal;
}
}
// =====================================================
// PARSER NEXTION
// =====================================================
void processHmiFrame(const String &msg) {
if (msg.length() < 3) return;
if (msg.startsWith("", &motorPct, &dir, &irisPct) == 3) {
motorPct = clampInt(motorPct, 0, 100);
dir = clampInt(dir, 0, 1);
irisPct = clampInt(irisPct, 0, 100);
requestedMotorPct = (uint8_t)motorPct;
requestedDir = (uint8_t)dir;
requestedIrisPct = (uint8_t)irisPct;
Serial.printf("[HMI] H motor=%u dir=%u iris=%u\n",
requestedMotorPct, requestedDir, requestedIrisPct);
} else {
Serial.printf("[HMI] Frame H invalido: %s\n", msg.c_str());
}
return;
}
if (msg.startsWith("", &evt) == 1) {
if (evt == 1) {
cupRemovePulse = true;
Serial.println("[HMI] Evento REMOVE CUP");
} else if (evt == 2) {
cupReturnPulse = true;
Serial.println("[HMI] Evento RETURN CUP");
} else {
Serial.printf("[HMI] Evento C desconocido: %d\n", evt);
}
} else {
Serial.printf("[HMI] Frame C invalido: %s\n", msg.c_str());
}
return;
}
Serial.printf("[HMI] Frame ignorado: %s\n", msg.c_str());
}
void readNextionFrames() {
while (NextionSerial.available() > 0) {
char ch = (char)NextionSerial.read();
if (ch == '\r') continue;
if (ch == '\n') {
if (nextionRxIdx > 0) {
nextionRxBuf[nextionRxIdx] = '\0';
processHmiFrame(String(nextionRxBuf));
nextionRxIdx = 0;
}
} else {
if (nextionRxIdx < sizeof(nextionRxBuf) - 1) {
nextionRxBuf[nextionRxIdx++] = ch;
} else {
nextionRxIdx = 0;
}
}
}
}
// =====================================================
// MOTOR DC
// =====================================================
uint16_t porcentajeADuty(uint8_t porcentaje) {
if (porcentaje > 100) porcentaje = 100;
return (uint16_t)((porcentaje * PWM_MAX_MOTOR) / 100);
}
void escribirPuente(Direccion dir, uint8_t velPercent) {
uint16_t duty = porcentajeADuty(velPercent);
switch (dir) {
case DIR_D:
ledcWrite(PIN_RPWM, duty);
ledcWrite(PIN_LPWM, 0);
break;
case DIR_I:
ledcWrite(PIN_RPWM, 0);
ledcWrite(PIN_LPWM, duty);
break;
case DIR_STOP:
default:
ledcWrite(PIN_RPWM, 0);
ledcWrite(PIN_LPWM, 0);
break;
}
}
void apagarMotorPorSeguridad() {
inversionEnProceso = false;
esperandoPausaInversion = false;
dirPendiente = DIR_STOP;
velocidadPendiente = 0;
dirActual = DIR_STOP;
velocidadActual = 0;
velocidadObjetivo = 0;
escribirPuente(DIR_STOP, 0);
}
void detenerMotorNormal() {
inversionEnProceso = false;
esperandoPausaInversion = false;
dirPendiente = DIR_STOP;
velocidadPendiente = 0;
velocidadObjetivo = 0;
}
void iniciarInversion(Direccion nuevaDir, uint8_t nuevaVel) {
dirPendiente = nuevaDir;
velocidadPendiente = nuevaVel;
inversionEnProceso = true;
esperandoPausaInversion = false;
velocidadObjetivo = 0;
Serial.printf("Inversion solicitada. Frenando a 0 y esperando %lu ms.\n",
TIEMPO_CAMBIO_SENTIDO_MS);
}
void procesarSolicitudMotor(Direccion nuevaDir, uint8_t nuevaVel) {
if (nuevaVel > 100) {
Serial.println("Error: velocidad fuera de rango (0-100)");
return;
}
if (nuevaVel == 0) {
dirUsuario = DIR_STOP;
velocidadUsuario = 0;
} else {
dirUsuario = nuevaDir;
velocidadUsuario = nuevaVel;
}
if (!puertaCerradaEstable) {
apagarMotorPorSeguridad();
if (nuevaVel == 0) {
Serial.println("Puerta abierta. Motor detenido y configuracion en STOP.");
} else {
Serial.printf("Puerta abierta. Configuracion guardada para reanudar luego: %s%u\n",
textoDireccion(dirUsuario), velocidadUsuario);
}
return;
}
if (nuevaVel == 0) {
Serial.println("Parada solicitada.");
detenerMotorNormal();
return;
}
if (dirActual == DIR_STOP && velocidadActual == 0 && !inversionEnProceso) {
dirActual = nuevaDir;
velocidadObjetivo = nuevaVel;
Serial.printf("Arranque: %s%u\n", textoDireccion(nuevaDir), nuevaVel);
return;
}
if (!inversionEnProceso && dirActual == nuevaDir) {
velocidadObjetivo = nuevaVel;
Serial.printf("Nueva velocidad: %s%u\n", textoDireccion(nuevaDir), nuevaVel);
return;
}
if (!inversionEnProceso && esSentidoValido(dirActual) && nuevaDir != dirActual) {
iniciarInversion(nuevaDir, nuevaVel);
return;
}
if (inversionEnProceso) {
dirPendiente = nuevaDir;
velocidadPendiente = nuevaVel;
Serial.printf("Destino pendiente actualizado: %s%u\n",
textoDireccion(nuevaDir), nuevaVel);
}
}
void actualizarRampaMotor() {
if (!puertaCerradaEstable) return;
unsigned long ahora = millis();
if (ahora - tRampa < INTERVALO_RAMPA_MS) return;
tRampa = ahora;
if (inversionEnProceso && !esperandoPausaInversion) {
if (velocidadActual > velocidadObjetivo) {
uint8_t diferencia = (uint8_t)(velocidadActual - velocidadObjetivo);
uint8_t delta = minU8(PASO_RAMPA, diferencia);
velocidadActual -= delta;
escribirPuente(dirActual, velocidadActual);
}
if (velocidadActual == 0) {
escribirPuente(DIR_STOP, 0);
dirActual = DIR_STOP;
esperandoPausaInversion = true;
tEsperaInversion = millis();
Serial.println("Motor en 0. Iniciando pausa de inversion...");
}
return;
}
if (inversionEnProceso && esperandoPausaInversion) {
if (millis() - tEsperaInversion >= TIEMPO_CAMBIO_SENTIDO_MS) {
dirActual = dirPendiente;
velocidadObjetivo = velocidadPendiente;
inversionEnProceso = false;
esperandoPausaInversion = false;
Serial.printf("Inversion completada. Nuevo objetivo: %s%u\n",
textoDireccion(dirActual), velocidadObjetivo);
}
return;
}
if (velocidadActual < velocidadObjetivo) {
uint8_t faltante = (uint8_t)(velocidadObjetivo - velocidadActual);
uint8_t delta = minU8(PASO_RAMPA, faltante);
velocidadActual += delta;
escribirPuente(dirActual, velocidadActual);
}
else if (velocidadActual > velocidadObjetivo) {
uint8_t diferencia = (uint8_t)(velocidadActual - velocidadObjetivo);
uint8_t delta = minU8(PASO_RAMPA, diferencia);
velocidadActual -= delta;
if (velocidadActual == 0 && velocidadObjetivo == 0) {
escribirPuente(DIR_STOP, 0);
dirActual = DIR_STOP;
} else {
escribirPuente(dirActual, velocidadActual);
}
}
appliedMotorPct = velocidadActual;
appliedDir = (dirActual == DIR_I) ? 1 : 0;
}
// =====================================================
// SERVO / IRIS
// =====================================================
uint32_t servoPulseUsToDuty(uint32_t pulseUs) {
return (pulseUs * PWM_MAX_SERVO) / SERVO_PERIODO_US;
}
void escribirServoAngulo(int angulo) {
angulo = clampInt(angulo, 0, 180);
long pulseUs = mapLongClamped(angulo, 0, 180, SERVO_MIN_US, SERVO_MAX_US);
uint32_t duty = servoPulseUsToDuty((uint32_t)pulseUs);
ledcWrite(PIN_SERVO, duty);
}
void moverServoA(int angulo) {
servoAnguloObjetivo = clampInt(angulo, 0, 180);
Serial.printf("Servo objetivo -> %d grados\n", servoAnguloObjetivo);
}
int irisPctToServoAngle(uint8_t pct) {
return (int)mapLongClamped((long)pct, 0, 100, SERVO_ANGULO_CERRADO, SERVO_ANGULO_ABIERTO);
}
uint8_t servoAngleToIrisPct(int angle) {
return (uint8_t)clampLong(
mapLongClamped((long)angle, SERVO_ANGULO_CERRADO, SERVO_ANGULO_ABIERTO, 0, 100),
0, 100
);
}
void abrirCompuerta() {
requestedIrisPct = 100;
moverServoA(SERVO_ANGULO_ABIERTO);
Serial.printf("Compuerta ABRIR -> %d grados\n", SERVO_ANGULO_ABIERTO);
}
void cerrarCompuerta() {
requestedIrisPct = 0;
moverServoA(SERVO_ANGULO_CERRADO);
Serial.printf("Compuerta CERRAR -> %d grados\n", SERVO_ANGULO_CERRADO);
}
void actualizarServo() {
unsigned long ahora = millis();
if (ahora - tServo < INTERVALO_SERVO_MS) return;
tServo = ahora;
if (servoAnguloActual < servoAnguloObjetivo) {
servoAnguloActual += PASO_SERVO;
if (servoAnguloActual > servoAnguloObjetivo) servoAnguloActual = servoAnguloObjetivo;
escribirServoAngulo(servoAnguloActual);
}
else if (servoAnguloActual > servoAnguloObjetivo) {
servoAnguloActual -= PASO_SERVO;
if (servoAnguloActual < servoAnguloObjetivo) servoAnguloActual = servoAnguloObjetivo;
escribirServoAngulo(servoAnguloActual);
}
appliedIrisPct = servoAngleToIrisPct(servoAnguloActual);
}
// =====================================================
// PUERTA
// =====================================================
bool leerPuertaCrudaCerrada() {
return (digitalRead(PIN_PUERTA) == PUERTA_CERRADA_NIVEL);
}
void reanudarUltimaConfiguracion() {
if (!puertaCerradaEstable) return;
if (!esSentidoValido(dirUsuario) || velocidadUsuario == 0) {
Serial.println("Puerta cerrada. No hay configuracion previa para reanudar.");
return;
}
dirActual = dirUsuario;
velocidadObjetivo = velocidadUsuario;
Serial.printf("Puerta cerrada. Reanudando ultima configuracion: %s%u\n",
textoDireccion(dirUsuario), velocidadUsuario);
}
void manejarEventoPuertaAbierta() {
Serial.println("EVENTO: PUERTA ABIERTA -> APAGADO FORZADO");
apagarMotorPorSeguridad();
}
void manejarEventoPuertaCerrada() {
Serial.println("EVENTO: PUERTA CERRADA");
reanudarUltimaConfiguracion();
}
void actualizarPuerta() {
bool lecturaActual = leerPuertaCrudaCerrada();
if (lecturaActual != puertaCerradaRawAnterior) {
puertaCerradaRawAnterior = lecturaActual;
tCambioPuerta = millis();
}
if (millis() - tCambioPuerta >= DEBOUNCE_PUERTA_MS) {
puertaCerradaRaw = lecturaActual;
if (puertaCerradaEstable != puertaCerradaRaw) {
puertaCerradaEstable = puertaCerradaRaw;
if (puertaCerradaEstable) {
manejarEventoPuertaCerrada();
} else {
manejarEventoPuertaAbierta();
}
}
}
}
// =====================================================
// APLICACION DE SOLICITUDES HMI
// =====================================================
void applyCrusherMotor() {
Direccion reqDir = (requestedDir == 0) ? DIR_D : DIR_I;
procesarSolicitudMotor(reqDir, requestedMotorPct);
}
void applyIris() {
int targetAngle = irisPctToServoAngle(requestedIrisPct);
moverServoA(targetAngle);
}
void applyRequestedStateIfChanged() {
if (requestedMotorPct != lastIssuedMotorPct || requestedDir != lastIssuedDir) {
applyCrusherMotor();
lastIssuedMotorPct = requestedMotorPct;
lastIssuedDir = requestedDir;
}
if (requestedIrisPct != lastIssuedIrisPct) {
applyIris();
lastIssuedIrisPct = requestedIrisPct;
}
}
// =====================================================
// STEPPERS CON ACCELSTEPPER
// =====================================================
bool axisLimitActive(StepperAxis &ax) {
return digitalRead(ax.limitPin) == ax.limitActiveLevel;
}
// Convierte posición máquina (0=home, positivo alejándose)
// a posición lógica de AccelStepper.
long axisLogicalFromMachine(const StepperAxis &ax, long machinePos) {
return (ax.homeDir == 1) ? -machinePos : machinePos;
}
// Convierte posición lógica de AccelStepper a posición máquina.
long axisMachineFromLogical(const StepperAxis &ax, long logicalPos) {
return (ax.homeDir == 1) ? -logicalPos : logicalPos;
}
long axisMachinePosition(const StepperAxis &ax) {
return axisMachineFromLogical(ax, ax.stepper->currentPosition());
}
bool axisIsBusy(const StepperAxis &ax) {
return (ax.homePhase != HOME_IDLE) || ax.jogMode || (ax.stepper->distanceToGo() != 0);
}
float axisLogicalSpeedTowardHome(const StepperAxis &ax, float speedAbs) {
return (ax.homeDir == 1) ? +fabs(speedAbs) : -fabs(speedAbs);
}
float axisLogicalSpeedAwayFromHome(const StepperAxis &ax, float speedAbs) {
return -axisLogicalSpeedTowardHome(ax, speedAbs);
}
void axisConfigureMove(StepperAxis &ax, float maxSpeed, float accel) {
ax.stepper->setMaxSpeed(maxSpeed);
ax.stepper->setAcceleration(accel);
}
void axisStopImmediate(StepperAxis &ax) {
long pos = ax.stepper->currentPosition();
ax.stepper->moveTo(pos);
ax.homePhase = HOME_IDLE;
ax.jogMode = false;
ax.targetMachinePos = axisMachinePosition(ax);
}
void axisSetAtHome(StepperAxis &ax) {
ax.stepper->setCurrentPosition(0);
ax.stepper->moveTo(0);
ax.homePhase = HOME_IDLE;
ax.jogMode = false;
ax.homed = true;
ax.targetMachinePos = 0;
}
void axisStartQuietHome(StepperAxis &ax, const char* nombre,
float fastSpeed, float slowSpeed, float backoffSpeed) {
ax.homeFastSpeed = fastSpeed;
ax.homeSlowSpeed = slowSpeed;
ax.homeBackoffSpeed = backoffSpeed;
ax.jogMode = false;
ax.homed = false;
// durante homing usamos runSpeed(), no movimiento acelerado
ax.stepper->moveTo(ax.stepper->currentPosition());
if (axisLimitActive(ax)) {
ax.homePhase = HOME_RELEASE;
ax.stepper->setSpeed(axisLogicalSpeedAwayFromHome(ax, ax.homeBackoffSpeed));
ax.homePhaseStartPos = ax.stepper->currentPosition();
Serial.printf("%s -> HOME silencioso: liberando switch...\n", nombre);
} else {
ax.homePhase = HOME_SEEK_FAST;
ax.stepper->setSpeed(axisLogicalSpeedTowardHome(ax, ax.homeFastSpeed));
ax.homePhaseStartPos = ax.stepper->currentPosition();
Serial.printf("%s -> HOME silencioso: búsqueda rápida...\n", nombre);
}
}
void axisStartHome(StepperAxis &ax, const char* nombre) {
axisStartQuietHome(ax, nombre, ax.homeFastSpeed, ax.homeSlowSpeed, ax.homeBackoffSpeed);
}
void axisStartAbsolute(StepperAxis &ax, const char* nombre, long machineTarget) {
if (!ax.homed) {
Serial.printf("%s -> primero haz HOME\n", nombre);
return;
}
machineTarget = clampLong(machineTarget, 0, ax.rangeSteps);
long logicalTarget = axisLogicalFromMachine(ax, machineTarget);
axisConfigureMove(ax, ax.maxSpeed, ax.accel);
ax.stepper->moveTo(logicalTarget);
ax.targetMachinePos = machineTarget;
ax.homePhase = HOME_IDLE;
ax.jogMode = false;
Serial.printf("%s -> movimiento absoluto a %ld\n", nombre, machineTarget);
}
void axisStartRelative(StepperAxis &ax, const char* nombre, long delta) {
if (!ax.homed) {
Serial.printf("%s -> primero haz HOME\n", nombre);
return;
}
long currentMachine = axisMachinePosition(ax);
long targetMachine = clampLong(currentMachine + delta, 0, ax.rangeSteps);
if (targetMachine == currentMachine) {
Serial.printf("%s -> ya esta en el limite permitido\n", nombre);
return;
}
axisStartAbsolute(ax, nombre, targetMachine);
}
void axisStartJog(StepperAxis &ax, const char* nombre, int8_t coordDir) {
if (!ax.homed) {
Serial.printf("%s -> primero haz HOME\n", nombre);
return;
}
axisConfigureMove(ax, ax.maxSpeed, ax.accel);
long farTarget = (coordDir > 0) ? ax.rangeSteps : 0;
long logicalTarget = axisLogicalFromMachine(ax, farTarget);
ax.stepper->moveTo(logicalTarget);
ax.targetMachinePos = farTarget;
ax.homePhase = HOME_IDLE;
ax.jogMode = true;
Serial.printf("%s -> JOG %s\n", nombre, (coordDir > 0 ? "+" : "-"));
}
void axisUpdateHomeQuiet(StepperAxis &ax, const char* nombre) {
switch (ax.homePhase) {
case HOME_IDLE:
return;
case HOME_RELEASE:
ax.stepper->runSpeed();
if (!axisLimitActive(ax)) {
ax.homePhase = HOME_SEEK_FAST;
ax.stepper->setSpeed(axisLogicalSpeedTowardHome(ax, ax.homeFastSpeed));
ax.homePhaseStartPos = ax.stepper->currentPosition();
Serial.printf("%s -> switch liberado, búsqueda rápida.\n", nombre);
} else {
long delta = labs(ax.stepper->currentPosition() - ax.homePhaseStartPos);
if (delta > HOME_RELEASE_MAX_STEPS) {
ax.homePhase = HOME_IDLE;
Serial.printf("%s -> ERROR liberando switch.\n", nombre);
}
}
return;
case HOME_SEEK_FAST:
ax.stepper->runSpeed();
if (axisLimitActive(ax)) {
ax.homePhase = HOME_BACKOFF;
ax.stepper->setSpeed(axisLogicalSpeedAwayFromHome(ax, ax.homeBackoffSpeed));
ax.homePhaseStartPos = ax.stepper->currentPosition();
Serial.printf("%s -> switch tocado, retroceso.\n", nombre);
} else {
long delta = labs(ax.stepper->currentPosition() - ax.homePhaseStartPos);
if (delta > HOME_SEARCH_STEPS) {
ax.homePhase = HOME_IDLE;
Serial.printf("%s -> ERROR no encontró home.\n", nombre);
}
}
return;
case HOME_BACKOFF:
ax.stepper->runSpeed();
if (!axisLimitActive(ax)) {
ax.homePhase = HOME_SEEK_SLOW;
ax.stepper->setSpeed(axisLogicalSpeedTowardHome(ax, ax.homeSlowSpeed));
ax.homePhaseStartPos = ax.stepper->currentPosition();
Serial.printf("%s -> búsqueda lenta final.\n", nombre);
} else {
long delta = labs(ax.stepper->currentPosition() - ax.homePhaseStartPos);
if (delta > HOME_RELEASE_MAX_STEPS) {
ax.homePhase = HOME_IDLE;
Serial.printf("%s -> ERROR en backoff.\n", nombre);
}
}
return;
case HOME_SEEK_SLOW:
ax.stepper->runSpeed();
if (axisLimitActive(ax)) {
axisSetAtHome(ax);
Serial.printf("%s -> HOME completo, posición = 0\n", nombre);
} else {
long delta = labs(ax.stepper->currentPosition() - ax.homePhaseStartPos);
if (delta > HOME_RELEASE_MAX_STEPS) {
ax.homePhase = HOME_IDLE;
Serial.printf("%s -> ERROR en búsqueda lenta.\n", nombre);
}
}
return;
}
}
void axisUpdate(StepperAxis &ax, const char* nombre) {
if (ax.homePhase != HOME_IDLE) {
axisUpdateHomeQuiet(ax, nombre);
return;
}
long currentMachine = axisMachinePosition(ax);
if (currentMachine < 0) {
ax.stepper->setCurrentPosition(axisLogicalFromMachine(ax, 0));
ax.stepper->moveTo(axisLogicalFromMachine(ax, 0));
currentMachine = 0;
}
if (currentMachine > ax.rangeSteps) {
ax.stepper->setCurrentPosition(axisLogicalFromMachine(ax, ax.rangeSteps));
ax.stepper->moveTo(axisLogicalFromMachine(ax, ax.rangeSteps));
currentMachine = ax.rangeSteps;
}
ax.stepper->run();
if (ax.jogMode) {
long p = axisMachinePosition(ax);
if (p <= 0 && ax.targetMachinePos == 0) {
ax.stepper->setCurrentPosition(axisLogicalFromMachine(ax, 0));
ax.stepper->moveTo(axisLogicalFromMachine(ax, 0));
ax.jogMode = false;
Serial.printf("%s -> jog detenido en home\n", nombre);
return;
}
if (p >= ax.rangeSteps && ax.targetMachinePos == ax.rangeSteps) {
ax.stepper->setCurrentPosition(axisLogicalFromMachine(ax, ax.rangeSteps));
ax.stepper->moveTo(axisLogicalFromMachine(ax, ax.rangeSteps));
ax.jogMode = false;
Serial.printf("%s -> jog detenido en maximo\n", nombre);
return;
}
}
}
// =====================================================
// SECUENCIAS AUTOMATICAS
// =====================================================
void startRemoveCupSequence() {
if (autoSequenceActive()) return;
autoSeqState = AUTOSEQ_REMOVE_HOME_Z;
autoSeqStepStarted = false;
Serial.println("[AUTO] Iniciando REMOVE CUP");
}
void startReturnCupSequence() {
if (autoSequenceActive()) return;
autoSeqState = AUTOSEQ_RETURN_HOME_Z;
autoSeqStepStarted = false;
Serial.println("[AUTO] Iniciando RETURN CUP");
}
void updateAutoSequence() {
switch (autoSeqState) {
case AUTOSEQ_NONE:
break;
case AUTOSEQ_STARTUP_HOME_Z:
if (!autoSeqStepStarted) {
Serial.println("[AUTO] Startup: seteo suave eje Z");
axisStartQuietHome(axis1, "Z/M1",
STARTUP_HOME_FAST_SPEED,
STARTUP_HOME_SLOW_SPEED,
STARTUP_HOME_BACKOFF_SPEED);
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis1)) {
if (!axis1.homed) {
Serial.println("[AUTO] ERROR: home startup Z falló.");
autoSeqState = AUTOSEQ_NONE;
} else {
autoSeqState = AUTOSEQ_STARTUP_HOME_Y;
autoSeqStepStarted = false;
}
}
break;
case AUTOSEQ_STARTUP_HOME_Y:
if (!autoSeqStepStarted) {
Serial.println("[AUTO] Startup: seteo suave eje Y");
axisStartQuietHome(axis2, "Y/M2",
STARTUP_HOME_FAST_SPEED,
STARTUP_HOME_SLOW_SPEED,
STARTUP_HOME_BACKOFF_SPEED);
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis2)) {
if (!axis2.homed) {
Serial.println("[AUTO] ERROR: home startup Y falló.");
autoSeqState = AUTOSEQ_NONE;
} else {
startupHomingDone = true;
autoSeqState = AUTOSEQ_NONE;
autoSeqStepStarted = false;
Serial.println("[AUTO] Startup completo. Ambos ejes en origen.");
}
}
break;
case AUTOSEQ_REMOVE_HOME_Z:
if (!autoSeqStepStarted) {
axisStartHome(axis1, "Z/M1");
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis1)) {
if (!axis1.homed) {
Serial.println("[AUTO] ERROR: home Z en REMOVE CUP falló.");
autoSeqState = AUTOSEQ_NONE;
} else {
autoSeqState = AUTOSEQ_REMOVE_HOME_Y;
autoSeqStepStarted = false;
}
}
break;
case AUTOSEQ_REMOVE_HOME_Y:
if (!autoSeqStepStarted) {
axisStartHome(axis2, "Y/M2");
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis2)) {
if (!axis2.homed) {
Serial.println("[AUTO] ERROR: home Y en REMOVE CUP falló.");
autoSeqState = AUTOSEQ_NONE;
} else {
autoSeqState = AUTOSEQ_REMOVE_MOVE_Y_MAX;
autoSeqStepStarted = false;
}
}
break;
case AUTOSEQ_REMOVE_MOVE_Y_MAX:
if (!autoSeqStepStarted) {
axisStartAbsolute(axis2, "Y/M2", axis2.rangeSteps);
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis2)) {
autoSeqState = AUTOSEQ_NONE;
autoSeqStepStarted = false;
Serial.println("[AUTO] REMOVE CUP completado.");
}
break;
case AUTOSEQ_RETURN_HOME_Z:
if (!autoSeqStepStarted) {
axisStartHome(axis1, "Z/M1");
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis1)) {
if (!axis1.homed) {
Serial.println("[AUTO] ERROR: home Z en RETURN CUP falló.");
autoSeqState = AUTOSEQ_NONE;
} else {
autoSeqState = AUTOSEQ_RETURN_MOVE_Y_NEAR_HOME;
autoSeqStepStarted = false;
}
}
break;
case AUTOSEQ_RETURN_MOVE_Y_NEAR_HOME:
if (!autoSeqStepStarted) {
axisStartAbsolute(axis2, "Y/M2", M2_RETURN_CUP_Y_STEPS);
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis2)) {
autoSeqState = AUTOSEQ_RETURN_MOVE_Z_MAX;
autoSeqStepStarted = false;
}
break;
case AUTOSEQ_RETURN_MOVE_Z_MAX:
if (!autoSeqStepStarted) {
// aquí Z se aleja del final y sube al máximo
axisStartAbsolute(axis1, "Z/M1", axis1.rangeSteps);
autoSeqStepStarted = true;
}
if (!axisIsBusy(axis1)) {
autoSeqState = AUTOSEQ_NONE;
autoSeqStepStarted = false;
Serial.println("[AUTO] RETURN CUP completado.");
}
break;
}
}
// =====================================================
// CUP EVENTS
// =====================================================
void handleCupRemove() {
if (!cupRemovePulse) return;
if (!startupHomingDone) return;
if (autoSequenceActive()) return;
cupRemovePulse = false;
startRemoveCupSequence();
}
void handleCupReturn() {
if (!cupReturnPulse) return;
if (!startupHomingDone) return;
if (autoSequenceActive()) return;
cupReturnPulse = false;
startReturnCupSequence();
}
// =====================================================
// REPORTE GENERAL
// =====================================================
void reportarEstadoSistema() {
if (millis() - tReporte < INTERVALO_REPORTE_MS) return;
tReporte = millis();
long pos1 = axisMachinePosition(axis1);
long pos2 = axisMachinePosition(axis2);
Serial.printf(
"PUERTA:%s | REQ_MOTOR:%u/%u | APP_MOTOR:%u/%u | REQ_IRIS:%u | APP_IRIS:%u | SERVO:%d/%d | "
"FC1:%s POS1:%ld/%ld HOMED1:%d BUSY1:%d | "
"FC2:%s POS2:%ld/%ld HOMED2:%d BUSY2:%d | AUTOSEQ:%d\n",
puertaCerradaEstable ? "CERRADA" : "ABIERTA",
requestedMotorPct, requestedDir,
appliedMotorPct, appliedDir,
requestedIrisPct, appliedIrisPct,
servoAnguloActual, servoAnguloObjetivo,
axisLimitActive(axis1) ? "ACT" : "LIB",
pos1, axis1.rangeSteps, axis1.homed ? 1 : 0, axisIsBusy(axis1) ? 1 : 0,
axisLimitActive(axis2) ? "ACT" : "LIB",
pos2, axis2.rangeSteps, axis2.homed ? 1 : 0, axisIsBusy(axis2) ? 1 : 0,
(int)autoSeqState
);
}
// =====================================================
// COMANDOS SERIAL DEBUG
// =====================================================
void imprimirAyuda() {
Serial.println("===== COMANDOS =====");
Serial.println("Motor DC:");
Serial.println(" D100");
Serial.println(" I50");
Serial.println(" D0");
Serial.println("");
Serial.println("Servo:");
Serial.println(" ABRIR");
Serial.println(" CERRAR");
Serial.println(" ANG90");
Serial.println(" IRIS60");
Serial.println("");
Serial.println("Steppers:");
Serial.println(" HOME1");
Serial.println(" HOME2");
Serial.println(" P1+1000");
Serial.println(" P1-500");
Serial.println(" P2+1000");
Serial.println(" P2-500");
Serial.println(" J1+ / J1-");
Serial.println(" J2+ / J2-");
Serial.println(" STOP1");
Serial.println(" STOP2");
Serial.println("");
Serial.println("Secuencias:");
Serial.println(" REMOVECUP");
Serial.println(" RETURNCUP");
Serial.println("");
Serial.println("General:");
Serial.println(" ESTADO");
Serial.println(" AYUDA");
}
void imprimirEstadoUnaVez() {
long pos1 = axisMachinePosition(axis1);
long pos2 = axisMachinePosition(axis2);
Serial.printf(
"PUERTA:%s | REQ_MOTOR:%u/%u | APP_MOTOR:%u/%u | REQ_IRIS:%u | APP_IRIS:%u | SERVO:%d/%d | "
"FC1:%s POS1:%ld/%ld HOMED1:%d BUSY1:%d | "
"FC2:%s POS2:%ld/%ld HOMED2:%d BUSY2:%d | AUTOSEQ:%d\n",
puertaCerradaEstable ? "CERRADA" : "ABIERTA",
requestedMotorPct, requestedDir,
appliedMotorPct, appliedDir,
requestedIrisPct, appliedIrisPct,
servoAnguloActual, servoAnguloObjetivo,
axisLimitActive(axis1) ? "ACT" : "LIB",
pos1, axis1.rangeSteps, axis1.homed ? 1 : 0, axisIsBusy(axis1) ? 1 : 0,
axisLimitActive(axis2) ? "ACT" : "LIB",
pos2, axis2.rangeSteps, axis2.homed ? 1 : 0, axisIsBusy(axis2) ? 1 : 0,
(int)autoSeqState
);
}
void procesarComando(const char* cmdOriginal) {
if (cmdOriginal == nullptr || cmdOriginal[0] == '\0') return;
char cmd[40];
strncpy(cmd, cmdOriginal, sizeof(cmd) - 1);
cmd[sizeof(cmd) - 1] = '\0';
toUpperInPlace(cmd);
if (strcmp(cmd, "ABRIR") == 0) {
abrirCompuerta();
return;
}
if (strcmp(cmd, "CERRAR") == 0) {
cerrarCompuerta();
return;
}
if (strcmp(cmd, "REMOVECUP") == 0) {
cupRemovePulse = true;
return;
}
if (strcmp(cmd, "RETURNCUP") == 0) {
cupReturnPulse = true;
return;
}
if (strncmp(cmd, "IRIS", 4) == 0) {
char* endPtr = nullptr;
long pct = strtol(cmd + 4, &endPtr, 10);
if (endPtr == cmd + 4 || *endPtr != '\0') {
Serial.println("Formato invalido. Usa IRIS60");
return;
}
pct = clampLong(pct, 0, 100);
requestedIrisPct = (uint8_t)pct;
applyIris();
lastIssuedIrisPct = requestedIrisPct;
return;
}
if (strncmp(cmd, "ANG", 3) == 0) {
char* endPtr = nullptr;
long ang = strtol(cmd + 3, &endPtr, 10);
if (endPtr == cmd + 3 || *endPtr != '\0') {
Serial.println("Formato invalido. Usa ANG90");
return;
}
if (ang < 0 || ang > 180) {
Serial.println("Angulo invalido. 0 a 180.");
return;
}
moverServoA((int)ang);
return;
}
if (autoSequenceActive()) {
if (strcmp(cmd, "HOME1") == 0 || strcmp(cmd, "HOME2") == 0 ||
strcmp(cmd, "J1+") == 0 || strcmp(cmd, "J1-") == 0 ||
strcmp(cmd, "J2+") == 0 || strcmp(cmd, "J2-") == 0 ||
strcmp(cmd, "STOP1") == 0 || strcmp(cmd, "STOP2") == 0 ||
strncmp(cmd, "P1", 2) == 0 || strncmp(cmd, "P2", 2) == 0) {
Serial.println("Secuencia automática activa. Espera a que termine.");
return;
}
}
if (strcmp(cmd, "HOME1") == 0) {
axisStartHome(axis1, "M1");
return;
}
if (strcmp(cmd, "HOME2") == 0) {
axisStartHome(axis2, "M2");
return;
}
if (strcmp(cmd, "J1+") == 0) {
axisStartJog(axis1, "M1", +1);
return;
}
if (strcmp(cmd, "J1-") == 0) {
axisStartJog(axis1, "M1", -1);
return;
}
if (strcmp(cmd, "J2+") == 0) {
axisStartJog(axis2, "M2", +1);
return;
}
if (strcmp(cmd, "J2-") == 0) {
axisStartJog(axis2, "M2", -1);
return;
}
if (strcmp(cmd, "STOP1") == 0) {
axisStopImmediate(axis1);
Serial.println("M1 detenido");
return;
}
if (strcmp(cmd, "STOP2") == 0) {
axisStopImmediate(axis2);
Serial.println("M2 detenido");
return;
}
if (strncmp(cmd, "P1", 2) == 0) {
char* endPtr = nullptr;
long delta = strtol(cmd + 2, &endPtr, 10);
if (endPtr == cmd + 2 || *endPtr != '\0') {
Serial.println("Formato invalido. Usa P1+1000 o P1-500");
return;
}
axisStartRelative(axis1, "M1", delta);
return;
}
if (strncmp(cmd, "P2", 2) == 0) {
char* endPtr = nullptr;
long delta = strtol(cmd + 2, &endPtr, 10);
if (endPtr == cmd + 2 || *endPtr != '\0') {
Serial.println("Formato invalido. Usa P2+1000 o P2-500");
return;
}
axisStartRelative(axis2, "M2", delta);
return;
}
if (cmd[0] == 'D' || cmd[0] == 'I') {
char* endPtr = nullptr;
long valor = strtol(cmd + 1, &endPtr, 10);
if (endPtr == cmd + 1 || *endPtr != '\0') {
Serial.println("Formato invalido. Ejemplos: D50, I100, D0");
return;
}
if (valor < 0 || valor > 100) {
Serial.println("Valor invalido. Debe estar entre 0 y 100");
return;
}
requestedMotorPct = (uint8_t)valor;
requestedDir = (cmd[0] == 'D') ? 0 : 1;
applyCrusherMotor();
lastIssuedMotorPct = requestedMotorPct;
lastIssuedDir = requestedDir;
return;
}
if (strcmp(cmd, "ESTADO") == 0) {
imprimirEstadoUnaVez();
return;
}
if (strcmp(cmd, "AYUDA") == 0) {
imprimirAyuda();
return;
}
Serial.println("Comando no reconocido. Escribe AYUDA.");
}
void leerSerialNoBloqueante() {
while (Serial.available() > 0) {
char ch = Serial.read();
if (ch == '\n' || ch == '\r') {
if (idxRx > 0) {
bufferRx[idxRx] = '\0';
procesarComando(bufferRx);
idxRx = 0;
}
} else if (ch == ' ' || ch == '\t') {
// ignorar
} else {
if (idxRx < sizeof(bufferRx) - 1) {
bufferRx[idxRx++] = ch;
} else {
idxRx = 0;
Serial.println("Comando demasiado largo");
}
}
}
}
// =====================================================
// SETUP AXIS
// =====================================================
void setupAxis(
StepperAxis &ax,
AccelStepper* stepperObj,
uint8_t stepPin,
uint8_t dirPin,
uint8_t limitPin,
bool limitActiveLevel,
bool invertDir,
int8_t homeDir,
float runSpeed,
float runAccel,
long rangeSteps,
float homeFast,
float homeSlow,
float homeBackoff
) {
ax.stepper = stepperObj;
ax.stepPin = stepPin;
ax.dirPin = dirPin;
ax.limitPin = limitPin;
ax.limitActiveLevel = limitActiveLevel;
ax.invertDir = invertDir;
ax.homeDir = homeDir;
ax.maxSpeed = runSpeed;
ax.accel = runAccel;
ax.rangeSteps = rangeSteps;
ax.homeFastSpeed = homeFast;
ax.homeSlowSpeed = homeSlow;
ax.homeBackoffSpeed = homeBackoff;
pinMode(ax.limitPin, INPUT);
ax.stepper->setPinsInverted(ax.invertDir, false, false);
ax.stepper->setMaxSpeed(ax.maxSpeed);
ax.stepper->setAcceleration(ax.accel);
ax.stepper->setMinPulseWidth(4);
ax.stepper->setCurrentPosition(0);
ax.targetMachinePos = 0;
ax.homePhase = HOME_IDLE;
}
// =====================================================
// SETUP / LOOP
// =====================================================
void setup() {
Serial.begin(115200);
NextionSerial.begin(NEXTION_BAUD, SERIAL_8N1, NEXTION_RX_PIN, NEXTION_TX_PIN);
bool ok1 = ledcAttach(PIN_RPWM, PWM_FREQ_MOTOR, PWM_RES_MOTOR);
bool ok2 = ledcAttach(PIN_LPWM, PWM_FREQ_MOTOR, PWM_RES_MOTOR);
bool ok3 = ledcAttach(PIN_SERVO, PWM_FREQ_SERVO, PWM_RES_SERVO);
if (!ok1 || !ok2 || !ok3) {
Serial.println("Error configurando PWM LEDC");
while (true) {}
}
pinMode(PIN_PUERTA, INPUT_PULLUP);
bool estadoInicialPuerta = leerPuertaCrudaCerrada();
puertaCerradaRaw = estadoInicialPuerta;
puertaCerradaRawAnterior = estadoInicialPuerta;
puertaCerradaEstable = estadoInicialPuerta;
setupAxis(axis1, &stepper1, M1_STEP_PIN, M1_DIR_PIN, M1_LIMIT_PIN,
LIMIT1_ACTIVE_LEVEL, M1_INVERT_DIR, M1_HOME_DIR,
M1_MAX_SPEED, M1_ACCEL, M1_RANGE_STEPS,
M1_HOME_FAST_SPEED, M1_HOME_SLOW_SPEED, M1_HOME_BACKOFF_SPEED);
setupAxis(axis2, &stepper2, M2_STEP_PIN, M2_DIR_PIN, M2_LIMIT_PIN,
LIMIT2_ACTIVE_LEVEL, M2_INVERT_DIR, M2_HOME_DIR,
M2_MAX_SPEED, M2_ACCEL, M2_RANGE_STEPS,
M2_HOME_FAST_SPEED, M2_HOME_SLOW_SPEED, M2_HOME_BACKOFF_SPEED);
tCambioPuerta = millis();
tReporte = 0;
tRampa = millis();
tServo = millis();
tNextionFeedback = 0;
servoAnguloActual = clampInt(SERVO_ANGULO_CERRADO, 0, 180);
servoAnguloObjetivo = servoAnguloActual;
escribirServoAngulo(servoAnguloActual);
requestedIrisPct = 0;
appliedIrisPct = 0;
apagarMotorPorSeguridad();
lastDoorFeedbackSent = -1;
autoSeqState = AUTOSEQ_STARTUP_HOME_Z;
autoSeqStepStarted = false;
startupHomingDone = false;
Serial.println("Sistema listo.");
Serial.println("UART Nextion lista en GPIO23(RX) y GPIO25(TX)");
Serial.println("Steppers con AccelStepper.");
Serial.println("Home silencioso con runSpeed(): liberar -> buscar -> retroceder -> buscar lento.");
Serial.println("Microstepping 1/16 aplicado a ambos ejes.");
imprimirAyuda();
Serial.printf("Estado inicial puerta: %s\n",
puertaCerradaEstable ? "CERRADA" : "ABIERTA");
Serial.printf("Servo inicial: %d grados\n", servoAnguloActual);
Serial.printf("M1_RANGE_STEPS = %ld\n", M1_RANGE_STEPS);
Serial.printf("M2_RANGE_STEPS = %ld\n", M2_RANGE_STEPS);
Serial.printf("M2_RETURN_CUP_Y_STEPS = %ld\n", M2_RETURN_CUP_Y_STEPS);
}
void loop() {
leerSerialNoBloqueante();
readNextionFrames();
actualizarPuerta();
updateAutoSequence();
applyRequestedStateIfChanged();
actualizarRampaMotor();
actualizarServo();
handleCupRemove();
handleCupReturn();
axisUpdate(axis1, "M1");
axisUpdate(axis2, "M2");
updateHmiFeedback();
reportarEstadoSistema();
Programming and electronics gallery
Sketch of the electrical connections that our machine should have
biomaterial crusher connections.
developing the iris-shaped entrance.
Developing the Nextion screen interface
PCB completed with all the necessary outputs and inputs for the operation of the crusher
diagram of the parts of the crusher.
Iris test for opening and closing at the fiber entrance.
Blade shredding test to check DC motor power
Shredding test: we see that it shreds dry fibers well.
Modular design assembly and support structures
The BIOCRUSHER machine was designed using a modular approach, allowing each component to be fabricated, assembled and replaced independently. The structural system combines 3D printed parts, laser-cut panels and mechanical supports to ensure stability and adaptability during operation.
The support structure includes a rigid chassis made from laser-cut MDF/acrylic panels, while key mechanical components such as mounts, gears and guides were produced using 3D printing. This combination of digital fabrication techniques enables rapid prototyping, customization and easy maintenance of the machine.
Assembly and fabrication gallery
Designing the structure and casing of the crusher, after ensuring that the mechanical and electrical parts work.
Design with Nema stepper motors and the Z, X, Y axes
3D printed outer casing test, to make it modular.
Unlike unshredded and shredded fiber, our machine works.
Finishing the final adjustments and practicing the pitch.
And our machine is finished and it has very cheerful colors.
One final touch, now it will be easy to find our shredder in the dark
Final machine demonstration
Video. Final operation of the BIOCRUSHER machine showing the complete modular assembly, shredding mechanism and material collection system.
Problems and solutions
| Problem | Cause | Solution / action |
|---|---|---|
| Mechanical friction in the blade shafts | Alignment and tolerances between shaft, bearings and blade stack. | Checked bearing blocks, adjusted spacing and verified smooth manual rotation. |
| Possible clogging with long fibers | Fiber length and irregular feeding. | Added controlled iris inlet and tested different feed rates. |
| Safety risk when the chamber is open | Moving blades are exposed during loading or maintenance. | Added door sensor logic to block operation when open. |
| Motor speed not suitable for all fibers | Different fibers have different hardness and moisture levels. | Added material selection profiles for soft, medium and hard fibers. |
| Container alignment with outlet | Rail motion needed controlled positioning. | Used NEMA motors, limit switches and guided movement sequence. |
Future improvements
Automatic torque control
Add current sensing to detect overload and automatically reduce feed or stop the motor.
Improved material profiles
Store specific speed and time settings for cassava, coconut, banana and pineapple fibers.
Better container detection
Add more reliable full/empty sensing and automatic container exchange sequence.
Modular blade system
Design replaceable blades for different fiber types and different particle sizes.
IoT monitoring
Send machine status, processing time and material data to a remote dashboard.
Enclosed electronics
Improve cable management and add a protected electronics box for long-term use.
Conclusion
The BIOCRUSHER project successfully demonstrated the integration of mechanical design, digital fabrication, electronics and programming into a functional machine capable of processing fibrous biomaterials. The development process allowed the team to apply a multidisciplinary approach, combining CAD design, 3D printing, laser cutting and embedded systems to create a modular and scalable solution.
One of the main achievements of the project was the implementation of a dual-shaft shredding mechanism, capable of reducing the size of different types of fibers. This system, combined with a controlled feeding mechanism (iris) and a safety door, ensured both efficiency and safe operation during the shredding process.
The integration of the ESP32 microcontroller and the Nextion HMI interface enabled real-time monitoring and control of the machine. Through this interface, users can manage key parameters such as motor speed, operation time, and system status, improving usability and interaction with the machine.
Additionally, the implementation of a dual-axis linear motion system using stepper motors allowed precise positioning of the material collection container. This automation step significantly improved the workflow by enabling controlled material handling after the shredding process.
From a learning perspective, this project strengthened teamwork, problem-solving skills and the ability to integrate multiple technologies into a single system. The iterative design process allowed continuous improvement, especially in areas such as mechanical alignment, system stability and electronic integration.
Overall, BIOCRUSHER represents a functional prototype that demonstrates how digital fabrication and automation can be applied to develop sustainable solutions for biomaterial processing, particularly in the context of Amazonian resources.
Future Improvements and Recommendations
Although the BIOCRUSHER prototype achieved its main objectives, several improvements can be implemented to enhance performance, reliability and scalability of the system.
One of the key areas for improvement is the mechanical system. Future iterations could include the use of more resistant materials for the shredding blades, such as hardened steel, to increase durability when processing harder fibers. Additionally, improving shaft alignment and reducing mechanical tolerances would minimize friction and energy loss.
The motor control system could also be enhanced by implementing closed-loop control. By integrating current sensors or encoders, the system would be able to adjust speed and torque dynamically, preventing overload and improving efficiency during operation.
In terms of automation, the integration of additional sensors would improve system feedback and decision-making. For example, optical or weight sensors could be used to detect the amount of processed material, enabling automatic stopping or container replacement.
The Nextion interface can be further developed to include advanced features such as data logging, error reporting and customizable operation profiles for different types of biomaterials. This would allow users to optimize machine performance based on specific material properties.
Another important improvement would be the implementation of IoT capabilities. By connecting the ESP32 to a network, the machine could transmit real-time data, allow remote monitoring and enable predictive maintenance strategies.
From a structural perspective, the enclosure of the machine should be improved to increase safety and protect internal components from external factors such as dust and moisture. A fully enclosed system with transparent panels would also enhance user safety and visibility during operation.
Finally, future work could focus on scaling the machine and integrating it into a complete biomaterial production system, including processes such as fiber cooking, pulping and sheet formation. This would transform the BIOCRUSHER from a standalone prototype into a complete production solution.
.Team Experience and Weekly Anecdotes
Beyond the technical development, this week was also a valuable team-building experience. The BIOCRUSHER project required long working hours, constant collaboration and problem-solving under pressure. Throughout the process, the team strengthened communication, trust and coordination skills.
We spent extended sessions working together in the lab, often staying late to complete mechanical assemblies, test electronics and refine the system. These moments allowed us to share ideas, support each other and celebrate small achievements during the development process.
In between intensive work sessions, we also shared informal moments such as eating together, having snacks and enjoying time as a team. These experiences helped maintain motivation and created a positive and collaborative environment throughout the week.
This balance between technical work and team bonding was essential to complete the project successfully, making the experience not only productive but also memorable.
Team moments gallery
Team working late in the lab during assembly stage.
Group discussion and planning next steps.
Late-night debugging and testing session.
Sharing ideas during machine integration.
Team break with food after long working hours.
Celebrating progress after completing a milestone.
Collaborative work during electronics setup.
Leaving the lab late again, very late.
A photo from when we had to print in the UNI lab
Design files and downloads
The group page must include all design files used for the project: CAD, STL, DXF, electronics files, HMI files, source code, final slide and final video.