uni

Thing1's amazing uni repo
Log | Files | Refs

commit 19e9c2872529702d951761702694424f974cb475
parent b0cbe666ccf9a12ba717329ffccbfc51c5a22d60
Author: thing1 <thing1@seacrossedlovers.xyz>
Date:   Sat,  6 Dec 2025 11:58:28 +0000

finished robot code (mostly)

Diffstat:
MCS12020/robot/calibrate/calibrate.ino | 22+++++++++++++++++-----
MCS12020/robot/calibrate/helper.h | 69++++++++++++++++-----------------------------------------------------
ACS12020/robot/line/checklist | 25+++++++++++++++++++++++++
MCS12020/robot/line/helper.h | 23-----------------------
MCS12020/robot/line/line.ino | 86+++++++++++++++++++++++++++++++++++++++++++++++++++++--------------------------
APH16210/04.12.25.md | 12++++++++++++
6 files changed, 128 insertions(+), 109 deletions(-)

diff --git a/CS12020/robot/calibrate/calibrate.ino b/CS12020/robot/calibrate/calibrate.ino @@ -2,7 +2,7 @@ #include <stdint.h> #include "helper.h" -void +void setup() { Serial.begin(9600); @@ -14,11 +14,23 @@ setup() { SEprintf("%d, %d, %d", LDRA_SWITCH + 100, LDRB_SWITCH + 100, LDRC_SWITCH + 100); - writeuint16(LDRA_SWITCH + 100, 6); - writeuint16(LDRB_SWITCH + 100, 10); - writeuint16(LDRB_SWITCH + 100, 14); + EEPROM.put(6, LDRA_SWITCH + 100); + EEPROM.put(10, LDRB_SWITCH + 100); + EEPROM.put(14, LDRB_SWITCH + 100); + + SEprintf("expecting to be on white\n"); + delay(3000); + while (!isLDRBright(LDRA)) LDRA_SWITCH++; + while (!isLDRBright(LDRB)) LDRB_SWITCH++; + while (!isLDRBright(LDRC)) LDRC_SWITCH++; + + SEprintf("%d, %d, %d", LDRA_SWITCH + 100, LDRB_SWITCH + 100, LDRC_SWITCH + 100); + + EEPROM.put(4, LDRA_SWITCH + 100); + EEPROM.put(8, LDRB_SWITCH + 100); + EEPROM.put(12, LDRB_SWITCH + 100); } -void +void loop() { } diff --git a/CS12020/robot/calibrate/helper.h b/CS12020/robot/calibrate/helper.h @@ -1,6 +1,5 @@ #include <Servo.h> #include <stdint.h> -#include <EEPROM.h> #define GREEN_LED 7 #define YELLOW_LED 12 @@ -16,8 +15,10 @@ #define LDRB A1 #define LDRC A0 -#define SERVOA_ZERO 96 -#define SERVOB_ZERO 96 +#define SERVOA_ZERO 84 +#define SERVOB_ZERO 85 +#define SPEED 10 + #define ANALOG_MAX 1023 #define IRTRANSMITTER 3 @@ -25,12 +26,12 @@ #define IRFREQ 38000 +#define SIZE(arr) (sizeof(arr) / sizeof(arr[0])) + uint16_t LDRA_SWITCH = 0; uint16_t LDRB_SWITCH = 0; uint16_t LDRC_SWITCH = 0; -#define SIZE(arr) (sizeof(arr) / sizeof(arr[0])) - enum DIRECTIONS { FWD = 1, BWD = -1, @@ -41,49 +42,28 @@ enum DIRECTIONS { Servo servoA; Servo servoB; -void +void setupRobot() { - Serial.begin(9600); - pinMode(GREEN_LED, OUTPUT); - pinMode(YELLOW_LED, OUTPUT); - pinMode(RED_LED, OUTPUT); - pinMode(BUTTONA, INPUT); + Serial.begin(9600); + pinMode(GREEN_LED, OUTPUT); + pinMode(YELLOW_LED, OUTPUT); + pinMode(RED_LED, OUTPUT); + pinMode(BUTTONA, INPUT); pinMode(BUTTONB, INPUT); - pinMode(SERVOA_PIN, OUTPUT); + pinMode(SERVOA_PIN, OUTPUT); pinMode(SERVOB_PIN, OUTPUT); pinMode(LDRA, INPUT); pinMode(LDRB, INPUT); pinMode(LDRC, INPUT); pinMode(IRTRANSMITTER, OUTPUT); pinMode(IRRECEVIER, INPUT); - servoA.attach(SERVOA_PIN); - servoB.attach(SERVOB_PIN); + servoA.attach(SERVOA_PIN); + servoB.attach(SERVOB_PIN); servoA.write(SERVOA_ZERO); servoB.write(SERVOB_ZERO); } void -writeuint16(uint16_t num, int start) { - uint8_t n[2] = {0}; - memcpy(n, &num, 2); - - EEPROM.update(start, n[0]); - EEPROM.update(start + 1, n[1]); -} - -uint16_t -readuint16(int start) { - uint8_t n[2] = {0}; - uint16_t num = 0; - - n[0] = EEPROM.read(start); - n[1] = EEPROM.read(start + 1); - - memcpy(&num, n, 2); - return num; -} - -void SEprintf(const char *fmt, ...) { static char sbuf[64] = { 0 }; va_list ap; @@ -99,6 +79,7 @@ SEprintf(const char *fmt, ...) { bool isObstacle() { tone(IRTRANSMITTER, IRFREQ); + delay(5); bool ret = (digitalRead(IRRECEVIER) == LOW); noTone(IRTRANSMITTER); return ret; @@ -129,24 +110,6 @@ waitButton(int pin, int state) { while (digitalRead(pin) == state) ; } -void -stepMove(int dir) { - servoA.write(SERVOA_ZERO + (6 * dir)); - servoB.write(SERVOB_ZERO - (6 * dir)); - delay(10); - servoA.write(SERVOA_ZERO); - servoB.write(SERVOB_ZERO); -} - -void -stepTurn(int dir) { - servoA.write(SERVOA_ZERO + (10 * dir)); - servoB.write(SERVOB_ZERO - (10 * -dir)); - delay(10); - servoA.write(SERVOA_ZERO); - servoB.write(SERVOB_ZERO); -} - bool isButtonAPressed() { return !digitalRead(BUTTONA); diff --git a/CS12020/robot/line/checklist b/CS12020/robot/line/checklist @@ -0,0 +1,24 @@ +calibrate +======= +- [x] read white +- [x] read black + +main program +=========== +- [x] follow line +- [x] stop when object + - [x] yellow LED +- [x] avoidance + - [x] red LED +- [x] attraction + - [x] green LED +- [ ] EEPROM + - [x] LDR black values + - [x] LDR white values + - [ ] motor values +- [ ] Testing + - [ ] buttons + - [ ] LEDS + - [ ] LDRS + - [ ] Servo debug msgs + - [ ] function +\ No newline at end of file diff --git a/CS12020/robot/line/helper.h b/CS12020/robot/line/helper.h @@ -1,6 +1,5 @@ #include <Servo.h> #include <stdint.h> -#include <EEPROM.h> #define GREEN_LED 7 #define YELLOW_LED 12 @@ -64,28 +63,6 @@ setupRobot() { servoB.write(SERVOB_ZERO); } - -void -writeuint16(uint16_t num, int start) { - uint8_t n[2] = {0}; - memcpy(n, &num, 2); - - EEPROM.update(start, n[0]); - EEPROM.update(start + 1, n[1]); -} - -uint16_t -readuint16(int start) { - uint8_t n[2] = {0}; - uint16_t num = 0; - - n[0] = EEPROM.read(start); - n[1] = EEPROM.read(start + 1); - - memcpy(&num, n, 2); - return num; -} - void SEprintf(const char *fmt, ...) { static char sbuf[64] = { 0 }; diff --git a/CS12020/robot/line/line.ino b/CS12020/robot/line/line.ino @@ -1,3 +1,4 @@ +#include <EEPROM.h> #include "helper.h" #define DEBUG_NAH @@ -11,16 +12,18 @@ #define FLASHTIME 256 / 2 typedef struct state { - bool left, mid, right; - int rawleft, rawmid, rawright; - enum DIRECTIONS prevDir; - long timeStamp; - long lastmove, lastturn; - long gstate, ystate, rstate; + bool left, mid, right; /* is on black */ + int rawleft, rawmid, rawright; /* raw readings from LDRS */ + enum DIRECTIONS prevDir; /* enum to store which direction we moved in last, used to error correct */ + long timeStamp; /* barcode timestamp, used to see how long it has been since we went over a barcode */ + long lastmove, lastturn; /* time the last stepmove call was made, used to turn the motor off when we stop calling the functions */ + long gstate, ystate, rstate; /*used to store the time values of the LEDs to turn them off when needed */ } state; void -flash(int pin, state *s) { +flash(int pin, state *s) +{ + /* user facing function to start flashing of the LEDs */ switch (pin) { case GREEN_LED: s->gstate = millis(); break; case YELLOW_LED: s->ystate = millis(); break; @@ -29,7 +32,9 @@ flash(int pin, state *s) { } void -stepFlash(int pin) { +stepFlash(int pin) +{ + /* we define this a static to preserve its value across function calls */ static uint8_t flashCount; DBG({ @@ -40,11 +45,15 @@ stepFlash(int pin) { digitalWrite(pin, HIGH); else if (flashCount > FLASHTIME / 2) digitalWrite(pin, LOW); + + /* this value wraps which is by design, this will cause the flashing to reset */ flashCount++; } void -updateFlash(state *s) { +updateFlash(state *s) +{ + /* turn off the leds if they arent ment to be on anymore */ if (millis() - s->gstate > FLASHTIME) { s->gstate = 0; digitalWrite(GREEN_LED, LOW); @@ -56,27 +65,34 @@ updateFlash(state *s) { digitalWrite(RED_LED, LOW); } + /* turn on the leds if needed */ if (s->gstate) stepFlash(GREEN_LED); if (s->ystate) stepFlash(YELLOW_LED); if (s->rstate) stepFlash(RED_LED); } void -stepMove(int dir, state *s) { +stepMove(int dir, state *s) +{ + /* move the robot fwd or bwd */ servoA.write(SERVOA_ZERO + (SPEED * dir)); servoB.write(SERVOB_ZERO - (SPEED * dir)); s->lastmove = millis(); } void -stepTurn(int dir, state *s) { +stepTurn(int dir, state *s) +{ + /* turn the robot lft or rgt */ servoA.write(SERVOA_ZERO + (SPEED * dir)); servoB.write(SERVOB_ZERO - (SPEED * -dir)); s->lastturn = millis(); } void -updateMotor(state *s) { +updateMotor(state *s) +{ + /* turns of the motor if we hacent called step move/turn recently */ if (millis() - s->lastmove > 10 && millis() - s->lastturn) { servoA.write(SERVOA_ZERO); servoB.write(SERVOB_ZERO); @@ -84,8 +100,11 @@ updateMotor(state *s) { } state * -getState() { +getState() +{ static state s; + + /* update all of the robots LDR readings */ s.left = !isLDRBright(LDRA); s.mid = !isLDRBright(LDRB); s.right = !isLDRBright(LDRC); @@ -100,7 +119,8 @@ getState() { } void -stepAvoidanceBehave(state *s) { +stepAvoidanceBehave(state *s) +{ flash(RED_LED, s); DBG({ /* WARNING this causes the program to stutter when left on, @@ -120,7 +140,8 @@ stepAvoidanceBehave(state *s) { void -stepAttractionBehave(state *s) { +stepAttractionBehave(state *s) +{ flash(GREEN_LED, s); DBG({ SEprintf("Attract: %d, %d, %d\n", s->rawleft, s->rawmid, s->rawright); @@ -137,7 +158,8 @@ stepAttractionBehave(state *s) { } void -runBehave(void (*stepBehave)(state *)) { +runBehave(void (*stepBehave)(state *)) +{ while (true) { state *s = getState(); stepBehave(s); @@ -145,7 +167,8 @@ runBehave(void (*stepBehave)(state *)) { } void -checkBarcode(state *s) { +checkBarcode(state *s) +{ long t = millis(); if (s->timeStamp > 500) { /* long barcode */ @@ -159,21 +182,23 @@ checkBarcode(state *s) { s->timeStamp = t; } +/* TODO check if dirs are correct */ void -move(state *s) { +move(state *s) +{ /* small adjustments */ if (s->right && s->mid) - stepTurn(RGT,s); + stepTurn(RGT, s); else if (s->left && s->mid) - stepTurn(LFT,s); + stepTurn(LFT, s); /* large adjustments */ else if (s->right) { s->prevDir = LFT; - stepTurn(RGT,s); + stepTurn(RGT, s); } else if (s->left) { s->prevDir = RGT; - stepTurn(LFT,s); + stepTurn(LFT, s); /* drive straight, nominal */ } else if (s->mid) { @@ -190,7 +215,8 @@ move(state *s) { } void -setup() { +setup() +{ delay(3000); setupRobot(); @@ -199,13 +225,15 @@ setup() { s->prevDir = BWD; s->timeStamp = 0; - LDRA_SWITCH = readuint16(6); - LDRB_SWITCH = readuint16(10); - LDRC_SWITCH = readuint16(14); + /* read the calibrated values that should be in EEPROM */ + EEPROM.get(6, LDRA_SWITCH); + EEPROM.get(10, LDRB_SWITCH); + EEPROM.get(14, LDRC_SWITCH); } void -loop() { +loop() +{ state *s = getState(); /* do nothing while there is an obstacle, should flash orange */ @@ -214,13 +242,15 @@ loop() { return; } - + /* the robots on a barcode */ if (s->right && s->left && s->mid) { checkBarcode(s); + /* run through the barcode */ for (int i = 0; i < 20; i++) stepMove(FWD, s); } + /* don't do any turns when on a the barcode, go straight */ else move(s); } diff --git a/PH16210/04.12.25.md b/PH16210/04.12.25.md @@ -0,0 +1,12 @@ +04/12/25 +======== + +- see FIG1 for an diagram that shows a linear constant coff ODE + - see FIG2 for the general solution to this when u(t) is 0 + +- FIG3 shows the results of the charateristic equation + - note on solution II there is only one value of lambda + - III is using imaginary values + +- FIG4 shows the general solution +