uni

Thing1's amazing uni repo
Log | Files | Refs

commit 76d1f2df166c998341f5814656bba8f43fba8d1b
parent 19e9c2872529702d951761702694424f974cb475
Author: thing1 <thing1@seacrossedlovers.xyz>
Date:   Sat,  6 Dec 2025 14:01:49 +0000

finished testing on robot

Diffstat:
MCS12020/robot/line/helper.h | 21++++++++++++++-------
MCS12020/robot/line/line.ino | 127++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++-----------
ACS12020/robot/line/reading.h | 45+++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 169 insertions(+), 24 deletions(-)

diff --git a/CS12020/robot/line/helper.h b/CS12020/robot/line/helper.h @@ -1,3 +1,5 @@ +#ifndef __HELPER_H_ +#define __HELPER_H_ #include <Servo.h> #include <stdint.h> @@ -15,9 +17,10 @@ #define LDRB A1 #define LDRC A0 -#define SERVOA_ZERO 84 -#define SERVOB_ZERO 85 -#define SPEED 10 +uint8_t SERVOA_ZERO = 84; +uint8_t SERVOB_ZERO = 85; +uint8_t SPEEDA = 10; +uint8_t SPEEDB = 10; #define ANALOG_MAX 1023 @@ -65,11 +68,11 @@ setupRobot() { void SEprintf(const char *fmt, ...) { - static char sbuf[64] = { 0 }; + char sbuf[256] = { 0 }; va_list ap; va_start(ap, fmt); - vsnprintf(sbuf, 64, fmt, ap); + vsnprintf(sbuf, 256, fmt, ap); va_end(ap); Serial.print(sbuf); @@ -107,9 +110,11 @@ setLEDs(int g, int y, int r) { void waitButton(int pin, int state) { - while (digitalRead(pin) == state) ; + while (digitalRead(pin) != !state) ; + delay(50); + while (digitalRead(pin) != state) ; + delay(50); } - bool isButtonAPressed() { return !digitalRead(BUTTONA); @@ -119,3 +124,4 @@ bool isButtonBPressed() { return !digitalRead(BUTTONB); } +#endif +\ No newline at end of file diff --git a/CS12020/robot/line/line.ino b/CS12020/robot/line/line.ino @@ -1,15 +1,20 @@ #include <EEPROM.h> #include "helper.h" -#define DEBUG_NAH +#define READING_INTERVAL 300 + +#include "reading.h" + +#define DEBUG #ifdef DEBUG -#define DBG(expr) expr; + #define DBG(expr) expr; #else -#define DBG(expr) + #define DBG(expr) #endif #define FLASHTIME 256 / 2 +#define TESTREADINGS 10 typedef struct state { bool left, mid, right; /* is on black */ @@ -20,6 +25,72 @@ typedef struct state { long gstate, ystate, rstate; /*used to store the time values of the LEDs to turn them off when needed */ } state; +const char *colors[] = {"white", "black"}; + +/* these functions are only used for debugging, and do not need to take up memory when not in use */ +#ifdef DEBUG + void + testLDR() + { + SEprintf("Testing LDRS\n"); + for (int i = 0; i < 2; i++) { + SEprintf("Please turn on the lights, and place the robot on a %s surface (press button A to continue)\n", colors[i]); + waitButton(BUTTONA, HIGH); + readSensorsMean(TESTREADINGS); + + SEprintf("Test complete, please turn off the lights (press button A to continue)\n"); + waitButton(BUTTONA, HIGH); + readSensorsMean(TESTREADINGS); + } + SEprintf("finished testing LDRS, please check the values are expected for lighting conditions\n"); + } + + void + testButton(int pin) + { + SEprintf("Testing button on pin %d, please press it 10 times in a row\n", pin); + for (int i = 0; i < 10; i++) { + waitButton(pin, HIGH); + SEprintf("Button pressed\n"); + } + SEprintf("Button testing complete, 10 values read, if you did not press the button 10 times, this test failed\n"); + delay(3); + } + + void + testServo(Servo s, int speed, int zero) + { + SEprintf("Testing Servo on pin %d, it will spin for 10 seconds\n"); + s.write(zero + speed); + delay(10000); + s.write(zero); + SEprintf("Servo test complete, if the servo did not spin for 10 seconds, this test failed\n"); + } + + void + testIR() + { + int seen = 0; + + SEprintf("Testing IR sensor, please place an object infront of the IR sensor\n"); + delay(5000); + for (int i = 0; i < 10; i++) { + if (!isObstacle()) + SEprintf("Did not detect object\n"); + else { + SEprintf("Detected object\n"); + seen++; + } + + delay(READING_INTERVAL); + } + if (seen < 8) + SEprintf("Only saw the object %d times, test failed\n", seen); + else + SEprintf("Saw the object %d times, test passed\n", seen); + } +#endif + void flash(int pin, state *s) { @@ -37,10 +108,6 @@ stepFlash(int pin) /* we define this a static to preserve its value across function calls */ static uint8_t flashCount; - DBG({ - SEprintf("Flashcount: %d\n", flashCount); - }); - if (flashCount < FLASHTIME) digitalWrite(pin, HIGH); else if (flashCount > FLASHTIME / 2) @@ -75,8 +142,8 @@ void stepMove(int dir, state *s) { /* move the robot fwd or bwd */ - servoA.write(SERVOA_ZERO + (SPEED * dir)); - servoB.write(SERVOB_ZERO - (SPEED * dir)); + servoA.write(SERVOA_ZERO + (SPEEDA * dir)); + servoB.write(SERVOB_ZERO - (SPEEDB * dir)); s->lastmove = millis(); } @@ -84,8 +151,8 @@ void stepTurn(int dir, state *s) { /* turn the robot lft or rgt */ - servoA.write(SERVOA_ZERO + (SPEED * dir)); - servoB.write(SERVOB_ZERO - (SPEED * -dir)); + servoA.write(SERVOA_ZERO + (SPEEDA * dir)); + servoB.write(SERVOB_ZERO - (SPEEDB * -dir)); s->lastturn = millis(); } @@ -217,18 +284,44 @@ move(state *s) void setup() { + /* let the user attach the battery, attaching the battery while code is running caused strange behavior */ delay(3000); setupRobot(); + /* read the calibrated values that should be in EEPROM, these values will be made by the calibrate program */ + EEPROM.get(6, LDRA_SWITCH); + EEPROM.get(10, LDRB_SWITCH); + EEPROM.get(14, LDRC_SWITCH); + + /* servo speed values */ + EEPROM.get(0, SERVOA_ZERO); + EEPROM.get(1, SPEEDA); + EEPROM.get(2, SERVOB_ZERO); + EEPROM.get(3, SPEEDB); + /* because this is static, I can modify these values to set defaults */ state *s = getState(); s->prevDir = BWD; s->timeStamp = 0; - /* read the calibrated values that should be in EEPROM */ - EEPROM.get(6, LDRA_SWITCH); - EEPROM.get(10, LDRB_SWITCH); - EEPROM.get(14, LDRC_SWITCH); + + /* test all the sensors and motors */ + DBG({ + testLDR(); + delay(1000); + testButton(BUTTONA); + delay(1000); + testButton(BUTTONB); + delay(1000); + testServo(servoA, SPEEDA, SERVOA_ZERO); + delay(1000); + testServo(servoB, SPEEDB, SERVOB_ZERO); + delay(1000); + testIR(); + delay(1000); + SEprintf("finished testing\n"); + }); + } void @@ -236,7 +329,7 @@ loop() { state *s = getState(); - /* do nothing while there is an obstacle, should flash orange */ + /* do nothing while there is an obstacle */ while (isObstacle()) { flash(YELLOW_LED, s); return; @@ -251,6 +344,6 @@ loop() stepMove(FWD, s); } - /* don't do any turns when on a the barcode, go straight */ + /* normal movement */ else move(s); } diff --git a/CS12020/robot/line/reading.h b/CS12020/robot/line/reading.h @@ -0,0 +1,44 @@ +#include "helper.h" + +/* READING_INTERVAL should be declared by the caller program before this code is included */ + +typedef struct reading { + int left, mid, right; +} reading; + +reading +readSensors() +{ + return (reading){analogRead(LDRA), analogRead(LDRB), analogRead(LDRC)}; +} + +reading +addreadings(reading r1, reading r2) +{ + return (reading){r1.left + r2.left, r1.mid + r2.mid, r1.right + r2.right}; +} + +reading +divreadings(reading r, int n) +{ + return (reading){r.left / n, r.mid / n , r.right / n}; +} + +reading +readSensorsMean(int readings) +{ + reading rs[readings], r; + for (int i = 0; i < readings; i++) { + rs[i] = readSensors(); + delay(READING_INTERVAL); + } + + for (int i = 0; i < readings; i++) { + SEprintf("single:%d,%d,%d\n", rs[i].left, rs[i].mid, rs[i].right); + r = addreadings(r, rs[i]); + } + + r = divreadings(r, readings); + SEprintf("mean:%d,%d,%d\n", r.left, r.mid, r.right); + return r; +} +\ No newline at end of file