7/* 4/27/2024 Donald Heer Test code for the esp32_rbt.0 board Tests motors, WS2812, and I2C bus with a VLX530X attached. Expected serial output is a list of distances based on the VLX530X module GPIO22 SCL GPIO21 SDA GPIO19 M1A GPIO18 M1B GPIO17 M2A GPIO16 M2B GPIO4 WS2812 */ #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 forward(uint8_t mySpeed){ ledcWrite(2, mySpeed); //Set M2A to mySpeed ledcWrite(3, 0); //Set M2B to LOW ledcWrite(0, mySpeed);//Set M1A to mySpeed ledcWrite(1, 0); //Set M1B 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 M1BA to mySpeed } 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(230); } void loop() { int i = 0; //angry leds[0] = CRGB::Red; FastLED.show(); for (int i = 0; i < 3; i++) { cw(255); delay(500); ccw(255); delay(500); } forward(255); delay(200); leds[0] = CRGB::Black; FastLED.show(); delay(1000); //happy leds[0] = CRGB::Green; FastLED.show(); for (int i = 0; i < 3; i++) { forward(255); delay(500); reverse(255); delay(500); } cw(255); delay(200); leds[0] = CRGB::Black; FastLED.show(); delay(1000); //sad leds[0] = CRGB::Blue; FastLED.show(); forward(200); delay(600); reverse(200); delay(600); cw(200); delay(200); leds[0] = CRGB::Black; FastLED.show(); delay(1000); //scared leds[0] = CRGB::Purple; FastLED.show(); for (int i = 0; i < 5; i++) { forward(255); delay(100); reverse(255); delay(100); } cw(255); delay(500); ccw(255); delay(500); leds[0] = CRGB::Black; FastLED.show(); delay(1000); }