Jeff
Published © CC BY-NC

WALL-E with Bluetooth control app

Bluetooth controlled robot with motors, servos and Android app

IntermediateFull instructions provided6,313
WALL-E with Bluetooth control app

Things used in this project

Hardware components

Espressif DOIT ESP32 DEVKIT V1 Board
×1
110RPM Bringsmart JGB37-550 High Torque 12V DC Motor
×2
MG92B Robot 13.8g 3.5KG Torque Metal Gear Digital Servo
×7
PCA9685 16-Channel 12-bit PWM Servo Module
×1
L298N Dual H Bridge Stepper Motor Driver Board
×1
5 Amp Adjustable DC-DC Step Down Module / Buck Convertor
×1
DFPlayer Mini MP3 Player Module
×1
Micro SD card / TF Card
×1
Speaker 8ohm 0.5 watt 50mm diameter
×1
Resistor 220 ohm
Resistor 220 ohm
×1
Resistor 330 ohm
Resistor 330 ohm
×1
5 mm LED: Red
5 mm LED: Red
×1
Voltage Sensor for Arduino DC 0-25V
×1
SSD1306 OLED display 12C module
×1
10 amp Rocker switch
×1
12v battery (3S lipo)
×1
Android device
Android device
×1

Software apps and online services

MIT App Inventor
MIT App Inventor
Arduino IDE
Arduino IDE

Hand tools and fabrication machines

3D Printer (generic)
3D Printer (generic)
Soldering iron (generic)
Soldering iron (generic)

Story

Read more

Schematics

Wiring Diagram

Audio Files

App Inventor MAC edit

Edit to your ESP32 Bluetooth MAC address in MIT app Inventor in top left variable in the block layout section.

MP3 list documentation

Android app main screenshot

Code

Arduino code for ESP32

Arduino
/*
  -------------------------------------------------------------------
  Electronic Parts:
  -------------------------------------------------------------------
  - 100RPM Bringsmart JGA25-310 High Torque 12V DC Gear Motor from AliExpress https://www.aliexpress.com/item/32855856821.html
    255 fastest speed - 220 slowest speed
  - 7 Servos (MG92B Robot 13.8g 3.5KG Torque Metal Gear Digital Servos from Banggood.com)
  - PCA9685 16-Channel 12-bit PWM Servo  Module (from Banggood.com)
  - ESP32 Development Board - DOIT ESP32 DEVKIT V1 Board (Banggood.com)
  - L298N Dual H Bridge Stepper Motor Driver Board ((Banggood.com))
  - 5 Amp Adjustable DC-DC Step Down Module Power Supply Converter - Buck Converter (set to 5v to 5.5v) (from Banggood.com)
  - DFPlayer module (from Banggood.com)
  - Micro SD card (to store MP3 files on)
  - Ywrobot speaker module Speaker 8ohm 0.5 watt 50mm diameter Note: I did not use the module, just the speaker. (from Banggood.com)
  - 100K - 1M ohm resistor on DFPlayer (I am using a 220ohm resistor that seems to work fine)
  - 330ohm resistor for LED
  - 5mm Red LED
  - Voltage Sensor for Arduino DC 0-25V
  - 3S LIPO battery (or other approx 12v power supply)
  - SSD1306 OLED display 12C module (from Banggood.com) Geekcreit 0.96 Inch 4Pin White IIC I2C OLED Display Module 12864
      0.96 Inch
      Resolution: 128x64
      VCC: 3.3V-5.5V
  - Power switch (ON /OFF) I used a 10amp switch

  // -------------------------------------------------------------------
  // Key Command List
  // -------------------------------------------------------------------
  // Left head tilt = l
  // Right head tilt = r
  // Sad head = i
  // Neutral head = n
  // Eyes Raise = e
  // Alarm looped w/ LED Flashing = A
  // Reset ESP32 = Z

  // Forwards = w
  // Backwards = s
  // Turn Left = a
  // Turn Right = d
  // stop motors = q

  // Move left arm = L+(number between 0-100)
  // Move right arm = R+(number between 0-100)
  // Move head rotation = H+(number between 0-100)
  // Move neck bottom (To look up or down) = B+(number between 0-100)
  // Move neck top (To look up or down) = N+(number between 0-100)
  // Move eye left = E+(number between 0-100)
  // Move eye right = U+(number between 0-100)
  ---------------------------------------------
  Note: MP3 track play the order they are saved to the microSD card
  ---------------------------------------------
  // Play Sound Track = T+(number between 0-100) allows to have up to 100 sound tracks to play from micro SD card
  // Play music clip as Loop = C
  // Volume Control = V+(number between 0-30)
  // Pause Audio = P

  ---------------------------------------------
  Multi Moves in single Serial string:
  ---------------------------------------------
  H0\nN100\nB0\n = Head forward left
  H0\nN100\nB100\n = Neck up left
  H100\nN100\nB0\n =  Head forward right
  H100\nN100\nB100\n = Neck up right
  H0\nB0\nN25\n = Look left
  H100\nB0\nN25\n = Look right
  H50\nB0\nN25\nn\n = Center Head
  H50\nB0\nN100\nn\n = Look down
  H50\nB100\nN0\nn\n = Look up

*/

// -------------------------------------------------------------------
////////Libraries/////////
// -------------------------------------------------------------------
#include <Arduino.h>
#include <analogWrite.h>
#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include "DFRobotDFPlayerMini.h"
#include "BluetoothSerial.h"

#if !defined(CONFIG_BT_ENABLED) || !defined(CONFIG_BLUEDROID_ENABLED)
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
#endif

#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels

//See OLED datasheet for Address; normally 0x3D for 128x64, 0x3C for 128x32 (2 color display (yellow top 25%, blue bottom) 128x64 uses 0x3C)
#define SCREEN_ADDRESS 0x3C

// Declaration for an SSD1306 display connected to I2C (SDA = pin 21, SCL = pin 22 on ESP32 that I am using)
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);

// Servo shield controller class - assumes default address 0x40
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();

//Motor Inputs to L298 for motor controller
#define ENA 13        // Right Motor
#define ENB 25        // Left Motor

// Left Track
#define IN1 12
#define IN2 14

//Right Track
#define IN3 27
#define IN4 26

// Sound Track Selection
byte Track;

// Setting PWM properties
const int freq = 30000;
const int pwmChannel_A = 0;     // Channel for Right Motor
const int pwmChannel_B = 1;     // Channel for Left Motor
const int resolution = 8;
int rightMotorSpeed = 220;       // Starting-Lowest Motor Speed
int leftMotorSpeed = 220;       // Starting-Lowest Motor Speed

#define SR_OE 23           // Servo shield output enable pin

// Voltage Sensor Pin
const int Analog_channel_pin = 36;

// Floats for ADC voltage & Input voltage
float adc_voltage = 0.0;
float in_voltage = 0.0;

// Floats for resistor values in divider (in ohms)
float R1 = 30000.0;
float R2 = 7500.0;

// Float for Reference Voltage
float ref_voltage = 3.3;

// Integer for ADC value
int adc_value = 0;

//Used to make voltage reading more accurate (my acutal voltage was reading exactly 0.5volts higher then the ESP32 ADC output which is not very accurate)
// Test your voltage and adjust this variable accordingly
float voltageCorrection = 0.5;



// Define other constants
#define FREQUENCY 10       // Time in milliseconds of how often to update servo and motor positions
#define SERVOS 7           // Number of servo motors
#define THRESHOLD 1        // The minimum error which the dynamics controller tries to achieve
#define MOTOR_OFF 7000 	   // Turn servo motors off after 6 seconds
#define MAX_SERIAL 18       // Maximum number of characters that can be received before buffer is cleared

// Bluetooth serial
BluetoothSerial SerialBT;

// DFPlayer serial
HardwareSerial mySoftwareSerial(1);
DFRobotDFPlayerMini myDFPlayer;
byte volume = 20;

// Runtime Variables
unsigned long lastTime = 0;
unsigned long motorTimer = 0;     	//used in manageServos() function - uninterrupted delay used to Disable servos if robot is not moving
unsigned long motorTime = 0;      	//used to track time in motorSpeed() function - motor increasing speed delay
unsigned long motorDelay = 100;		  //delay amount for uninterrupted delay motor to increase speed
unsigned long updateTimer = 0;
unsigned long batteryTimer = 0;     //used to track time for checking voltage
unsigned long batteryDelay = 15000; //checks voltage only once every 15 secs

const int ledPin = 15;      		//LED connected to digital pin 15

// Serial Parsing
char firstChar;
char serialBuffer[MAX_SERIAL];
uint8_t serialLength = 0;


// ****** SERVO MOTOR CALIBRATION *********************
// Servo Positions:  Low,High
int preset[][2] =  {
  {468, 122}, // head rotation
  {135, 558}, // neck top
  {230, 610}, // neck bottom
  {225, 410}, // eye right
  {490, 350}, // eye left
  {495, 220}, // arm left
  {260, 528}  // arm right
};
// *****************************************************

// Servo Control - Position, Velocity, Acceleration
// -------------------------------------------------------------------
// Servo Pins:	     0,   1,   2,   3,   4,   5,   6
// Joint Name:	  head,necT,necB,eyeR,eyeL,armL,armR
float curpos[] = { 248, 560, 140, 475, 270, 250, 290};  // Current position (units)
float setpos[] = { 248, 560, 140, 475, 270, 250, 290};  // Required position (units)
float curvel[] = {   0,   0,   0,   0,   0,   0,   0};  // Current velocity (units/sec)
float maxvel[] = { 500, 400, 500, 2400, 2400, 600, 600}; // Max Servo velocity (units/sec)
float accell[] = { 450, 300, 480, 1800, 1800, 500, 500}; // Servo acceleration (units/sec^2)


// ------------------------------------------------------------------
// 		SETUP Configuration:
// ------------------------------------------------------------------
void setup() {

  // Output Enable (EO) pin for the servo motors
  pinMode(SR_OE, OUTPUT);
  digitalWrite(SR_OE, HIGH);

  // Communicate with servo shield (Analog servos run at ~60Hz)
  pwm.begin();
  pwm.setPWMFreq(60);

  // Turn off servo outputs
  for (int i = 0; i < SERVOS; i++) pwm.setPin(i, 0);

  // Initialize serial communication
  mySoftwareSerial.begin(9600, SERIAL_8N1, 16, 17);  // speed, type, RX, TX (for DFPlayer communication)

  Serial.begin(115200);           // Serial monitor interface for testing (diagnostics)
  SerialBT.begin("WALL-E");    	  // Bluetooth device name

  // SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
  if (!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
    Serial.println(F("SSD1306 allocation failed"));
    for (;;);
  }

  display.clearDisplay();
  display.display();
  delay(10);

  // Soft start the servo motors
  digitalWrite(SR_OE, LOW);

  // sets the pins as outputs for motor control
  pinMode(IN1, OUTPUT);
  pinMode(IN2, OUTPUT);
  pinMode(IN3, OUTPUT);
  pinMode(IN4, OUTPUT);

  pinMode(ENA, OUTPUT);
  pinMode(ENB, OUTPUT);

  // Red Alert LED
  pinMode(ledPin, OUTPUT);

  // configure LED PWM functionaly for Both Channels (for Motor Control)
  ledcSetup(pwmChannel_A, freq, resolution);
  ledcSetup(pwmChannel_B, freq, resolution);

  // attach the channel to the GPIO to be controlled by PWM Channels (for Motor Control)
  ledcAttachPin(ENA, pwmChannel_A);
  ledcAttachPin(ENB, pwmChannel_B);

  Serial.println(F("--------------------"));
  Serial.println(F("Initializing DFPlayer ... (May take 3~5 seconds)"));

  if (!myDFPlayer.begin(mySoftwareSerial)) {  //Use softwareSerial for ESP32 to communicate with DFPlayer module.

    Serial.println(myDFPlayer.readType(), HEX);
    Serial.println(F("Unable to begin:"));
    Serial.println(F("1.Please recheck the connection!"));
    Serial.println(F("2.Please insert the SD card!"));
    while (true);
  }
  Serial.println(F("DFPlayer Mini online."));

  //----Set volume----
  myDFPlayer.volume(volume);  //Set volume value (0~30)

  myDFPlayer.setTimeOut(500); //Set serial communicataion time out 500ms

  //----Set device we use SD as default----
  myDFPlayer.outputDevice(DFPLAYER_DEVICE_SD);

  PowerStartup ();

  //----Read information----
  Serial.print(F("Volume Level: "));
  Serial.println(myDFPlayer.readVolume()); //read current volume

  Serial.print(F("Detected Sound Files: "));
  Serial.println(myDFPlayer.readFileCounts()); //read all file counts in SD card

  myDFPlayer.playFolder(33, 1);   // plays startup sound clip (first clip in folder /33)

// Set head to neutral state on startup
  setpos[4] = int(0.4 * (preset[4][1] - preset[4][0]) + preset[4][0]);
  setpos[3] = int(0.4 * (preset[3][1] - preset[3][0]) + preset[3][0]);

// Set arms to lowest point on startup
  setpos[5] = int(0 * 0.01 * (preset[5][1] - preset[5][0]) + preset[5][0]);
  setpos[6] = int(0 * 0.01 * (preset[6][1] - preset[6][0]) + preset[6][0]);
  delay(1200);
  
  voltageReading ();      // Used to add the voltage reading to the Variable before the loop starts so there is no delay on actual voltage reading when booting up the ESP32
}

// -------------------------------------------------------------------
// 		MAIN PROGRAM LOOP
// -------------------------------------------------------------------
void loop() {

  checkBatteryLevel();

  // Read any new incoming serial data
  // -- -- -- -- -- -- -- -- -- -- -- -- -- --
  if (SerialBT.available() > 0) {     //Serial.read(); to use Serial Montior input control
    readSerial();
  }

  // Move Servos and wheels at regular time intervals
  // -- -- -- -- -- -- -- -- -- -- -- -- -- --
  if (updateTimer < millis()) {
    updateTimer = millis() + FREQUENCY;

    unsigned long newTime = micros();
    float dt = (newTime - lastTime) / 1000.0;
    lastTime = newTime;

    manageServos(dt);
  }
}



// ------------------------------------------------------------------
// 		FUNCTIONS
// ------------------------------------------------------------------

// Note: the positive and negative wires to motors connected to the L298 motor controller affect the direction of the motors and what direction the Inputs (IN1 to IN4) control.

// -------------------------------------------------------------------
// Move Forward
// -------------------------------------------------------------------
void forward() {
  digitalWrite(IN3, 0); // turn off
  digitalWrite(IN2, 0); // turn off
  digitalWrite(IN1, 1); // turn on Left track
  digitalWrite(IN4, 1); // turn on Right track
  motorSpeed();
}

// -------------------------------------------------------------------
// Move Backwards
// -------------------------------------------------------------------
void backwards() {
  digitalWrite(IN1, 0); // turn off
  digitalWrite(IN4, 0); // turn off
  digitalWrite(IN2, 1); // turn on Left track
  digitalWrite(IN3, 1); // turn on Right track
  motorSpeed();
}

// -------------------------------------------------------------------
// Turn Left
// -------------------------------------------------------------------
void left() {
  digitalWrite(IN2, 0); // turn off
  digitalWrite(IN4, 0); // turn off
  digitalWrite(IN1, 1); // turn on Left track (forward direction)
  digitalWrite(IN3, 1); // turn on Right track (backwards direction)
  motorSpeed();
}

// -------------------------------------------------------------------
// Turn Right
// -------------------------------------------------------------------
void right() {
  digitalWrite(IN1, 0); // turn off
  digitalWrite(IN3, 0); // turn off
  digitalWrite(IN2, 1); // turn on Left track (backwards direction)
  digitalWrite(IN4, 1); // turn on Right track (forward direction)
  motorSpeed();
}

// -------------------------------------------------------------------
// Stop motors
// -------------------------------------------------------------------
void stopMotors() {
  digitalWrite(IN1, 0); // turn off
  digitalWrite(IN3, 0); // turn off
  digitalWrite(IN2, 0); // turn off
  digitalWrite(IN4, 0); // turn off
  rightMotorSpeed = 220;    // Reset Motor Speed to lowest
  leftMotorSpeed = 220;		// Reset Motor Speed to lowest
}

// -------------------------------------------------------------------
// Gradually increases motor speed from lowest to max speed
// -------------------------------------------------------------------
void motorSpeed() {
  while (rightMotorSpeed <= 255 || leftMotorSpeed <= 255) {
    ledcWrite(pwmChannel_A, rightMotorSpeed);
    ledcWrite(pwmChannel_B, leftMotorSpeed);
    Serial.print("Forward A: ");
    Serial.println(rightMotorSpeed);
    Serial.print("Forward B: ");
    Serial.println(leftMotorSpeed);

    unsigned long currentMillis = millis();

    // Create uninterrupted delay for increasing speed controlled by motorDelay variable
    if (currentMillis - motorTime > motorDelay) {
      motorTime = currentMillis;
      rightMotorSpeed = rightMotorSpeed + 5;
      leftMotorSpeed = leftMotorSpeed + 5;
    }
  }
}


// -------------------------------------------------------------------
// READ INPUT FROM SERIAL
// -------------------------------------------------------------------
void readSerial() {
  // Read incoming byte
  char inchar = SerialBT.read();    //Serial.read(); to use Serial Montior input control

  // If the string has ended, evaluate the serial buffer
  if (inchar == '\n' || inchar == '\r') {

    if (serialLength > 0)
      evaluateSerial();
    serialBuffer[0] = 0;
    serialLength = 0;
  }
  // Otherwise add to the character to the buffer
  else {
    if (serialLength == 0) firstChar = inchar;
    else {
      serialBuffer[serialLength - 1] = inchar;
      serialBuffer[serialLength] = 0;
    }
    serialLength++;

    // To prevent overflows, evaluate the buffer if it is full then reset buffer
    if (serialLength == MAX_SERIAL) {
      evaluateSerial();
      serialBuffer[0] = 0;
      serialLength = 0;
    }
  }
}


// -------------------------------------------------------------------
// 		EVALUATE INPUT FROM SERIAL
// -------------------------------------------------------------------
void evaluateSerial() {
  // Evaluate integer number in the serial buffer
  int number = atoi(serialBuffer);

  Serial.print(firstChar); Serial.println(number);

  // -------------------------------------------------------------------
  // Manual servo control
  // -------------------------------------------------------------------
  if (firstChar == 'L' && number >= 0 && number <= 100) {   // Move left arm
    setpos[5] = int(number * 0.01 * (preset[5][1] - preset[5][0]) + preset[5][0]);
  }
  else if (firstChar == 'R' && number >= 0 && number <= 100) { // Move right arm
    setpos[6] = int(number * 0.01 * (preset[6][1] - preset[6][0]) + preset[6][0]);
  }
  else if (firstChar == 'B' && number >= 0 && number <= 100) { // Move neck bottom
    setpos[2] = int(number * 0.01 * (preset[2][1] - preset[2][0]) + preset[2][0]);
  }
  else if (firstChar == 'N' && number >= 0 && number <= 100) { // Move neck top
    setpos[1] = int(number * 0.01 * (preset[1][1] - preset[1][0]) + preset[1][0]);
  }
  else if (firstChar == 'H' && number >= 0 && number <= 100) { // Move head rotation
    setpos[0] = int(number * 0.01 * (preset[0][1] - preset[0][0]) + preset[0][0]);
  }
  else if (firstChar == 'E' && number >= 0 && number <= 100) { // Move eye left
    setpos[4] = int(number * 0.01 * (preset[4][1] - preset[4][0]) + preset[4][0]);
  }
  else if (firstChar == 'U' && number >= 0 && number <= 100) { // Move eye right
    setpos[3] = int(number * 0.01 * (preset[3][1] - preset[3][0]) + preset[3][0]);
  }

  // -------------------------------------------------------------------
  // Manual Movements with WASD
  // -------------------------------------------------------------------
  else if (firstChar == 'w') {		// Forward movement
    forward();
  }

  else if (firstChar == 's') {		// Backward movement
    backwards();
  }

  else if (firstChar == 'a') {		//Turn left
    left();
  }

  else if (firstChar == 'd') {   	// Turn right
    right();
  }

  else if (firstChar == 'q') {		// Stop movement & Pause/Sounds
    stopMotors();
  }

  // -------------------------------------------------------------------
  // Manual Eye Movements
  // -------------------------------------------------------------------
  else if (firstChar == 'l') {		// Left head tilt
    setpos[4] = preset[4][0];
    setpos[3] = preset[3][1];
  }
  else if (firstChar == 'r') {		// Right head tilt
    setpos[4] = preset[4][1];
    setpos[3] = preset[3][0];
  }
  else if (firstChar == 'i') {		// Sad head
    myDFPlayer.playFolder(33, 5);     // Plays sad sound clip
    setpos[4] = preset[4][0];
    setpos[3] = preset[3][0];
  }
  else if (firstChar == 'n') {		// Neutral head
    setpos[4] = int(0.4 * (preset[4][1] - preset[4][0]) + preset[4][0]);
    setpos[3] = int(0.4 * (preset[3][1] - preset[3][0]) + preset[3][0]);
  }
  else if (firstChar == 'e') {    // Eye Raise
    setpos[4] = int(99 * 0.01 * (preset[4][1] - preset[4][0]) + preset[4][0]);
    setpos[3] = int(99 * 0.01 * (preset[3][1] - preset[3][0]) + preset[3][0]);
    myDFPlayer.playFolder(33, 6);     // Play suprised sound clip
  }


  // -------------------------------------------------------------------
  // Audio
  // -------------------------------------------------------------------
  else if (firstChar == 'V' && number > 0 && number < 30) {
    volume = number;
    myDFPlayer.volume(volume);   //Set volume value (0~30)
    Serial.println(myDFPlayer.readVolume()); //read current volume
  }

  else if (firstChar == 'T' && number >= 0 && number <= 99) {
    Track = number;
    myDFPlayer.pause();
    myDFPlayer.playFolder(33, Track);
    Serial.println(F("Now Playing Track:"));
    Serial.println(myDFPlayer.readCurrentFileNumber()); //read current play file number
  }

  else if (firstChar == 'C') {
    myDFPlayer.loop(7);  //Loop a music clip - mp3 (7)means it was the 7th MPS saved to the microSD card.
  }

  else if (firstChar == 'P') {    // Pause Audio
    myDFPlayer.pause();
  }

  else if (firstChar == 'A') {
    myDFPlayer.playFolder(33, 4); //Play Alarm clip (save to folder named 33 and is 4th file saved to the SD card)with LED flashing delay (adjusted delay to sync with time to sound clip)

    for (int i = 0; i < 3; i++) {
      digitalWrite(ledPin, HIGH);
      delay(570);
      digitalWrite(ledPin, LOW);
      delay(570);
    }
  }
  // -------------------------------------------------------------------
  // Reset ESP32 with Bluetooth / Serial command (used as ESP32 does not seem to allow device to reconnect after a a disconnect to via Bluetooth)
  // -------------------------------------------------------------------
  else if (firstChar == 'Z') {
    ESP.restart();		// Reset ESP32
  }

}

// -------------------------------------------------------------------
// 		MANAGE THE MOVEMENT OF THE SERVO MOTORS
// -------------------------------------------------------------------
void manageServos(float dt) {
  // SERVO MOTORS
  // -  -  -  -  -  -  -  -  -  -  -  -  -
  bool moving = false;
  for (int i = 0; i < SERVOS; i++) {

    float posError = setpos[i] - curpos[i];

    // If position error is above the threshold
    if (abs(posError) > THRESHOLD && (setpos[i] != -1)) {

      digitalWrite(SR_OE, LOW);
      moving = true;

      // Determine motion direction
      bool dir = true;
      if (posError < 0) dir = false;

      // Determine whether to accelerate or decelerate
      float acceleration = accell[i];
      if ((curvel[i] * curvel[i] / (2 * accell[i])) > abs(posError)) acceleration = -accell[i];

      // Update the current velocity
      if (dir) curvel[i] += acceleration * dt / 1000.0;
      else curvel[i] -= acceleration * dt / 1000.0;

      // Limit Velocity
      if (curvel[i] > maxvel[i]) curvel[i] = maxvel[i];
      if (curvel[i] < -maxvel[i]) curvel[i] = -maxvel[i];

      float dP = curvel[i] * dt / 1000.0;

      if (abs(dP) < abs(posError)) curpos[i] += dP;
      else curpos[i] = setpos[i];

      pwm.setPWM(i, 0, curpos[i]);

    } else {
      curvel[i] = 0;
    }
  }

  // Disable servos if robot is not moving
  // This prevents the motors from overheating
  if (moving) motorTimer = millis() + MOTOR_OFF;
  else if (millis() > motorTimer) {
    //digitalWrite(SR_OE, HIGH);
    for (int i = 0; i < SERVOS; i++) {
      pwm.setPin(i, 0);
    }
  }
}

// -------------------------------------------------------------------
// 	VOLTAGE reading - Reads the Analog Input of Voltage sensor and output to actual voltage.
// -------------------------------------------------------------------

void voltageReading () {
  adc_value = analogRead(Analog_channel_pin);

  // Determine voltage at ADC input
  adc_voltage  = (adc_value * ref_voltage) / 4095.0;

  // Calculate voltage at divider input
  in_voltage = adc_voltage / (R2 / (R1 + R2));
  in_voltage = in_voltage + voltageCorrection;

  Serial.print("Input Voltage = ");
  Serial.println(in_voltage, 1);          // Sends Voltage reading out to Arduino Serial Monitor
  SerialBT.println(in_voltage, 1);        // Sends Voltage reading in text format out to Bluetooth App
}

// -------------------------------------------------------------------
// Checks Voltage Reading every 15seconds set by batteryDelay variable
// -------------------------------------------------------------------

void checkBatteryLevel() {

  unsigned long currentMillis = millis();

  // Checks voltage only once every 15 secs
  if (currentMillis - batteryTimer > batteryDelay) {
    batteryTimer = currentMillis;
    voltageReading ();
  }
  BatteryDisplay();
}

// -------------------------------------------------------------------
// Displays number of bars on OLED display based on the Voltage reading  (10 bars=100%, 5 Bars=50%, 1 Bar=10%)
// -------------------------------------------------------------------

void BatteryDisplay() {
  if (in_voltage >= 12.2) {
    Battery_100p();
  }
  else if (in_voltage < 12.2 && in_voltage >= 11.8) {
    Battery_90p();
  }
  else if (in_voltage < 11.8 && in_voltage >= 11.5) {
    Battery_80p();
  }
  else if (in_voltage < 11.5 && in_voltage >= 11.2) {
    Battery_70p();
  }
  else if (in_voltage < 11.2 && in_voltage >= 11) {
    Battery_60p();
  }
  else if (in_voltage < 10.8 && in_voltage >= 10.6) {
    Battery_50p();
  }
  else if (in_voltage < 10.6 && in_voltage >= 10.4) {
    Battery_40p();
  }
  else if (in_voltage < 10.4 && in_voltage >= 10.3) {
    Battery_30p();
  }
  else if (in_voltage < 10.3 && in_voltage >= 10.1) {
    Battery_20p();
  }

  // If voltage goes Below 10.1 voltage Alarm sounds the Red LED flashed and OLED flashes the 10%(bottom) bar.
  // Lipo Battey should be recharged to prevent damage at this point
  else if (in_voltage < 10.1) {
    myDFPlayer.playFolder(33, 4); //Play Alarm clip (save to folder named 33 and is 4th file saved to the SD card)with LED flashing delay (adjusted delay to sync with time to sound clip)

    for (int i = 0; i < 3; i++) {       //make LED & OLED flash
      display.clearDisplay();
      display.display();
      digitalWrite(ledPin, HIGH);
      delay(570);
      digitalWrite(ledPin, LOW);
      Battery_10p();
      delay(570);
    }
  }
}

// -------------------------------------------------------------------
// Draws Rectangle Bars on OLED display
// -------------------------------------------------------------------
void Battery_10p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);		// 10% percent
  display.display();
}

void Battery_20p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);		// 20% percent
  display.display();
}

void Battery_30p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);		// 30% percent
  display.display();
}

void Battery_40p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);		// 40% percent
  display.display();
}

void Battery_50p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);		// 50% percent
  display.display();
}

void Battery_60p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);
  display.fillRect(48, 0, 7, 64, WHITE);		// 60% percent
  display.display();
}

void Battery_70p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);
  display.fillRect(48, 0, 7, 64, WHITE);
  display.fillRect(36, 0, 7, 64, WHITE);		// 70% percent
  display.display();
}

void Battery_80p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);
  display.fillRect(48, 0, 7, 64, WHITE);
  display.fillRect(36, 0, 7, 64, WHITE);
  display.fillRect(24, 0, 7, 64, WHITE);		// 80% percent
}

void Battery_90p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);
  display.fillRect(48, 0, 7, 64, WHITE);
  display.fillRect(36, 0, 7, 64, WHITE);
  display.fillRect(24, 0, 7, 64, WHITE);
  display.fillRect(12, 0, 7, 64, WHITE);		// 90% percent
  display.display();
}

void Battery_100p() {
  display.clearDisplay();
  display.fillRect(108, 0, 16, 64, WHITE);
  display.fillRect(96, 0, 7, 64, WHITE);
  display.fillRect(84, 0, 7, 64, WHITE);
  display.fillRect(72, 0, 7, 64, WHITE);
  display.fillRect(60, 0, 7, 64, WHITE);
  display.fillRect(48, 0, 7, 64, WHITE);
  display.fillRect(36, 0, 7, 64, WHITE);
  display.fillRect(24, 0, 7, 64, WHITE);
  display.fillRect(12, 0, 7, 64, WHITE);
  display.fillRect(0, 0, 7, 64, WHITE);			// 100% percent
  display.display();
}

// -------------------------------------------------------------------
// Animates OLED bars as ESP32 boots up
// -------------------------------------------------------------------
void PowerStartup () {      // Power up battery level animated
  Battery_10p(); delay (500);
  Battery_20p(); delay (500);
  Battery_30p(); delay (400);
  Battery_40p(); delay (400);
  Battery_50p(); delay (350);
  Battery_60p(); delay (200);
  Battery_70p(); delay (200);
  Battery_80p(); delay (150);
  Battery_90p(); delay (100);
  Battery_100p(); delay (10);
}

BT_Walle_MKI_final.aia

Scratch
No preview (download only).

Credits

Jeff

Jeff

4 projects • 7 followers

Comments