The following code is known to work so I think, from what I've read that I'm missing a library. Any pointers on how to troubleshoot the code would be appreciated. I noticed some libraries show up in red text and some in black, is that a clue?
#include <BluetoothSerial.h>
/*
Modified control software to allow use of an ESP32 board in conjusction with Matthew Zwarts Android app to control a BB-R2 style droid
Matt Zwarts app communicates by Bluetooth sending data for LeftJoy_X,LeftJoy_Y, Right_Joy_X, RightJoy_Y as comma seperated items
Joystick values are between 0 and 200. 100,100 is Joystick centered.
Start of the data packet is a double '<'
example datastream: 00,100<<100,100,100,100<<150,130,100,100<<150,130,....
///////////////////////////////////////////////////////////////////////////////////////
//Connections
///////////////////////////////////////////////////////////////////////////////////////
ESP32
Servo1 = 12 Left drive
Servo2 = 13 Right drive
Servo3 = 14 Dome
DFPlayer Rx = 26
DFPlayer Tx = 27
*//////////////////////////////////////////////////////////////////////////////////////
//
//If you find one of your servos drifting when joysticks are centered, or Bluetooth is not connected use the 'trim' variables with small numbers
//Drive motor mixing code taken from https://www.impulseadventure.com/elec/robot-differential-steering.html
//
// Uncomment the following line if you are using a DFPlayer for sounds
#define Using_DFPlayer
#include <Arduino.h>
#include <SoftwareSerial.h> // uses ESPSoftwareSerial library https://github.com/plerup/espsoftwareserial/
#include <BluetoothSerial.h> // uses https://github.com/espressif/arduino-esp32/tree/master/libraries/BluetoothSerial
#include <Servo.h> // uses ServoESP32 library https://github.com/RoboticsBrno/ServoESP32
#include <HardwareSerial.h>
#include "soc/soc.h"
#include "soc/rtc_cntl_reg.h"
//Bluetooth Definition
BluetoothSerial MySerial;
#define BT_NAME "ESP32BT_Chopp"
#ifdef Using_DFPlayer
#include "DFRobotDFPlayerMini.h"
//Serial for DFPlayer
HardwareSerial DFSerial(1);
DFRobotDFPlayerMini myDFPlayer;
bool PlayLabel = false;
long Player_Timer = 0;
int sound_called = 0;
#endif
static const int servoPin1 = 12; //Left Drive
static const int servoPin2 = 13; //Right Drive
static const int servoPin3 = 14; //Dome
Servo servo1;
Servo servo2;
Servo servo3;
long previousMillis = 0;
int timeout = 500;
unsigned long elapsedTime; // time current
byte receivedChar; // serial data received from bluetooth device
int x_drive = 100; // value from joystick
int y_drive = 100; // value from joystick
int x2_dome = 100; // value from joystick
int y2_dome = 100; // value from joystick
int dome_val;
// Use to trim servos that move when joystick centered
// Use small numbers
int x1_trim = 0;
int y1_trim = 0;
int x2_trim = 0;
int y2_trim = 0;
// Differential Steering Variables ////////////////////////////////////////
// INPUTS
int nJoyX; // Joystick X input (-128..+127)
int nJoyY; // Joystick Y input (-128..+127)
// OUTPUTS
int nMotMixL; // Motor (left) mixed output (-128..+127)
int nMotMixR; // Motor (right) mixed output (-128..+127)
// CONFIG
// - fPivYLimt : The threshold at which the pivot action starts
// This threshold is measured in units on the Y-axis
// away from the X-axis (Y=0). A greater value will assign
// more of the joystick's range to pivot actions.
// Allowable range: (0..+127)
float fPivYLimit = 32.0;
// TEMP VARIABLES
float nMotPremixL; // Motor (left) premixed output (-128..+127)
float nMotPremixR; // Motor (right) premixed output (-128..+127)
int nPivSpeed; // Pivot Speed (-128..+127)
float fPivScale; // Balance scale b/w drive and pivot ( 0..1 )
///////////////////////////////////////////////////////////////////////////////
int keywordPointer2=0;
void setup() {
// put your setup code here, to run once:
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); //disable brownout detector
Serial.begin(115200); //Used only for debugging on arduino serial monitor
Serial.println("Hello, my name is C1-10P!");
MySerial.begin(BT_NAME); //Start Bluetooth Serial
#ifdef Using_DFPlayer
DFSerial.begin(9600, SERIAL_8N1, 27, 26); // speed, type, RX, TX
myDFPlayer.begin(DFSerial); //Initialize DFPlayer
#endif
servo1.attach(servoPin1);
servo2.attach(servoPin2);
servo3.attach(servoPin3);
/**************************** Setup DFPlayer ************************************/
/***************************************************************************/
#ifdef Using_DFPlayer
Serial.println();
Serial.println(F("DFRobot DFPlayer Mini Demo"));
Serial.println(F("Initializing DFPlayer ... (May take 3~5 seconds)"));
if (!myDFPlayer.begin(DFSerial)) { //Use softwareSerial to communicate with mp3.
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."));
myDFPlayer.setTimeOut(500); //Set serial communictaion time out 500ms
//----Set volume----
myDFPlayer.volume(25); //Set volume value (0~30).
//----Set different EQ----
myDFPlayer.EQ(DFPLAYER_EQ_NORMAL);
//----Set device we use SD as default----
myDFPlayer.outputDevice(DFPLAYER_DEVICE_SD);
#endif
/***************************************************************************/
/***************************************************************************/
}
void loop() {
// put your main code here, to run repeatedly:
// called functions////////////////////////////////////////////////////////////////////////
bluetooth_data();
steering_servos();
Dome_servo();
// Play sounds
Play_Sounds();
}
void bluetooth_data() {
char rawData[40] = "";
char trimmedData[40] ="";
char keyword[] = "<<";
if (MySerial.available() > 0) {//new data in
size_t byteCount = MySerial.readBytesUntil('\n', rawData, sizeof(rawData) - 1); //read 100 CHARS in data to buffer
rawData[byteCount] = NULL;//put an end character on the data
/*
Serial.print("Raw Data = ");
Serial.println(rawData);
*/
//now find keyword and parse
char *keywordPointer = strstr(rawData, keyword);
if (keywordPointer != NULL) {
strcpy(rawData,(rawData+(strlen(rawData)+2-strlen(keywordPointer)))); // Trim Leading characters and <<
//Serial.println(rawData); //OK to here
char *keywordPointer2 = strstr(rawData, keyword); // Trim << and trailing characters
if (keywordPointer2) // Trim << and trailing characters
*keywordPointer2=0; // Trim << and trailing characters
/*
Serial.print("Trimmed Data = ");
Serial.println(rawData);
*/
const char delimiter[] = ",";
char parsedStrings[5][20];
int dataCount = 0;
char *token = strtok(rawData, delimiter);//look for first piece of data after keyword until comma
if (token != NULL && strlen(token) < sizeof(parsedStrings[0])) {
strncpy(parsedStrings[0], token, sizeof(parsedStrings[0]));
dataCount++;
previousMillis = millis();
} else {
Serial.println("token too big");
strcpy(parsedStrings[0], NULL);
}
for (int i = 1; i < 5; i++) {
token = strtok(NULL, delimiter);
if (token != NULL && strlen(token) < sizeof(parsedStrings[i])) {
strncpy(parsedStrings[i], token, sizeof(parsedStrings[i]));
dataCount++;
} else {
Serial.println("token to big");
strcpy(parsedStrings[i], NULL);
}
}
/* for debug only
Serial.print("Found ");
Serial.print(dataCount);
Serial.println(" strings:");
for (int i = 0; i < 5; i++){
Serial.print("Token");
Serial.print(i);
Serial.print(" ");
Serial.println(parsedStrings[i]);//Serial.println("");
}
*/
if (dataCount == 5) {
//Serial.println("Datacount=4");
x_drive = atoi(parsedStrings[0]);
y_drive = atoi(parsedStrings[1]);
x2_dome = atoi(parsedStrings[2]);
y2_dome = atoi(parsedStrings[3]);
#ifdef Using_DFPlayer
sound_called = atoi(parsedStrings[4]);
#endif
trim_servos();
nJoyX = map(x_drive,200,0,-127,127);
nJoyY = map(y_drive,0,200,-127,127);
}
else {
Serial.println("data no good");
}
}
else {
Serial.println("sorry no keyword");
}
}
else { /////////////////////Write the motors to low if no signal is present for more than 500ms
if (millis() - previousMillis >= timeout) {
x_drive = 100;
y_drive = 100;
x2_dome = 100;
y2_dome = 100;
trim_servos();
nJoyX = map(x_drive,200,0,-127,127);
nJoyY = map(y_drive,0,200,-127,127);
}
}
}
void steering_servos(){
// Calculate Drive Turn output due to Joystick X input
if (nJoyY >= 0) {
// Forward
nMotPremixL = (nJoyX>=0)? 127.0 : (127.0 + nJoyX);
nMotPremixR = (nJoyX>=0)? (127.0 - nJoyX) : 127.0;
} else {
// Reverse
nMotPremixL = (nJoyX>=0)? (127.0 - nJoyX) : 127.0;
nMotPremixR = (nJoyX>=0)? 127.0 : (127.0 + nJoyX);
}
// Scale Drive output due to Joystick Y input (throttle)
nMotPremixL = nMotPremixL * nJoyY/128.0;
nMotPremixR = nMotPremixR * nJoyY/128.0;
// Now calculate pivot amount
// - Strength of pivot (nPivSpeed) based on Joystick X input
// - Blending of pivot vs drive (fPivScale) based on Joystick Y input
nPivSpeed = nJoyX;
fPivScale = (abs(nJoyY)>fPivYLimit)? 0.0 : (1.0 - abs(nJoyY)/fPivYLimit);
// Calculate final mix of Drive and Pivot
nMotMixL = (1.0-fPivScale)*nMotPremixL + fPivScale*( nPivSpeed);
nMotMixR = (1.0-fPivScale)*nMotPremixR + fPivScale*(-nPivSpeed);
// Do something with x and y
nMotMixL = map(nMotMixL,-127,127,0,180);
nMotMixR = map(nMotMixR,127,-127,0,180);
servo1.write(nMotMixL);
servo2.write(nMotMixR);
}
void Dome_servo(){
dome_val = map(x2_dome,200,0,180,0);
//dome_val = map(x2_dome,200,0,0,180); //Reverse rotation of dome
servo3.write(dome_val);
/* for debug only
Serial.print("servo3.write(");
Serial.print(dome_val);
Serial.println(");");
*/
}
void trim_servos(){
x_drive = x_drive + x1_trim; //x2 trim
x_drive = max(x_drive,0);
x_drive = min(x_drive,200);
y_drive = y_drive + y1_trim; //x2 trim
y_drive = max(y_drive,0);
y_drive = min(y_drive,200);
x2_dome = x2_dome + x2_trim; //x2 trim
x2_dome = max(x2_dome,0);
x2_dome = min(x2_dome,200);
y2_dome = y2_dome + y2_trim; //x2 trim
y2_dome = max(y2_dome,0);
y2_dome = min(y2_dome,200);
}
void Play_Sounds(){
#ifdef Using_DFPlayer
if (sound_called == 0) {
PlayLabel=false;
}
else{
if (PlayLabel == false){
if ((sound_called > 0) && (sound_called < 9)) {
PlayLabel=true;
myDFPlayer.play(sound_called);
}
if (sound_called == 9 ) {
if ((millis()-Player_Timer) > 7000){
myDFPlayer.play(random(1,9));
Player_Timer = millis();
}
}
}
}
#endif
}