#include <Adafruit_MotorShield.h> #include <Servo.h> //General uint8_t regions[2] = {BACKWARD, FORWARD}; uint8_t regions_opposite[2] = {FORWARD, BACKWARD}; int region = 1; int button_val = 0; int button_port = 0; int cur_status = 0; long cur_loop_count = 0; bool status_repeat = false; //Motors Adafruit_MotorShield AFMS = Adafruit_MotorShield(); Adafruit_DCMotor *motors[] = {AFMS.getMotor(3), AFMS.getMotor(4)}; #define left 1 //index value in motor pointer array #define right 0 //IR #define white 1 #define black 0 #define num_IR 4 #define IR_floating_avg_num 3 int IR_threshold[num_IR] = {400, 300, 500, 300}; float IR_avgs[num_IR] = {0}; //LRFB int IR_colours[num_IR] = {0}; int IR_locns[num_IR] = {A0, A3, A1, A2}; float IR_vals[num_IR][IR_floating_avg_num] = {0}; //check int IR_float_counter[num_IR] = {0}; //US #define echoPin 2 #define trigPin 3 #define US_float_avg_num 5 float duration; float new_US_distance; int US_index = 0; float US_distance_vals[US_float_avg_num] = {0}; float US_distance_avg; //Servo #define servo_position 180 Servo servo; void setup() { // put your setup code here, to run once: Serial.begin(9600); if (!AFMS.begin()) { // create with the default frequency 1.6KHz // if (!AFMS.begin(1000)) { // OR with a different frequency, say 1KHz Serial.println("Could not find Motor Shield. Check wiring."); while (1); } for(int j=0; j<2; j++) { motors[j]->run(RELEASE); } for(int i=0; i< num_IR; i++) { pinMode(IR_locns[i], INPUT); } pinMode(button_port, INPUT); pinMode(trigPin, OUTPUT); pinMode(echoPin, INPUT); //servo.attach(9); } void loop() { // put your main code here, to run repeatedly: for(int i=0; i < 2*IR_floating_avg_num; i++) { //Get some values in before evaluation starts update_IR_vals(); } for(int j = 0; j<2; j++) { motors[j]->run(regions[region]); } //servo.write(servo_position); while (true) { check_push_button(motors); update_IR_vals(); int IR_check_val = IR_check(IR_colours); //New code for stuck in a loop check_if_in_loop(IR_check_val); if (status_repeat) { Serial.println("RECOVERY CODE"); move_both(motors, 255); continue; } line_sensing(motors, IR_check_val); } } void line_sensing(Adafruit_DCMotor *motors[], int IR_check_val) { if (IR_check_val == 0) { move_both(motors, 255); Serial.println("FORWARD"); } else if (IR_check_val == 1) { move_one_motor(motors, 200, left); Serial.println("TURN LEFT"); } else if (IR_check_val == 2) { move_one_motor(motors, 200, right); Serial.println("TURN RIGHT"); } else if (IR_check_val == 3) { Serial.println("Junction"); } else if (IR_check_val == 4) { Serial.println("Ramp off"); } else if (IR_check_val == 5) { Serial.println("Ramp on"); } else { move_both(motors, 255); Serial.println("Else block fml"); /* for(int j = 0; j < 2; j++) { motors[j]->setSpeed(0); } */ /* for(int j = 0; j < num_IR; j++) { Serial.print(IR_avgs[j]); Serial.print(" -> "); } */ //Serial.println(); //while (1); } } void move_one_motor(Adafruit_DCMotor *motors[], int velocity, int side) { //May need to account for direction later motors[(side+1)%2]->setSpeed(velocity); motors[side]->setSpeed(0); } void move_both(Adafruit_DCMotor *motors[], int velocity) { for(int j=0; j<2; j++) { motors[j]->setSpeed(velocity); } } void rotate(Adafruit_DCMotor *motors[], int velocity, int side) { //May need to account for direction later //If you want to turn right, the left motor moves forward but the right motor moves in the other direction motors[side]->run(regions_opposite[region]); motors[(side+1)%2]->run(regions[region]); move_both(motors, velocity); } float floating_average(int *index, float vals[], float curAvg, float newVal, int arr_len) { curAvg = ((curAvg * float(arr_len)) - vals[*index] + newVal)/float(arr_len); vals[*index] = newVal; *index = (*index + 1) % arr_len; return curAvg; } int IR_check(int LRFB[]) { if (LRFB[0] == black && LRFB[1] == black && LRFB[2] == white && LRFB[3] == white) { return 0; } else if (LRFB[0] == white && LRFB[1] == black) { return 1; } else if (LRFB[0] == black && LRFB[1] == white) { return 2; } else if (LRFB[0] == white && LRFB[1] == white && LRFB[2] == white && LRFB[3] == white) { return 3; } else if (LRFB[0] == black && LRFB[1] == black && LRFB[2] == white && LRFB[3] == black) { return 4; } else if (LRFB[0] == black && LRFB[1] == black && LRFB[2] == black && LRFB[3] == white) { return 5; } else { return 6; } } void update_IR_vals() { for(int i=0; i<num_IR; i++) { int new_val = analogRead(IR_locns[i]); IR_avgs[i] = floating_average(&IR_float_counter[i], IR_vals[i], IR_avgs[i], new_val, IR_floating_avg_num); if (IR_avgs[i] > IR_threshold[i]) { IR_colours[i] = black; } else { IR_colours[i] = white; } } } void check_push_button(Adafruit_DCMotor *motors[]) { button_val = digitalRead(button_port); if (button_val == 1) { Serial.println("Button pushed. Exiting"); for(int j = 0; j < 2; j++) { motors[j]->run(RELEASE); } while (1); } } void check_if_in_loop(int IR_check_val) { if (IR_check_val != 0 && cur_status == IR_check_val) { //Remember to change value after binary cur_loop_count += 1; if (cur_loop_count > 800) { status_repeat = true; } else { status_repeat = false; } } else { status_repeat = false; cur_loop_count = 0; cur_status = IR_check_val; } } float check_ultrasonic_distance(void){ digitalWrite(trigPin, LOW); delayMicroseconds(2); digitalWrite(trigPin, HIGH); delayMicroseconds(10); digitalWrite(trigPin, LOW); duration = pulseIn(echoPin, HIGH); new_US_distance = duration * 0.034 / 2; US_distance_avg = floating_average(&US_index, US_distance_vals, US_distance_avg, new_US_distance, US_float_avg_num); return US_distance_avg; }