/* 6/7/2024 Ethan Davis, Sheukeeng Lee Final Robot Code */ #include #include VL53L0X sensor; #include #define NUM_LEDS 2 CRGB leds[NUM_LEDS]; #define M2A 17 #define M2B 16 #define M1A 19 #define M1B 18 #define WSLED 4 uint32_t lastTime = 0; void errorLed(int count = 1){ for (int i = 0; i< count; i++){ leds[0] = CRGB::Red; FastLED.show(); delay(100); leds[0] = CRGB::Black; FastLED.show(); delay(100); } delay(1000); } void reverse(uint8_t mySpeed){ ledcWrite(3, mySpeed); //Set M2B to mySpeed ledcWrite(2, 0); //Set M2A to LOW ledcWrite(1, mySpeed);//Set M1B to mySpeed ledcWrite(0, 0); //Set M1A to LOW } void cw(uint8_t mySpeed){ ledcWrite(3, mySpeed); //Set M2B to mySpeed ledcWrite(2, 0); //Set M2A to LOW ledcWrite(1, 0); //Set M1B to LOW ledcWrite(0, mySpeed); //Set M1A to mySpeed } void ccw(uint8_t mySpeed){ ledcWrite(2, mySpeed); //Set M2A to mySpeed ledcWrite(3, 0); //Set M2B to LOW ledcWrite(0, 0); //Set M1A to LOW ledcWrite(1, mySpeed); //Set M1A to mySpeed } void forward(uint8_t mySpeed, uint8_t myOtherSpeed){ // makes one wheel faster than the other to achieve partial turn ledcWrite(0, mySpeed); ledcWrite(1, 0); ledcWrite(2, myOtherSpeed); ledcWrite(3, 0); delay(95); // flips, this creates the wiggle effect ledcWrite(0, myOtherSpeed); ledcWrite(1, 0); ledcWrite(2, mySpeed); ledcWrite(3, 0); delay(95); } void chaser(uint8_t mySpeed){ // target spotted! Full speed ahead! ledcWrite(0, mySpeed); ledcWrite(1, 0); ledcWrite(2, mySpeed); ledcWrite(3, 0); } void setup() { Serial.begin(115200); FastLED.addLeds(leds, NUM_LEDS); // GRB ordering is assumed // This section creates the I2C (Wire) connection and quieries for a VL53LX Wire.begin(); sensor.setTimeout(500); if (!sensor.init()) { Serial.println("Failed to detect and initialize sensor!"); while (1) {errorLed();} } // Set the 4 motor controll lines as outputs pinMode(M1A, OUTPUT); pinMode(M1B, OUTPUT); pinMode(M2A, OUTPUT); pinMode(M2B, OUTPUT); //These lines connect 4 PWM channels to the 4 motor control Pins ledcSetup(0, 30000, 8); ledcAttachPin(M1A, 0); ledcSetup(1, 30000, 8); ledcAttachPin(M1B, 1); ledcSetup(2, 30000, 8); ledcAttachPin(M2A, 2); ledcSetup(3, 30000, 8); ledcAttachPin(M2B, 3); forward(180, 255); } void loop() { int distance = sensor.readRangeSingleMillimeters(); if (distance < 50){ //Real close! Avoid reverse(255); delay(200); cw(255); delay(150); } if (distance < 600 && distance > 100){ // sees a target but not too close leds[0].setRGB(255,0,0); // make them red, its angry >:( leds[1].setRGB(255,0,0); FastLED.show(); chaser(255); Serial.println("CHASER!!!"); } if (distance < 100){ // Getting close, slow down leds[0].setRGB(0,0,255); // make them blue leds[1].setRGB(0,0,255); FastLED.show(); forward(200-(30-((distance/300.0)*30)), 255-(30-((distance/300.0)*30))); } if (distance > 600){ // bot cannot see any targets, start doing its little silverfish wiggle leds[0].setRGB(0,0,255); // make them blue, its docile leds[1].setRGB(0,0,255); FastLED.show(); Serial.println("idle..."); forward(180, 255); } Serial.println(distance); }