#include "Arduino.h"
// ============================================================================
// STUDENT CONFIGURATION
// ============================================================================
#define STUDENT_NUMBER 2248578
// ============================================================================
// SYSTEM PARAMETERS - AUTO-GENERATED FROM STUDENT_NUMBER
// DO NOT MODIFY MANUALLY - Computed by generateParameters()
// ============================================================================
struct SystemParams {
float v1, v2, v3; // Conveyor speeds (cm/s)
float d0, d1, d2, d3, d4; // Conv1 distances from obstruction sensor (cm)
float d5, d6; // Conv2/Conv3 total lengths (cm)
float L_min, L_max, L_threshold; // Length criteria (cm)
float W_min, W_max, W_threshold; // Weight criteria (g)
float T_gate; // Gate mechanical response time (ms)
int C1, C2, C3; // Area capacities (products)
int productInterval; // Product loading interval (ms)
};
SystemParams sp;
#define DIST_LEAD 10.0f // Fixed: entry point to obstruction sensor (cm)
#define DEBUG_PIN 12
// ============================================================================
// TYPE DEFINITIONS
// ============================================================================
enum class ProductEventType {
OBSTRUCTION_SENSOR_RISE,
OBSTRUCTION_SENSOR_FALL,
G2_CHECK, // Size gate check
WEIGHT_SENSOR_ENTER_WINDOW,
WEIGHT_SENSOR_EXIT_WINDOW,
G3_CHECK, // Weight gate check
BARCODE_SENSOR_ENTER_WINDOW,
BARCODE_SENSOR_EXIT_WINDOW,
G4_CHECK, // Routing gate check
ARRIVE_DESTINATION, // Product reaches final area
FINISH
};
struct Product {
float length; // Product length (cm)
float weight; // Product weight (g)
int barcodeID; // Barcode tracking number
};
struct ProductEvent {
uint64_t triggerTimeMicros;
ProductEventType eventType;
int gateExpected; // For gate checks: expected gate state (0 or 1)
int destArea; // For ARRIVE: destination area (0=A1, 1=A2, 2=A3)
};
struct ProductScheduler {
Product product;
ProductEvent events[16];
int totalEvents;
int currentEventIndex;
int debugPin;
hw_timer_t* timerHandle;
};
// Gate error counters: [0]=G2, [1]=G3, [2]=G4
// Check these to verify your gate control is correct (should all be 0)
volatile int errorGateCNT[3] = {0};
// Ground truth area counts (maintained by simulator)
volatile int simAreaCount[3] = {0, 0, 0}; // Area1, Area2, Area3
extern void startSimulator(void);
// ============================================================================
// PARAMETER GENERATION (deterministic from student number)
// ============================================================================
static uint32_t paramHash(uint32_t seed, uint32_t idx) {
uint32_t v = seed * 2654435761u + idx * 2246822519u;
v ^= v >> 16;
v *= 0x45d9f3bu;
v ^= v >> 16;
return v;
}
static float paramRangeF(uint32_t seed, uint32_t idx, float lo, float hi) {
return lo + (float)(paramHash(seed, idx) % 10001u) / 10000.0f * (hi - lo);
}
static int paramRangeI(uint32_t seed, uint32_t idx, int lo, int hi) {
return lo + (int)(paramHash(seed, idx) % (uint32_t)(hi - lo + 1));
}
void generateParameters(uint32_t sn) {
if (sn == 0) {
// Default parameters (no student number set)
sp.v1 = 100.0f; sp.v2 = 120.0f; sp.v3 = 80.0f;
sp.d0 = 15.0f; sp.d1 = 25.0f; sp.d2 = 35.0f;
sp.d3 = 45.0f; sp.d4 = 55.0f;
sp.d5 = 40.0f; sp.d6 = 40.0f;
sp.L_min = 4.5f; sp.L_max = 5.5f; sp.L_threshold = 5.0f;
sp.W_min = 90.0f; sp.W_max = 110.0f; sp.W_threshold = 100.0f;
sp.T_gate = 3.0f;
sp.C1 = 5; sp.C2 = 10; sp.C3 = 10;
sp.productInterval = 500;
return;
}
sp.v1 = paramRangeF(sn, 1, 80.0f, 120.0f);
sp.v2 = paramRangeF(sn, 2, 100.0f, 150.0f);
sp.v3 = paramRangeF(sn, 3, 60.0f, 100.0f);
sp.d0 = paramRangeF(sn, 4, 12.0f, 20.0f);
sp.d1 = sp.d0 + paramRangeF(sn, 5, 8.0f, 15.0f);
sp.d2 = sp.d1 + paramRangeF(sn, 6, 8.0f, 15.0f);
sp.d3 = sp.d2 + paramRangeF(sn, 7, 8.0f, 15.0f);
sp.d4 = sp.d3 + paramRangeF(sn, 8, 8.0f, 15.0f);
sp.d5 = paramRangeF(sn, 9, 30.0f, 50.0f);
sp.d6 = paramRangeF(sn, 10, 30.0f, 50.0f);
sp.L_min = paramRangeF(sn, 11, 4.0f, 5.0f);
sp.L_max = sp.L_min + paramRangeF(sn, 12, 0.8f, 1.5f);
sp.L_threshold = (sp.L_min + sp.L_max) / 2.0f;
sp.W_min = paramRangeF(sn, 13, 80.0f, 100.0f);
sp.W_max = sp.W_min + paramRangeF(sn, 14, 15.0f, 30.0f);
sp.W_threshold = (sp.W_min + sp.W_max) / 2.0f;
sp.T_gate = paramRangeF(sn, 15, 2.0f, 5.0f);
sp.C1 = paramRangeI(sn, 16, 3, 8);
sp.C2 = paramRangeI(sn, 17, 8, 15);
sp.C3 = paramRangeI(sn, 18, 8, 15);
sp.productInterval = paramRangeI(sn, 19, 400, 600);
}
void printParameters() {
Serial.println("========== SmartSort System Parameters ==========");
Serial.printf("Student Number: %u\n", (unsigned)STUDENT_NUMBER);
Serial.println("----- Conveyor Speeds -----");
Serial.printf(" v1 (Conv1): %.1f cm/s\n", sp.v1);
Serial.printf(" v2 (Conv2): %.1f cm/s\n", sp.v2);
Serial.printf(" v3 (Conv3): %.1f cm/s\n", sp.v3);
Serial.println("----- Distances (from obstruction sensor, cm) -----");
Serial.printf(" d0 (to G2): %.1f\n", sp.d0);
Serial.printf(" d1 (to Weight): %.1f\n", sp.d1);
Serial.printf(" d2 (to G3): %.1f\n", sp.d2);
Serial.printf(" d3 (to Barcode): %.1f\n", sp.d3);
Serial.printf(" d4 (to G4): %.1f\n", sp.d4);
Serial.printf(" d5 (Conv2 len): %.1f\n", sp.d5);
Serial.printf(" d6 (Conv3 len): %.1f\n", sp.d6);
Serial.println("----- Length Criteria (cm) -----");
Serial.printf(" L_min=%.2f L_max=%.2f L_threshold=%.2f\n", sp.L_min, sp.L_max, sp.L_threshold);
Serial.println("----- Weight Criteria (g) -----");
Serial.printf(" W_min=%.2f W_max=%.2f W_threshold=%.2f\n", sp.W_min, sp.W_max, sp.W_threshold);
Serial.println("----- Timing & Capacity -----");
Serial.printf(" T_gate=%.1f ms Interval=%d ms\n", sp.T_gate, sp.productInterval);
Serial.printf(" C1=%d C2=%d C3=%d\n", sp.C1, sp.C2, sp.C3);
Serial.println("=================================================");
}
// ============================================================================
// PRODUCT ARRAY - Generated based on parameters to cover all sorting paths
// Students may modify this array for additional testing
// ============================================================================
#define MAX_TEST_PRODUCTS 20
Product productArray[MAX_TEST_PRODUCTS];
int numProducts = 0;
void generateProductArray() {
int idx = 0;
float Lmid = (sp.L_min + sp.L_max) / 2.0f;
float Wmid = (sp.W_min + sp.W_max) / 2.0f;
// Category 1: Size abnormal (too short) -> Area 1 via G2
productArray[idx++] = {sp.L_min - 0.5f, Wmid, 1001};
productArray[idx++] = {sp.L_min - 1.0f, Wmid + 3.0f, 1002};
// Category 2: Size abnormal (too long) -> Area 1 via G2
productArray[idx++] = {sp.L_max + 0.5f, Wmid, 1003};
productArray[idx++] = {sp.L_max + 0.8f, Wmid - 2.0f, 1004};
// Category 3: Normal size, weight too light -> Area 1 via G3
productArray[idx++] = {Lmid, sp.W_min - 5.0f, 1005};
productArray[idx++] = {sp.L_min + 0.1f, sp.W_min - 3.0f, 1006};
// Category 4: Normal size, weight too heavy -> Area 1 via G3
productArray[idx++] = {Lmid, sp.W_max + 5.0f, 1007};
productArray[idx++] = {sp.L_max - 0.1f, sp.W_max + 3.0f, 1008};
// Category 5: Normal, small & light -> Area 2 (L<=Lthresh AND W<=Wthresh)
productArray[idx++] = {sp.L_min + 0.1f, sp.W_min + 1.0f, 1009};
productArray[idx++] = {sp.L_threshold, sp.W_threshold, 1010}; // Edge case: exactly at threshold
productArray[idx++] = {sp.L_threshold - 0.1f, sp.W_threshold - 1.0f, 1011};
// Category 6: Normal, large or heavy -> Area 3
productArray[idx++] = {sp.L_threshold + 0.1f, sp.W_threshold - 1.0f, 1012};
productArray[idx++] = {sp.L_min + 0.2f, sp.W_threshold + 1.0f, 1013};
productArray[idx++] = {sp.L_max - 0.1f, sp.W_max - 1.0f, 1014};
productArray[idx++] = {sp.L_threshold + 0.2f, sp.W_threshold + 2.0f, 1015};
// Edge cases
productArray[idx++] = {sp.L_min, sp.W_min, 1016}; // Exactly at min boundaries -> Area 2
productArray[idx++] = {sp.L_max, sp.W_max, 1017}; // Exactly at max -> Area 3
productArray[idx++] = {Lmid, Wmid, 1018}; // Center values -> Area 2
numProducts = idx;
}
/*!!!!!!!!!!!!!!!!!!ANY CODE ABOVE THIS LINE SHOULD NOT BE MODIFIED BY STUDENTS!!!!!!!!!!!!!!!!!!!*/
/*=========================== INTERFACE BETWEEN SIMULATOR AND STUDENT CODE ============================*/
/*
g_obstructionSensorPin outputs the physical signal of the obstruction sensor (for oscilloscope).
*/
#define g_obstructionSensorPin 32
/*
Debug output pins for gate signals (for oscilloscope verification).
The simulator does NOT read these - they are for your debugging only.
*/
#define gate2DebugPin 33
#define gate3DebugPin 27
#define gate4DebugPin 14
/*
SHARED VARIABLES - DO NOT RENAME
The simulator uses these to provide sensor data and check your gate controls.
*/
// ========== Simulator writes, students read ==========
volatile bool g_obstructionSensor = false; // Obstruction sensor state
volatile int g_barcodeReader = 0; // Barcode reading (0=invalid/not in window)
volatile float g_weightSensor = 0.0f; // Weight reading (0=invalid/not in window)
// ========== Students write, simulator reads ==========
// G1 (Intake): true=allow products in, false=block entry
volatile bool g_gate1Ctrl = true;
// G2 (Size divert): false=let pass, true=activate pusher (divert to Area 1)
volatile bool g_gate2Ctrl = false;
// G3 (Weight divert): false=let pass, true=activate pusher (divert to Area 1)
volatile bool g_gate3Ctrl = false;
// G4 (Routing): false=route to Conv2/Area2, true=route to Conv3/Area3
volatile bool g_gate4Ctrl = false;
/*================================= IMPLEMENT YOUR RTOS CODE BELOW ===================================*/
// ============================================================================
// CONSTANTS
// ============================================================================
#define LEN_EPS_CM 0.005f
#define WGT_EPS_G 0.005f
#define STATUS_HISTORY_SIZE 6
#define GATE_QUEUE_SIZE 32
#define ARRIVAL_QUEUE_SIZE 24
// ============================================================================
// ENUMS
// ============================================================================
typedef enum {
STATE_NEW_PRODUCT = 0,
STATE_LENGTH_READY,
STATE_WAIT_WEIGHT,
STATE_WEIGHT_READY,
STATE_WAIT_BARCODE,
STATE_BARCODE_READY,
STATE_FINISHED,
STATE_ABORTED
} ParcelState;
typedef enum {
DEST_NONE = 0,
DEST_A1 = 1,
DEST_A2 = 2,
DEST_A3 = 3
} Destination;
typedef enum {
GATE_G2 = 2,
GATE_G3 = 3,
GATE_G4 = 4
} GateId;
// ============================================================================
// STRUCTURES
// ============================================================================
typedef struct {
int64_t riseUs;
int64_t fallUs;
} BeamEdges;
typedef struct {
uint32_t sequenceId;
uint32_t epoch;
BeamEdges beam;
ParcelState state;
Destination destination;
float lengthCm;
float weightG;
int barcode;
int64_t g2CheckUs;
int64_t g3CheckUs;
int64_t g4CheckUs;
} ParcelContext;
typedef struct {
uint32_t sequenceId;
int barcode;
float lengthCm;
float weightG;
Destination destination;
} RecentParcel;
typedef struct {
int occupied[3]; // A1, A2, A3
int travelling[3]; // A1, A2, A3
float sumLengthAll;
float sumWeightAll;
int countAll;
float sumLengthA2;
float sumWeightA2;
int countA2;
float sumLengthA3;
float sumWeightA3;
int countA3;
} SortState;
typedef struct {
GateId gate;
bool stateRequired;
int64_t onTimeUs;
int64_t gateArrivalUs;
int64_t offTimeUs;
uint32_t epoch;
} GateJob;
typedef struct {
GateId gate;
QueueHandle_t queue;
} GateTaskParam;
typedef struct {
uint32_t sequenceId;
int barcode;
float lengthCm;
float weightG;
Destination destination;
int64_t arrivalTimeUs;
uint32_t epoch;
} ArrivalJob;
// ============================================================================
// GLOBAL VARIABLES
// ============================================================================
static QueueHandle_t beamQueue = NULL;
static QueueHandle_t gateQueueG2 = NULL;
static QueueHandle_t gateQueueG3 = NULL;
static QueueHandle_t gateQueueG4 = NULL;
static QueueHandle_t arrivalQueue = NULL;
static SemaphoreHandle_t stateMutex = NULL;
static volatile BeamEdges activeBeam = {0, 0};
static SortState sortState = {0};
static RecentParcel recentList[STATUS_HISTORY_SIZE];
static int recentWriteIndex = 0;
static int recentCount = 0;
static volatile uint32_t nextSequenceId = 1;
static volatile uint32_t currentEpoch = 1;
static volatile bool emergencyStop = false;
static volatile bool intakeClosedByCapacity = false;
static volatile bool capacityMessagePrinted = false;
static volatile int capacityBlockedArea = 0;
static volatile int64_t g2LastAppliedArrivalUs = 0;
static volatile int64_t g3LastAppliedArrivalUs = 0;
static volatile int64_t g4LastAppliedArrivalUs = 0;
static volatile int64_t g2LastReleaseUs = 0;
static volatile int64_t g3LastReleaseUs = 0;
static volatile int64_t g4LastReleaseUs = 0;
static GateTaskParam gateParamG2;
static GateTaskParam gateParamG3;
static GateTaskParam gateParamG4;
// ============================================================================
// FORWARD DECLARATIONS
// ============================================================================
static int64_t travelUs(float distanceCm, float speedCmPerSec);
static bool epochValid(uint32_t epoch);
static void waitUntilUs(int64_t targetUs, uint32_t epoch);
static bool lengthOk(float lengthCm);
static bool weightOk(float weightG);
static bool qualifiesArea2(float lengthCm, float weightG);
static void updateG1CapacityControl();
static void reserveDestination(Destination dest);
static void completeDestinationArrival(const ArrivalJob *job);
static void addRecentRecord(const ArrivalJob *job);
static float readWeightTimed(int64_t centreUs, float lengthCm, uint32_t epoch);
static int readBarcodeTimed(int64_t centreUs, float lengthCm, uint32_t epoch);
static volatile bool* gateOutputPointer(GateId gate);
static volatile int64_t* gateLastAppliedPointer(GateId gate);
static volatile int64_t* gateLastReleasePointer(GateId gate);
static QueueHandle_t gateQueueFromId(GateId gate);
static void submitGateJob(GateId gate,
bool requiredState,
int64_t gateCheckUs,
float lengthCm,
uint32_t epoch);
static void submitArrivalJob(const ParcelContext *parcel, int64_t arrivalUs);
static void resetController();
static void clearDestinationAreas();
void parcelStateMachineTask(void *pvParameters);
void gateControlTask(void *pvParameters);
void arrivalManagerTask(void *pvParameters);
void productProcessingTask(void *pvParameters);
void backgroundTask(void *pvParameters);
// ============================================================================
// TIME HELPERS
// ============================================================================
static int64_t travelUs(float distanceCm, float speedCmPerSec) {
if (speedCmPerSec <= 0.0f) {
return 0;
}
return (int64_t)((distanceCm / speedCmPerSec) * 1000000.0f);
}
static bool epochValid(uint32_t epoch) {
return epoch == currentEpoch;
}
static void waitUntilUs(int64_t targetUs, uint32_t epoch) {
while (!emergencyStop && epochValid(epoch)) {
int64_t nowUs = esp_timer_get_time();
int64_t remainingUs = targetUs - nowUs;
if (remainingUs <= 0) {
return;
}
if (remainingUs > 4000) {
int delayMs = (int)((remainingUs - 2000) / 1000);
if (delayMs < 1) {
delayMs = 1;
}
vTaskDelay(pdMS_TO_TICKS(delayMs));
}
else {
delayMicroseconds((uint32_t)remainingUs);
return;
}
}
}
// ============================================================================
// CLASSIFICATION HELPERS
// ============================================================================
static bool lengthOk(float lengthCm) {
return (lengthCm >= (sp.L_min - LEN_EPS_CM) &&
lengthCm <= (sp.L_max + LEN_EPS_CM));
}
static bool weightOk(float weightG) {
return (weightG >= (sp.W_min - WGT_EPS_G) &&
weightG <= (sp.W_max + WGT_EPS_G));
}
static bool qualifiesArea2(float lengthCm, float weightG) {
return (lengthCm <= sp.L_threshold &&
weightG <= sp.W_threshold);
}
// ============================================================================
// CAPACITY AND STATISTICS
// ============================================================================
static void updateG1CapacityControl() {
if (stateMutex == NULL) {
return;
}
if (sp.C1 <= 0 || sp.C2 <= 0 || sp.C3 <= 0) {
g_gate1Ctrl = true;
intakeClosedByCapacity = false;
capacityMessagePrinted = false;
capacityBlockedArea = 0;
return;
}
xSemaphoreTake(stateMutex, portMAX_DELAY);
int blockedArea = 0;
if ((sortState.occupied[0] + sortState.travelling[0]) >= sp.C1) {
blockedArea = 1;
}
else if ((sortState.occupied[1] + sortState.travelling[1]) >= sp.C2) {
blockedArea = 2;
}
else if ((sortState.occupied[2] + sortState.travelling[2]) >= sp.C3) {
blockedArea = 3;
}
if (emergencyStop) {
g_gate1Ctrl = false;
}
else if (blockedArea != 0) {
g_gate1Ctrl = false;
intakeClosedByCapacity = true;
capacityBlockedArea = blockedArea;
}
else {
g_gate1Ctrl = true;
intakeClosedByCapacity = false;
capacityMessagePrinted = false;
capacityBlockedArea = 0;
}
xSemaphoreGive(stateMutex);
}
static void reserveDestination(Destination dest) {
int index = ((int)dest) - 1;
if (index < 0 || index > 2 || stateMutex == NULL) {
return;
}
xSemaphoreTake(stateMutex, portMAX_DELAY);
sortState.travelling[index]++;
xSemaphoreGive(stateMutex);
updateG1CapacityControl();
}
static void addRecentRecord(const ArrivalJob *job) {
if (job == NULL || stateMutex == NULL) {
return;
}
xSemaphoreTake(stateMutex, portMAX_DELAY);
recentList[recentWriteIndex].sequenceId = job->sequenceId;
recentList[recentWriteIndex].barcode = job->barcode;
recentList[recentWriteIndex].lengthCm = job->lengthCm;
recentList[recentWriteIndex].weightG = job->weightG;
recentList[recentWriteIndex].destination = job->destination;
recentWriteIndex = (recentWriteIndex + 1) % STATUS_HISTORY_SIZE;
if (recentCount < STATUS_HISTORY_SIZE) {
recentCount++;
}
xSemaphoreGive(stateMutex);
}
static void completeDestinationArrival(const ArrivalJob *job) {
if (job == NULL || stateMutex == NULL) {
return;
}
int index = ((int)job->destination) - 1;
if (index < 0 || index > 2) {
return;
}
xSemaphoreTake(stateMutex, portMAX_DELAY);
if (sortState.travelling[index] > 0) {
sortState.travelling[index]--;
}
sortState.occupied[index]++;
sortState.sumLengthAll += job->lengthCm;
sortState.sumWeightAll += job->weightG;
sortState.countAll++;
if (job->destination == DEST_A2) {
sortState.sumLengthA2 += job->lengthCm;
sortState.sumWeightA2 += job->weightG;
sortState.countA2++;
}
else if (job->destination == DEST_A3) {
sortState.sumLengthA3 += job->lengthCm;
sortState.sumWeightA3 += job->weightG;
sortState.countA3++;
}
xSemaphoreGive(stateMutex);
addRecentRecord(job);
updateG1CapacityControl();
}
// ============================================================================
// SENSOR TIMING
// ============================================================================
static float readWeightTimed(int64_t centreUs, float lengthCm, uint32_t epoch) {
float weight = 0.0f;
int64_t halfWindowUs = travelUs(lengthCm * 0.10f, sp.v1);
int64_t startUs = centreUs - halfWindowUs + 300;
int64_t endUs = centreUs + halfWindowUs - 300;
waitUntilUs(startUs, epoch);
while (!emergencyStop && epochValid(epoch) && esp_timer_get_time() <= endUs) {
if (g_weightSensor > 0.0f) {
weight = g_weightSensor;
break;
}
delayMicroseconds(300);
}
return weight;
}
static int readBarcodeTimed(int64_t centreUs, float lengthCm, uint32_t epoch) {
int code = 0;
int64_t halfWindowUs = travelUs(lengthCm * 0.10f, sp.v1);
int64_t startUs = centreUs - halfWindowUs + 300;
int64_t endUs = centreUs + halfWindowUs - 300;
waitUntilUs(startUs, epoch);
while (!emergencyStop && epochValid(epoch) && esp_timer_get_time() <= endUs) {
if (g_barcodeReader != 0) {
code = g_barcodeReader;
break;
}
delayMicroseconds(300);
}
return code;
}
// ============================================================================
// SERIALIZED PER-GATE CONTROL
// ============================================================================
static volatile bool* gateOutputPointer(GateId gate) {
switch (gate) {
case GATE_G2:
return &g_gate2Ctrl;
case GATE_G3:
return &g_gate3Ctrl;
case GATE_G4:
return &g_gate4Ctrl;
default:
return NULL;
}
}
static volatile int64_t* gateLastAppliedPointer(GateId gate) {
switch (gate) {
case GATE_G2:
return &g2LastAppliedArrivalUs;
case GATE_G3:
return &g3LastAppliedArrivalUs;
case GATE_G4:
return &g4LastAppliedArrivalUs;
default:
return NULL;
}
}
static volatile int64_t* gateLastReleasePointer(GateId gate) {
switch (gate) {
case GATE_G2:
return &g2LastReleaseUs;
case GATE_G3:
return &g3LastReleaseUs;
case GATE_G4:
return &g4LastReleaseUs;
default:
return NULL;
}
}
static QueueHandle_t gateQueueFromId(GateId gate) {
switch (gate) {
case GATE_G2:
return gateQueueG2;
case GATE_G3:
return gateQueueG3;
case GATE_G4:
return gateQueueG4;
default:
return NULL;
}
}
static void submitGateJob(GateId gate,
bool requiredState,
int64_t gateCheckUs,
float lengthCm,
uint32_t epoch) {
if (!epochValid(epoch)) {
return;
}
QueueHandle_t q = gateQueueFromId(gate);
if (q == NULL) {
return;
}
GateJob job;
int64_t leadUs = (int64_t)(sp.T_gate * 1000.0f);
job.gate = gate;
job.stateRequired = requiredState;
// Product front edge reaches the gate at gateCheckUs.
job.gateArrivalUs = gateCheckUs;
// Gate must start moving before the product reaches the gate.
job.onTimeUs = gateCheckUs - leadUs;
// Product clears the gate after its own length has travelled past the gate.
job.offTimeUs = gateCheckUs + travelUs(lengthCm, sp.v1);
job.epoch = epoch;
int64_t nowUs = esp_timer_get_time();
if (job.onTimeUs < nowUs) {
job.onTimeUs = nowUs;
}
xQueueSend(q, &job, pdMS_TO_TICKS(10));
}
void gateControlTask(void *pvParameters) {
GateTaskParam *param = (GateTaskParam *)pvParameters;
if (param == NULL || param->queue == NULL) {
vTaskDelete(NULL);
return;
}
GateJob job;
while (true) {
if (xQueueReceive(param->queue, &job, portMAX_DELAY) != pdTRUE) {
continue;
}
if (emergencyStop || !epochValid(job.epoch)) {
continue;
}
volatile bool *gateSignal = gateOutputPointer(job.gate);
volatile int64_t *lastAppliedArrival = gateLastAppliedPointer(job.gate);
volatile int64_t *lastRelease = gateLastReleasePointer(job.gate);
if (gateSignal == NULL ||
lastAppliedArrival == NULL ||
lastRelease == NULL) {
continue;
}
int64_t activationTimeUs = job.onTimeUs;
if (activationTimeUs < *lastRelease) {
activationTimeUs = *lastRelease;
}
waitUntilUs(activationTimeUs, job.epoch);
if (emergencyStop || !epochValid(job.epoch)) {
continue;
}
if (job.gateArrivalUs >= *lastAppliedArrival) {
*lastAppliedArrival = job.gateArrivalUs;
*gateSignal = job.stateRequired;
}
int64_t releaseTimeUs = job.offTimeUs;
if (releaseTimeUs < activationTimeUs) {
releaseTimeUs = activationTimeUs;
}
waitUntilUs(releaseTimeUs, job.epoch);
if (emergencyStop || !epochValid(job.epoch)) {
continue;
}
if (job.gateArrivalUs == *lastAppliedArrival) {
*lastRelease = releaseTimeUs;
}
}
}
// ============================================================================
// ARRIVAL TRACKING ON CORE 1
// ============================================================================
static void submitArrivalJob(const ParcelContext *parcel, int64_t arrivalUs) {
if (parcel == NULL || arrivalQueue == NULL || !epochValid(parcel->epoch)) {
return;
}
ArrivalJob job;
job.sequenceId = parcel->sequenceId;
job.barcode = parcel->barcode;
job.lengthCm = parcel->lengthCm;
job.weightG = parcel->weightG;
job.destination = parcel->destination;
job.arrivalTimeUs = arrivalUs;
job.epoch = parcel->epoch;
xQueueSend(arrivalQueue, &job, pdMS_TO_TICKS(10));
}
void arrivalManagerTask(void *pvParameters) {
ArrivalJob job;
while (true) {
if (xQueueReceive(arrivalQueue, &job, portMAX_DELAY) == pdTRUE) {
if (!epochValid(job.epoch) || emergencyStop) {
continue;
}
waitUntilUs(job.arrivalTimeUs, job.epoch);
if (epochValid(job.epoch) && !emergencyStop) {
completeDestinationArrival(&job);
}
}
}
}
// ============================================================================
// RESET AND CLEAR
// ============================================================================
static void resetController() {
currentEpoch++;
if (currentEpoch == 0) {
currentEpoch = 1;
}
if (stateMutex != NULL) {
xSemaphoreTake(stateMutex, portMAX_DELAY);
memset(&sortState, 0, sizeof(sortState));
memset(recentList, 0, sizeof(recentList));
recentWriteIndex = 0;
recentCount = 0;
nextSequenceId = 1;
xSemaphoreGive(stateMutex);
}
if (beamQueue != NULL) {
xQueueReset(beamQueue);
}
if (gateQueueG2 != NULL) {
xQueueReset(gateQueueG2);
}
if (gateQueueG3 != NULL) {
xQueueReset(gateQueueG3);
}
if (gateQueueG4 != NULL) {
xQueueReset(gateQueueG4);
}
if (arrivalQueue != NULL) {
xQueueReset(arrivalQueue);
}
g2LastAppliedArrivalUs = 0;
g3LastAppliedArrivalUs = 0;
g4LastAppliedArrivalUs = 0;
g2LastReleaseUs = 0;
g3LastReleaseUs = 0;
g4LastReleaseUs = 0;
emergencyStop = false;
intakeClosedByCapacity = false;
capacityMessagePrinted = false;
capacityBlockedArea = 0;
g_gate1Ctrl = true;
g_gate2Ctrl = false;
g_gate3Ctrl = false;
g_gate4Ctrl = false;
}
static void clearDestinationAreas() {
if (stateMutex != NULL) {
xSemaphoreTake(stateMutex, portMAX_DELAY);
sortState.occupied[0] = 0;
sortState.occupied[1] = 0;
sortState.occupied[2] = 0;
xSemaphoreGive(stateMutex);
}
intakeClosedByCapacity = false;
capacityMessagePrinted = false;
capacityBlockedArea = 0;
updateG1CapacityControl();
}
// ============================================================================
// OBSTRUCTION SENSOR ISR
// ============================================================================
void IRAM_ATTR obstructionSensorInterrupt() {
BaseType_t shouldYield = pdFALSE;
if (g_obstructionSensor == true) {
activeBeam.riseUs = esp_timer_get_time();
}
else {
activeBeam.fallUs = esp_timer_get_time();
if (beamQueue != NULL) {
BeamEdges beamCopy;
beamCopy.riseUs = activeBeam.riseUs;
beamCopy.fallUs = activeBeam.fallUs;
xQueueSendFromISR(beamQueue, &beamCopy, &shouldYield);
}
if (shouldYield) {
portYIELD_FROM_ISR();
}
}
}
// ============================================================================
// PRODUCT DISPATCH TASK - CORE 0
// ============================================================================
void productProcessingTask(void *pvParameters) {
BeamEdges beam;
while (true) {
if (xQueueReceive(beamQueue, &beam, portMAX_DELAY) == pdTRUE) {
if (emergencyStop) {
continue;
}
ParcelContext *parcel =
(ParcelContext *)pvPortMalloc(sizeof(ParcelContext));
if (parcel == NULL) {
continue;
}
memset(parcel, 0, sizeof(ParcelContext));
parcel->sequenceId = nextSequenceId++;
parcel->epoch = currentEpoch;
parcel->beam = beam;
parcel->state = STATE_NEW_PRODUCT;
parcel->destination = DEST_NONE;
parcel->barcode = 0;
parcel->weightG = 0.0f;
BaseType_t created = xTaskCreatePinnedToCore(
parcelStateMachineTask,
"ParcelFSM",
4096,
parcel,
8,
NULL,
0
);
if (created != pdPASS) {
vPortFree(parcel);
}
}
}
}
// ============================================================================
// PARCEL STATE MACHINE TASK - CORE 0
// ============================================================================
void parcelStateMachineTask(void *pvParameters) {
ParcelContext *parcel = (ParcelContext *)pvParameters;
if (parcel == NULL) {
vTaskDelete(NULL);
return;
}
while (!emergencyStop && epochValid(parcel->epoch)) {
switch (parcel->state) {
case STATE_NEW_PRODUCT: {
int64_t blockedUs = parcel->beam.fallUs - parcel->beam.riseUs;
if (blockedUs <= 0) {
parcel->state = STATE_ABORTED;
break;
}
parcel->lengthCm = (float)blockedUs * sp.v1 / 1000000.0f;
parcel->g2CheckUs = parcel->beam.riseUs + travelUs(sp.d0, sp.v1);
parcel->g3CheckUs = parcel->beam.riseUs + travelUs(sp.d2, sp.v1);
parcel->g4CheckUs = parcel->beam.riseUs + travelUs(sp.d4, sp.v1);
parcel->state = STATE_LENGTH_READY;
break;
}
case STATE_LENGTH_READY: {
if (!lengthOk(parcel->lengthCm)) {
parcel->destination = DEST_A1;
parcel->weightG = 0.0f;
parcel->barcode = 0;
reserveDestination(DEST_A1);
submitGateJob(GATE_G2,
true,
parcel->g2CheckUs,
parcel->lengthCm,
parcel->epoch);
submitArrivalJob(parcel,
parcel->g2CheckUs + travelUs(parcel->lengthCm, sp.v1));
parcel->state = STATE_FINISHED;
}
else {
submitGateJob(GATE_G2,
false,
parcel->g2CheckUs,
parcel->lengthCm,
parcel->epoch);
parcel->state = STATE_WAIT_WEIGHT;
}
break;
}
case STATE_WAIT_WEIGHT: {
float centreDistance = sp.d1 - (parcel->lengthCm / 2.0f);
if (centreDistance < 0.0f) {
centreDistance = 0.0f;
}
int64_t centreUs =
parcel->beam.fallUs + travelUs(centreDistance, sp.v1);
parcel->weightG =
readWeightTimed(centreUs, parcel->lengthCm, parcel->epoch);
parcel->state = STATE_WEIGHT_READY;
break;
}
case STATE_WEIGHT_READY: {
if (!weightOk(parcel->weightG)) {
parcel->destination = DEST_A1;
parcel->barcode = 0;
reserveDestination(DEST_A1);
submitGateJob(GATE_G3,
true,
parcel->g3CheckUs,
parcel->lengthCm,
parcel->epoch);
submitArrivalJob(parcel,
parcel->g3CheckUs + travelUs(parcel->lengthCm, sp.v1));
parcel->state = STATE_FINISHED;
}
else {
submitGateJob(GATE_G3,
false,
parcel->g3CheckUs,
parcel->lengthCm,
parcel->epoch);
parcel->state = STATE_WAIT_BARCODE;
}
break;
}
case STATE_WAIT_BARCODE: {
float centreDistance = sp.d3 - (parcel->lengthCm / 2.0f);
if (centreDistance < 0.0f) {
centreDistance = 0.0f;
}
int64_t centreUs =
parcel->beam.fallUs + travelUs(centreDistance, sp.v1);
parcel->barcode =
readBarcodeTimed(centreUs, parcel->lengthCm, parcel->epoch);
parcel->state = STATE_BARCODE_READY;
break;
}
case STATE_BARCODE_READY: {
if (qualifiesArea2(parcel->lengthCm, parcel->weightG)) {
parcel->destination = DEST_A2;
reserveDestination(DEST_A2);
submitGateJob(GATE_G4,
false,
parcel->g4CheckUs,
parcel->lengthCm,
parcel->epoch);
int64_t arrivalUs =
parcel->g4CheckUs + travelUs(sp.d5, sp.v2);
submitArrivalJob(parcel, arrivalUs);
}
else {
parcel->destination = DEST_A3;
reserveDestination(DEST_A3);
submitGateJob(GATE_G4,
true,
parcel->g4CheckUs,
parcel->lengthCm,
parcel->epoch);
int64_t arrivalUs =
parcel->g4CheckUs + travelUs(sp.d6, sp.v3);
submitArrivalJob(parcel, arrivalUs);
}
parcel->state = STATE_FINISHED;
break;
}
case STATE_FINISHED:
case STATE_ABORTED:
default:
vPortFree(parcel);
vTaskDelete(NULL);
return;
}
}
vPortFree(parcel);
vTaskDelete(NULL);
}
// ============================================================================
// BACKGROUND TASK - CORE 1
// ============================================================================
void backgroundTask(void *pvParameters) {
TickType_t lastWake = xTaskGetTickCount();
while (true) {
while (Serial.available() > 0) {
String cmd = Serial.readStringUntil('\n');
cmd.trim();
if (cmd == "reset") {
resetController();
}
else if (cmd == "clear") {
clearDestinationAreas();
}
else if (cmd == "emergency") {
emergencyStop = true;
g_gate1Ctrl = false;
g_gate2Ctrl = false;
g_gate3Ctrl = false;
g_gate4Ctrl = false;
Serial.println("EMERGENCY: System halted");
}
else if (cmd == "stat") {
float Lavg = 0.0f;
float Wavg = 0.0f;
float L2avg = 0.0f;
float W2avg = 0.0f;
float L3avg = 0.0f;
float W3avg = 0.0f;
if (stateMutex != NULL) {
xSemaphoreTake(stateMutex, portMAX_DELAY);
if (sortState.countAll > 0) {
Lavg = sortState.sumLengthAll / sortState.countAll;
Wavg = sortState.sumWeightAll / sortState.countAll;
}
if (sortState.countA2 > 0) {
L2avg = sortState.sumLengthA2 / sortState.countA2;
W2avg = sortState.sumWeightA2 / sortState.countA2;
}
if (sortState.countA3 > 0) {
L3avg = sortState.sumLengthA3 / sortState.countA3;
W3avg = sortState.sumWeightA3 / sortState.countA3;
}
xSemaphoreGive(stateMutex);
}
Serial.printf("sortSTAT: %.2f,%.2f,%.2f,%.2f,%.2f,%.2f\n",
Lavg, L2avg, L3avg, Wavg, W2avg, W3avg);
}
}
updateG1CapacityControl();
if (intakeClosedByCapacity && !capacityMessagePrinted) {
Serial.printf("Area %d Capacity is full. Please clear the area, then type clear to continue.\n",
capacityBlockedArea);
capacityMessagePrinted = true;
}
if (stateMutex != NULL) {
xSemaphoreTake(stateMutex, portMAX_DELAY);
if (emergencyStop || intakeClosedByCapacity) {}
else {
Serial.printf("sortRT: %03d,%03d,%03d",
sortState.occupied[0],
sortState.occupied[1],
sortState.occupied[2]);
for (int i = 0; i < recentCount; i++) {
int idx =
(recentWriteIndex - recentCount + i + STATUS_HISTORY_SIZE)
% STATUS_HISTORY_SIZE;
RecentParcel p = recentList[idx];
Serial.printf(",%d,%.1f,%.1f,A%d",
p.barcode,
p.lengthCm,
p.weightG,
(int)p.destination);
}
Serial.println();
}
xSemaphoreGive(stateMutex);
}
vTaskDelayUntil(&lastWake, pdMS_TO_TICKS(1000));
}
}
// ============================================================================
// SETUP
// ============================================================================
void setup() {
Serial.begin(115200);
beamQueue = xQueueCreate(10, sizeof(BeamEdges));
if (beamQueue == NULL) {
Serial.println("ERROR: beamQueue creation failed");
}
gateQueueG2 = xQueueCreate(GATE_QUEUE_SIZE, sizeof(GateJob));
if (gateQueueG2 == NULL) {
Serial.println("ERROR: gateQueueG2 creation failed");
}
gateQueueG3 = xQueueCreate(GATE_QUEUE_SIZE, sizeof(GateJob));
if (gateQueueG3 == NULL) {
Serial.println("ERROR: gateQueueG3 creation failed");
}
gateQueueG4 = xQueueCreate(GATE_QUEUE_SIZE, sizeof(GateJob));
if (gateQueueG4 == NULL) {
Serial.println("ERROR: gateQueueG4 creation failed");
}
arrivalQueue = xQueueCreate(ARRIVAL_QUEUE_SIZE, sizeof(ArrivalJob));
if (arrivalQueue == NULL) {
Serial.println("ERROR: arrivalQueue creation failed");
}
stateMutex = xSemaphoreCreateMutex();
if (stateMutex == NULL) {
Serial.println("ERROR: stateMutex creation failed");
}
g_gate1Ctrl = true;
g_gate2Ctrl = false;
g_gate3Ctrl = false;
g_gate4Ctrl = false;
gateParamG2.gate = GATE_G2;
gateParamG2.queue = gateQueueG2;
gateParamG3.gate = GATE_G3;
gateParamG3.queue = gateQueueG3;
gateParamG4.gate = GATE_G4;
gateParamG4.queue = gateQueueG4;
xTaskCreatePinnedToCore(
gateControlTask,
"GateG2",
4096,
&gateParamG2,
11,
NULL,
0
);
xTaskCreatePinnedToCore(
gateControlTask,
"GateG3",
4096,
&gateParamG3,
11,
NULL,
0
);
xTaskCreatePinnedToCore(
gateControlTask,
"GateG4",
4096,
&gateParamG4,
11,
NULL,
0
);
xTaskCreatePinnedToCore(
productProcessingTask,
"BeamDispatcher",
4096,
NULL,
10,
NULL,
0
);
xTaskCreatePinnedToCore(
arrivalManagerTask,
"ArrivalManager",
4096,
NULL,
4,
NULL,
1
);
xTaskCreatePinnedToCore(
backgroundTask,
"StatusTask",
4096,
NULL,
2,
NULL,
1
);
startSimulator();
}
// ============================================================================
// LOOP
// ============================================================================
void loop() {
vTaskDelay(portMAX_DELAY);
}
/******************************************** END OF STUDENT CODE *****************************************/
/*!!!!!!!!!!!!!!!!!!!!!!!!!!! ANY CODE BELOW THIS LINE SHOULD NOT BE MODIFIED !!!!!!!!!!!!!!!!!!!!!!!!!!!*/
/*================================ START OF SIMULATOR ENGINE ============================================*/
volatile int currentProductIndex = 0;
const int MAX_SCHEDULERS = 4;
ProductScheduler g_schedulers[MAX_SCHEDULERS];
static inline uint64_t distanceToMicros(float distance_cm, float speed_cm_s) {
double tSec = (double)distance_cm / (double)speed_cm_s;
return (uint64_t)(tSec * 1e6);
}
void fillProductEvents(ProductScheduler &sch) {
const Product &p = sch.product;
sch.totalEvents = 0;
sch.currentEventIndex = 0;
auto &events = sch.events;
int idx = 0;
uint64_t leadTime = distanceToMicros(DIST_LEAD, sp.v1);
// Determine product's ground-truth path
bool sizeOk = (p.length >= sp.L_min && p.length <= sp.L_max);
bool weightOk = (p.weight >= sp.W_min && p.weight <= sp.W_max);
bool isSmallLight = sizeOk && weightOk &&
(p.length <= sp.L_threshold) && (p.weight <= sp.W_threshold);
// Pre-compute destination area index (0=A1, 1=A2, 2=A3)
int destArea;
if (!sizeOk) destArea = 0;
else if (!weightOk) destArea = 0;
else if (isSmallLight) destArea = 1;
else destArea = 2;
// 1. Obstruction sensor: front edge arrives
events[idx].triggerTimeMicros = leadTime;
events[idx].eventType = ProductEventType::OBSTRUCTION_SENSOR_RISE;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
// 2. Obstruction sensor: back edge leaves
uint64_t fallTime = distanceToMicros(p.length, sp.v1);
events[idx].triggerTimeMicros = leadTime + fallTime;
events[idx].eventType = ProductEventType::OBSTRUCTION_SENSOR_FALL;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
// 3. G2 check (size gate) - front edge at d0
// G2: true=divert (size abnormal), expected true if !sizeOk
uint64_t g2Time = distanceToMicros(sp.d0, sp.v1) + leadTime;
events[idx].triggerTimeMicros = g2Time;
events[idx].eventType = ProductEventType::G2_CHECK;
events[idx].gateExpected = sizeOk ? 0 : 1;
events[idx].destArea = 0;
idx++;
if (!sizeOk) {
// Product diverted at G2 -> Area 1
events[idx].triggerTimeMicros = g2Time + 5000;
events[idx].eventType = ProductEventType::ARRIVE_DESTINATION;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
events[idx].triggerTimeMicros = g2Time + 10000;
events[idx].eventType = ProductEventType::FINISH;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
} else {
// 4. Weight sensor window
uint64_t centerAtWeight = distanceToMicros(sp.d1 + p.length / 2.0f, sp.v1) + leadTime;
uint64_t halfWindowW = distanceToMicros(p.length * 0.1f, sp.v1);
events[idx].triggerTimeMicros = centerAtWeight - halfWindowW;
events[idx].eventType = ProductEventType::WEIGHT_SENSOR_ENTER_WINDOW;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
events[idx].triggerTimeMicros = centerAtWeight + halfWindowW;
events[idx].eventType = ProductEventType::WEIGHT_SENSOR_EXIT_WINDOW;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
// 5. G3 check (weight gate) - front edge at d2
// G3: true=divert (weight abnormal), expected true if !weightOk
uint64_t g3Time = distanceToMicros(sp.d2, sp.v1) + leadTime;
events[idx].triggerTimeMicros = g3Time;
events[idx].eventType = ProductEventType::G3_CHECK;
events[idx].gateExpected = weightOk ? 0 : 1;
events[idx].destArea = 0;
idx++;
if (!weightOk) {
// Product diverted at G3 -> Area 1
events[idx].triggerTimeMicros = g3Time + 5000;
events[idx].eventType = ProductEventType::ARRIVE_DESTINATION;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
events[idx].triggerTimeMicros = g3Time + 10000;
events[idx].eventType = ProductEventType::FINISH;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
} else {
// 6. Barcode sensor window
uint64_t centerAtBarcode = distanceToMicros(sp.d3 + p.length / 2.0f, sp.v1) + leadTime;
uint64_t halfWindowB = distanceToMicros(p.length * 0.1f, sp.v1);
events[idx].triggerTimeMicros = centerAtBarcode - halfWindowB;
events[idx].eventType = ProductEventType::BARCODE_SENSOR_ENTER_WINDOW;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
events[idx].triggerTimeMicros = centerAtBarcode + halfWindowB;
events[idx].eventType = ProductEventType::BARCODE_SENSOR_EXIT_WINDOW;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
// 7. G4 check (routing gate) - front edge at d4
// G4: false=Conv2/Area2, true=Conv3/Area3
uint64_t g4Time = distanceToMicros(sp.d4, sp.v1) + leadTime;
events[idx].triggerTimeMicros = g4Time;
events[idx].eventType = ProductEventType::G4_CHECK;
events[idx].gateExpected = isSmallLight ? 0 : 1;
events[idx].destArea = 0;
idx++;
// 8. Arrive at destination area
uint64_t arriveTime;
if (isSmallLight) {
arriveTime = g4Time + distanceToMicros(sp.d5, sp.v2);
} else {
arriveTime = g4Time + distanceToMicros(sp.d6, sp.v3);
}
events[idx].triggerTimeMicros = arriveTime;
events[idx].eventType = ProductEventType::ARRIVE_DESTINATION;
events[idx].gateExpected = 0;
events[idx].destArea = destArea;
idx++;
events[idx].triggerTimeMicros = arriveTime + 5000;
events[idx].eventType = ProductEventType::FINISH;
events[idx].gateExpected = 0;
events[idx].destArea = 0;
idx++;
}
}
sch.totalEvents = idx;
// Sort events by time
for (int i = 0; i < sch.totalEvents - 1; i++) {
for (int j = i + 1; j < sch.totalEvents; j++) {
if (events[i].triggerTimeMicros > events[j].triggerTimeMicros) {
ProductEvent tmp = events[i];
events[i] = events[j];
events[j] = tmp;
}
}
}
}
void printProductEvents(const ProductScheduler &sch) {
Serial.println("===== Product Event Timeline =====");
Serial.printf("Length: %.2f cm Weight: %.2f g Barcode: %d\n",
sch.product.length, sch.product.weight, sch.product.barcodeID);
bool sizeOk = (sch.product.length >= sp.L_min && sch.product.length <= sp.L_max);
bool weightOk = (sch.product.weight >= sp.W_min && sch.product.weight <= sp.W_max);
const char* dest = "???";
if (!sizeOk) dest = "Area1(size)";
else if (!weightOk) dest = "Area1(weight)";
else if (sch.product.length <= sp.L_threshold && sch.product.weight <= sp.W_threshold) dest = "Area2";
else dest = "Area3";
Serial.printf("Expected destination: %s\n", dest);
for (int i = 0; i < sch.totalEvents; i++) {
const ProductEvent &evt = sch.events[i];
float timeMs = evt.triggerTimeMicros / 1000.0f;
Serial.printf(" %d: %.3f ms - ", i, timeMs);
switch (evt.eventType) {
case ProductEventType::OBSTRUCTION_SENSOR_RISE: Serial.println("OBSTRUCTION_RISE"); break;
case ProductEventType::OBSTRUCTION_SENSOR_FALL: Serial.println("OBSTRUCTION_FALL"); break;
case ProductEventType::G2_CHECK: Serial.println("G2_CHECK (size)"); break;
case ProductEventType::WEIGHT_SENSOR_ENTER_WINDOW: Serial.println("WEIGHT_ENTER"); break;
case ProductEventType::WEIGHT_SENSOR_EXIT_WINDOW: Serial.println("WEIGHT_EXIT"); break;
case ProductEventType::G3_CHECK: Serial.println("G3_CHECK (weight)"); break;
case ProductEventType::BARCODE_SENSOR_ENTER_WINDOW: Serial.println("BARCODE_ENTER"); break;
case ProductEventType::BARCODE_SENSOR_EXIT_WINDOW: Serial.println("BARCODE_EXIT"); break;
case ProductEventType::G4_CHECK: Serial.println("G4_CHECK (route)"); break;
case ProductEventType::ARRIVE_DESTINATION: Serial.println("ARRIVE_DESTINATION"); break;
case ProductEventType::FINISH: Serial.println("FINISH"); break;
default: Serial.println("UNKNOWN"); break;
}
}
Serial.println("==================================");
}
// Hardware timer ISR - executes product events
void ARDUINO_ISR_ATTR onTimerInterrupt(void* arg) {
ProductScheduler* sch = (ProductScheduler*)arg;
hw_timer_t* timer = sch->timerHandle;
if (!timer) return;
if (sch->currentEventIndex >= sch->totalEvents) {
timerEnd(timer);
sch->timerHandle = nullptr;
return;
}
// Get current event
ProductEvent evt = sch->events[sch->currentEventIndex];
sch->currentEventIndex++;
// Execute event logic (no floating-point comparisons - all pre-computed)
int evtType = (int)evt.eventType;
if (evtType == (int)ProductEventType::OBSTRUCTION_SENSOR_RISE) {
g_obstructionSensor = true;
digitalWrite(g_obstructionSensorPin, HIGH);
obstructionSensorInterrupt();
}
else if (evtType == (int)ProductEventType::OBSTRUCTION_SENSOR_FALL) {
g_obstructionSensor = false;
digitalWrite(g_obstructionSensorPin, LOW);
obstructionSensorInterrupt();
}
else if (evtType == (int)ProductEventType::WEIGHT_SENSOR_ENTER_WINDOW) {
g_weightSensor = sch->product.weight;
}
else if (evtType == (int)ProductEventType::WEIGHT_SENSOR_EXIT_WINDOW) {
g_weightSensor = 0.0f;
}
else if (evtType == (int)ProductEventType::BARCODE_SENSOR_ENTER_WINDOW) {
g_barcodeReader = sch->product.barcodeID;
}
else if (evtType == (int)ProductEventType::BARCODE_SENSOR_EXIT_WINDOW) {
g_barcodeReader = 0;
}
else if (evtType == (int)ProductEventType::G2_CHECK) {
// G2: true=divert. Pre-computed expected value in gateExpected
if ((int)g_gate2Ctrl != evt.gateExpected) {
errorGateCNT[0]++;
}
}
else if (evtType == (int)ProductEventType::G3_CHECK) {
// G3: true=divert. Pre-computed expected value in gateExpected
if ((int)g_gate3Ctrl != evt.gateExpected) {
errorGateCNT[1]++;
}
}
else if (evtType == (int)ProductEventType::G4_CHECK) {
// G4: false=Conv2, true=Conv3. Pre-computed expected value
if ((int)g_gate4Ctrl != evt.gateExpected) {
errorGateCNT[2]++;
}
}
else if (evtType == (int)ProductEventType::ARRIVE_DESTINATION) {
simAreaCount[evt.destArea]++;
}
else if (evtType == (int)ProductEventType::FINISH) {
digitalWrite(sch->debugPin, LOW);
}
// Set up next event or end timer
if (sch->currentEventIndex < sch->totalEvents) {
timerAlarm(timer, sch->events[sch->currentEventIndex].triggerTimeMicros, false, 0);
} else {
timerEnd(timer);
sch->timerHandle = nullptr;
}
}
hw_timer_t* allocateTimerForProduct(ProductScheduler &sch) {
digitalWrite(sch.debugPin, HIGH);
fillProductEvents(sch);
hw_timer_t* timer = timerBegin(1000000); // 1MHz = 1us resolution
if (!timer) return nullptr;
sch.timerHandle = timer;
timerAttachInterruptArg(timer, &onTimerInterrupt, (void*)&sch);
if (sch.totalEvents > 0) {
digitalWrite(sch.debugPin, LOW);
timerWrite(timer, 0);
timerAlarm(timer, sch.events[0].triggerTimeMicros, false, 0);
}
return timer;
}
// Status reporting task - prints simulator state periodically
void statusReportTask(void *pvParameters) {
vTaskDelay(2000 / portTICK_PERIOD_MS); // Initial delay
while (true) {
Serial.printf("[SIM] Products loaded: %d/%d | Area counts: A1=%d A2=%d A3=%d | Gate errors: G2=%d G3=%d G4=%d\n",
currentProductIndex, numProducts,
simAreaCount[0], simAreaCount[1], simAreaCount[2],
errorGateCNT[0], errorGateCNT[1], errorGateCNT[2]);
// Check if all products finished
if (currentProductIndex >= numProducts) {
bool allDone = true;
for (int i = 0; i < MAX_SCHEDULERS; i++) {
if (g_schedulers[i].timerHandle != nullptr) {
allDone = false;
break;
}
}
if (allDone) {
int totalArrived = simAreaCount[0] + simAreaCount[1] + simAreaCount[2];
Serial.println("\n=== SIMULATION COMPLETE ===");
Serial.printf("Total products processed: %d/%d\n", totalArrived, numProducts);
Serial.printf("Area 1: %d Area 2: %d Area 3: %d\n",
simAreaCount[0], simAreaCount[1], simAreaCount[2]);
Serial.printf("Gate errors: G2=%d G3=%d G4=%d\n",
errorGateCNT[0], errorGateCNT[1], errorGateCNT[2]);
if (errorGateCNT[0] == 0 && errorGateCNT[1] == 0 && errorGateCNT[2] == 0) {
Serial.println("Result: ALL GATES CORRECT!");
} else {
Serial.println("Result: GATE ERRORS DETECTED - check your control logic");
}
Serial.println("===========================\n");
vTaskDelete(NULL);
return;
}
}
vTaskDelay(2000 / portTICK_PERIOD_MS);
}
}
// Product loading task - loads products at fixed intervals, checks G1 gate
void productLoadingTask(void *pvParameters) {
TickType_t xLastWakeTime = xTaskGetTickCount();
while (true) {
if (currentProductIndex < numProducts) {
// Check G1 intake gate
if (g_gate1Ctrl) {
bool schedulerFound = false;
for (int i = 0; i < MAX_SCHEDULERS; i++) {
if (g_schedulers[i].timerHandle == nullptr) {
g_schedulers[i].product = productArray[currentProductIndex];
g_schedulers[i].debugPin = DEBUG_PIN + currentProductIndex % 3;
hw_timer_t* t = allocateTimerForProduct(g_schedulers[i]);
if (!t) {
Serial.println("ERROR: No hardware timer available!");
} else {
currentProductIndex++;
schedulerFound = true;
}
break;
}
}
if (!schedulerFound) {
// No scheduler available this cycle, will retry next interval
}
} else {
// G1 is closed - product blocked at intake
// The product remains in the queue, will be loaded when G1 opens
}
}
vTaskDelayUntil(&xLastWakeTime, sp.productInterval / portTICK_PERIOD_MS);
}
}
void startSimulator(void) {
// Generate parameters from student number
generateParameters(STUDENT_NUMBER);
printParameters();
// Generate test product array
generateProductArray();
Serial.printf("\nGenerated %d test products:\n", numProducts);
for (int i = 0; i < numProducts; i++) {
bool sizeOk = (productArray[i].length >= sp.L_min && productArray[i].length <= sp.L_max);
bool weightOk = (productArray[i].weight >= sp.W_min && productArray[i].weight <= sp.W_max);
const char* dest;
if (!sizeOk) dest = "A1(size)";
else if (!weightOk) dest = "A1(weight)";
else if (productArray[i].length <= sp.L_threshold && productArray[i].weight <= sp.W_threshold) dest = "A2";
else dest = "A3";
Serial.printf(" [%d] L=%.2f W=%.2f BC=%d -> %s\n",
i, productArray[i].length, productArray[i].weight, productArray[i].barcodeID, dest);
}
Serial.println();
// Setup GPIO pins
pinMode(g_obstructionSensorPin, OUTPUT);
pinMode(DEBUG_PIN, OUTPUT);
pinMode(DEBUG_PIN + 1, OUTPUT);
pinMode(DEBUG_PIN + 2, OUTPUT);
digitalWrite(DEBUG_PIN, LOW);
digitalWrite(DEBUG_PIN + 1, LOW);
digitalWrite(DEBUG_PIN + 2, LOW);
// Initialize sensor outputs
g_obstructionSensor = false;
g_barcodeReader = 0;
g_weightSensor = 0.0f;
// Initialize gate controls to default
g_gate1Ctrl = true;
g_gate2Ctrl = false;
g_gate3Ctrl = false;
g_gate4Ctrl = false;
// Reset counters
currentProductIndex = 0;
for (int i = 0; i < MAX_SCHEDULERS; i++) {
g_schedulers[i].timerHandle = nullptr;
}
for (int i = 0; i < 3; i++) {
errorGateCNT[i] = 0;
simAreaCount[i] = 0;
}
// Create product loading task (highest priority)
xTaskCreate(
productLoadingTask,
"ProductLoader",
2048,
NULL,
configMAX_PRIORITIES - 1,
NULL
);
// Create status reporting task
xTaskCreate(
statusReportTask,
"StatusReport",
2048,
NULL,
1,
NULL
);
Serial.println("=== SmartSort Simulator Started ===\n");
}