If I place my case with ESP32 under the middle of the bed I assume I will need maybe 0.5m long cables from some of the boxes with GY-521. I was thinking of using FTP cables with RJ45 connectors for these connections. But I don't know if it will work. Is there a solution for this? Maybe using some accelerometers with UART or SPI interface?
For second question I am not sure what you mean. If you mean resetting the "frozen" GY-521s I have to turn off the whole project and connect "frozen" gyroscopes one by one directly to ESP I2C bus and turn it on and they will start working. I thought that it should be the same if I leave them connected to MUX and just turn the power off but it was not working for some reason, they remained stuck.
But I made some changes, I connected all GY-521s directly to ESP I2C without MUX, I address them using ESP pins and I used PCA9685 PWM I2C driver to control DC motor drivers to save pins. It is working fine on the table next to PC but I am afraid if there is some problem with I2C due to longer connection cables it could be mess.
As for the code posting it is quite long, there is communication with ESP through Async Web Server, sending readings to PC and other misc functions. But here it is:
.ino file:
#include <WiFi.h>
#include <ESPmDNS.h>
#include <Wire.h>
#include <string>
#include <AsyncElegantOTA.h> // async OTA
#include <ESPmDNS.h>
#include <ESPAsyncWebServer.h>
#include "motors.h"
#include "misc.h"
#include "serverFunctions.h"
using namespace std;
void runMotorGyroControl(void);
void setup(void) {
initComm();
pinMode(ONBOARD_LED_PIN, OUTPUT); // Onboard LED
// ------------ Initialize PCA9685 I2C Motor PWM controller - required for motors initialization
PWMController.begin();
PWMController.setPWMFreq(100);
// ------------ Initialize Motors
LinearMotor motor1, motor2, motor3;
motorList.push_back(motor1);
motorList.push_back(motor2);
motorList.push_back(motor3);
// ------------ Initialize Buttons
//Buttons button1(1, stopButtonHandler, 1), button2(2, stopButtonHandler, 1), button3(3, stopButtonHandler, 1); // btnId must be same as buttonNumber in buttonXX !!! So starting from 1, increments by 1
//buttonList.push_back(button1);
//buttonList.push_back(button2);
//buttonList.push_back(button3);
// ------------ Initialize Gyroscopes
//Gyros gyro1(1, 3), gyro2(2, 4), gyro3(3, 5), gyro4(4, 6); // --- gyro(motorNumber; MUXChannel)
Gyros gyro1(1, 16), gyro2(2, 17), gyro3(3, 25), gyro4(4, 26); // --- gyro(motorNumber; Arduino pin of GY-521 AD0 address pin)
gyroList.push_back(gyro1);
gyroList.push_back(gyro2);
gyroList.push_back(gyro3);
gyroList.push_back(gyro4);
for (auto& gyroIdx : gyroList) {
gyroIdx.gyroBegin();
pinMode(gyroIdx.getAD0Pin(), OUTPUT);
digitalWrite(gyroIdx.getAD0Pin(), HIGH);
}
}
void loop(void) {
stopMotorsOnTimer();
//pollButtons();
if (program.getGyroRead()) pollGyros();
if (program.getIICRead()) getIICScannerReading();
if (program.getMotorGyroControl()) runMotorGyroControl();
//handleProgram();
}
// --------------- Controlling motors using gyro position
void runMotorGyroControl(void) {
static unsigned long pollTime = 0;
unsigned long actualTime = millis();
sensors_vec_t actualAccReading;
//bool directionSwitch = false;
if (actualTime - pollTime > 300) // polling in very short intervals causes problems
for (auto& gyroIdx : gyroList) {
uint8_t motorListIdx = gyroIdx.getMotorNumber() - 1;
selectGyro(gyroIdx.getAD0Pin());
actualAccReading = gyroIdx.getAccelReading(); //a.acceleration;
//directionSwitch = (abs(motorGyroOffset-lastYReading)>abs(motorGyroOffset-actualYReading));
selectGyro(0);
if ((actualAccReading.y > (gyroIdx.getGyroOffset() + gyroIdx.getGyroRange())) && (motorList[motorListIdx].getMotorDirection() != MOTOR_BACKWARD)) {
Serial.println(" - Move backward"); // motor must be stopped before changing direction, otherwise the motor driver of motor gets stuck for some reason
motorList[motorListIdx].setMotorDirection(MOTOR_STOP);
motorList[motorListIdx].runMotor();
motorList[motorListIdx].setMotorStopTime(0);
motorList[motorListIdx].setMotorState(false);
delay(100);
motorList[motorListIdx].setMotorDirection(MOTOR_BACKWARD);
motorList[motorListIdx].setMotorStopTime(0);
motorList[motorListIdx].setMotorSpeed(255);
motorList[motorListIdx].runMotor();
} else if ((actualAccReading.y < (gyroIdx.getGyroOffset() - gyroIdx.getGyroRange())) && (motorList[motorListIdx].getMotorDirection() != MOTOR_FORWARD)) {
Serial.println(" - Move forward");
motorList[motorListIdx].setMotorDirection(MOTOR_STOP);
motorList[motorListIdx].runMotor();
motorList[motorListIdx].setMotorStopTime(0);
motorList[motorListIdx].setMotorState(false);
delay(100);
motorList[motorListIdx].setMotorDirection(MOTOR_FORWARD);
motorList[motorListIdx].setMotorStopTime(0);
motorList[motorListIdx].setMotorSpeed(255);
motorList[motorListIdx].runMotor();
} else if ((abs(actualAccReading.y - gyroIdx.getGyroOffset()) < abs(gyroIdx.getGyroOffset() - gyroIdx.getGyroRange()))
&& (motorList[motorListIdx].getMotorDirection() != MOTOR_STOP)) { //&&(actualAccReading.y<(gyroIdx.getGyroOffset()+gyroIdx.getGyroRange()))&&(motorList[motorListIdx].getMotorDirection()!=MOTOR_STOP)){
Serial.println(" - Stop");
motorList[motorListIdx].setMotorDirection(MOTOR_STOP);
motorList[motorListIdx].runMotor();
motorList[motorListIdx].setMotorStopTime(0);
motorList[motorListIdx].setMotorState(false);
//return 1; // return motor reached final position - end of program step
}
pollTime = actualTime;
}
}
motors.h and motors.cpp
/*
Motor class header
*/
#ifndef MOTORS_H
#define MOTORS_H
#include "ESPAsyncWebServer.h"
#include <ArduinoJson.h>
#include <WiFi.h>
#include <Adafruit_PWMServoDriver.h>
#include <string>
#include <vector>
#define MOTOR_BACKWARD 1
#define MOTOR_STOP 2
#define MOTOR_FORWARD 3
#define MOTOR_NUMBER 0
#define MOTOR_DIRECTION 1
#define MOTOR_SPEED 2
#define MOTOR_TIME 3
using namespace std;
//- - - - - - - - - - ESP32 Channel Variables - - - - - - - - - -
const int FREQ = 1000; // Set up PWM Frequency
const int RES = 8; // Set up PWM Resolution
const int NUMBER_OF_MOTORS = 5; // number of motors in use
const int MAX_MOTOR_RUN_TIME = 15000; // max motor runtime
inline Adafruit_PWMServoDriver PWMController= Adafruit_PWMServoDriver(0x40); // PCA9685 I2C PWM controller
// ------------------ Motors controlled directly from ESP32
//const int En_LR ... // En_X pins hardwired to HIGH
// MAXIMUM 5 Motors !!!
//const int Outputs[10]={12, 13, 16, 17, 14, 27, 25, 26, 18, 19}; //list of output pins for motor PWM control: 0,2,4,... - LPWM; 1,3,5,... - RPWM
//- - - - - - - - - - Channel assignments - - - - - - - - - -
const int Channels[10] = {15, 14, 13, 12, 11, 10, 9, 8, 7, 6}; // ESP32 PWM channels list
// ---------------- ESP32 pin assigned to channels list
// Motor nr. | L_PWM pin | R_PWM pin
// 1 | 12 | 13
// 2 | 16 | 17
// 3 | 14 | 27
// 4 | 25 | 26
// 5 | 18 | 19
// ----------------- Motors controlled using PCA9685 I2C PWM controller ( 0-15 output pin numbers )
const int Outputs[10]={0, 1, 2, 3, 4, 5, 6, 7, 8, 9};
class LinearMotor {
private:
int pin_LPWM, pin_RPWM, channel_LPWM, channel_RPWM;
int motorNumber, motorSpeed, motorDirection, motorSpeed12bit;
unsigned long motorStopTime;
bool motorState;
public:
LinearMotor(void);
int getChannelLPWM(void) const {return channel_LPWM;}
int getChannelRPWM(void) const {return channel_RPWM;}
int getPinLPWM(void) const {return pin_LPWM;}
int getPinRPWM(void) const {return pin_RPWM;}
int getMotorNumber(void) const {return motorNumber;}
int getMotorSpeed(void) const {return motorSpeed;}
int getMotorDirection(void) const {return motorDirection;}
unsigned long getMotorStopTime(void) const {return motorStopTime;}
bool getMotorState(void) const {return motorState;}
void setMotorSpeed(int speed) {motorSpeed = speed;}
void setMotorDirection(int direction){motorDirection = direction;}
void setMotorStopTime(unsigned int motorRunTime) {motorStopTime = (motorRunTime>0) ? millis() + motorRunTime : 0;}
void setMotorState(bool state){motorState = state;}
int calcMotorSpeed12bit(void);
void runMotor(void);
static int motorCount;
};
inline AsyncWebServer server(80);
inline AsyncEventSource events("/events");
inline int LinearMotor::motorCount = 0; // initialize static int motor counter
inline vector<LinearMotor> motorList;
void stopMotorsOnTimer(void);
void stopMotor(uint8_t motorNumber);
void fetchServerMotorCommand(int (&opArray)[4], AsyncWebServerRequest *request);
#endif
#include "motors.h"
LinearMotor::LinearMotor(void){
motorCount++;
if (motorCount>NUMBER_OF_MOTORS) Serial.println("WARNING! Current motor number exceeds NUMBER_OF_MOTORS constant!!");
else {
motorNumber = motorCount;
channel_LPWM = Channels[2*(motorNumber-1)]; // set LPWM channel from PWM channels' list
channel_RPWM = Channels[2*(motorNumber-1)+1]; // set RPWM channel from PWM channels' list
pin_LPWM = Outputs[2*(motorNumber-1)]; //set output pin number for LPWM from pins' list
pin_RPWM = Outputs[2*(motorNumber-1)+1]; //set output pin number for RPWM from pins' list
// --------- for direct pwm control from ESP32
/*
ledcSetup(channel_LPWM, FREQ,RES) ; // setup PWM channel for BST L_PWM
ledcSetup(channel_RPWM, FREQ,RES) ; // setup PWM channel for BST R_PWM
ledcAttachPin( pin_LPWM, channel_LPWM) ; // Attach BST L_PWM
ledcAttachPin( pin_RPWM, channel_RPWM) ; // Attach BST R_PWM
ledcWrite(channel_LPWM,0); // initial PWM value set to 0 on both channels - motor stopped
ledcWrite(channel_RPWM,0);
*/
// --------- for pwm control using PCA9685 servo controler
PWMController.setPWM(pin_LPWM, 0, 1); // initial PWM value set to 0 on both pins - motor stopped
PWMController.setPWM(pin_RPWM, 0, 1);
// ------------------
motorSpeed = 0;
motorSpeed12bit = 1;
motorDirection = MOTOR_STOP; // initial direction - 2 = STOP
motorStopTime = 0;
motorState = false; // motor is stopped
Serial.print(" Initialized motor number: ");
Serial.print(motorCount);
Serial.print("; PCA9685 pin numbers for motor LPWM/RPWM: ");
Serial.print(pin_LPWM);
Serial.print("/");
Serial.println(pin_RPWM);
}
}
int LinearMotor::calcMotorSpeed12bit(void){
if (motorSpeed == 0) motorSpeed12bit = 1;
else if (motorSpeed >= 255) motorSpeed12bit = 4095;
else motorSpeed12bit = 16 * motorSpeed;
return motorSpeed12bit;
}
/*
// --- pwm directly from Arduino
void LinearMotor::runMotor(void){
switch(motorDirection) {
case MOTOR_BACKWARD:
ledcWrite(channel_LPWM,0);
ledcWrite(channel_RPWM,motorSpeed);
setMotorState(true);
break;
case MOTOR_STOP:
ledcWrite(channel_LPWM,0) ;
ledcWrite(channel_RPWM,0);
setMotorState(false);
setMotorStopTime(0);
break;
case MOTOR_FORWARD:
ledcWrite(channel_LPWM,motorSpeed);
ledcWrite(channel_RPWM,0);
setMotorState(true);
break;
}
}
*/
// --------- pwm from I2C PCA9685 servo driver
void LinearMotor::runMotor(void){
calcMotorSpeed12bit();
switch(motorDirection) {
case MOTOR_BACKWARD:
PWMController.setPWM(pin_LPWM, 0, 1); // LPWM ouput - 0
PWMController.setPWM(pin_RPWM, 0, motorSpeed12bit); // RPWM output - speed
setMotorState(true);
break;
case MOTOR_STOP:
PWMController.setPWM(pin_LPWM, 0, 1);
PWMController.setPWM(pin_RPWM, 0, 1);
setMotorState(false);
setMotorStopTime(0);
break;
case MOTOR_FORWARD:
PWMController.setPWM(pin_LPWM, 0, motorSpeed12bit); // LPWM ouput - speed
PWMController.setPWM(pin_RPWM, 0, 1); // RPWM output - 0
setMotorState(true);
break;
}
}
void stopMotorsOnTimer(void) {
unsigned long actualTime = millis();
for (auto& motorIdx : motorList) {
if ((motorIdx.getMotorState() == true) && (motorIdx.getMotorStopTime() > 0) && (actualTime > motorIdx.getMotorStopTime())) { // if motor is running && runtime is not infinite && actual time is greater than stop time of motor
motorIdx.setMotorDirection(MOTOR_STOP);
motorIdx.runMotor();
motorIdx.setMotorState(false);
motorIdx.setMotorStopTime(0);
}
}
}
void stopMotor(uint8_t motorNumber) {
for (auto& motorIdx : motorList) {
if (motorIdx.getMotorNumber() == motorNumber) { // stop motor with number motorNumber
motorIdx.setMotorDirection(MOTOR_STOP);
motorIdx.runMotor();
motorIdx.setMotorState(false);
motorIdx.setMotorStopTime(0);
}
}
}
// ---------------- AsyncWebServer
void fetchServerMotorCommand(int (&operationArray)[4], AsyncWebServerRequest *request){
unsigned int time = 0;
unsigned int tmpSpeed = 0;
String response = "Command: \"motor\"; ";
String strTime = "";
String strMotorSpeed = "";
String strDir = "";
String strMotorNum = "";
String strSerialMessage = "{\"command\":\"motor\",";
if (!(request->hasArg("motornum"))){ //Parameter not found
response += "Motor number not specified, setting motor number 0; ";
strSerialMessage += "\"motornum\":0,";
operationArray[0]=0;
}else {
operationArray[0] = request->arg("motornum").toInt();
if ((operationArray[0] > NUMBER_OF_MOTORS) || (operationArray[0] < 1)) {
operationArray[0] = 0;
response += "Motor number out of range or wrong format!!! Setting motor number 0; Number of motors: ";
response += to_string(NUMBER_OF_MOTORS).c_str();
response += "; ";
strSerialMessage += "\"motornum\":0,";
}
else {
response += "Motor number: ";
response += request->arg("motornum")+", ";
strSerialMessage += "\"motornum\":";
strSerialMessage += request->arg("motornum")+",";
}
}
// Direction: backward = 1, stop = 2, forward = 3;
if (!request->hasArg("dir")){
response += " Direction not specified, setting default stop direction; ";
strSerialMessage += "\"dir\":\"stop\",";
operationArray[1] = 2;
} else if((request->arg("dir") != "bwd")&&(request->arg("dir") != "stop")&&(request->arg("dir") != "fwd")){
response += " Unknown direction parameter, setting default stop direction; ";
strSerialMessage += "\"dir\":\"stop\",";
operationArray[1] = 2;
}
else {
response += "Direction: ";
response += request->arg("dir")+", ";
if (request->arg("dir") == "bwd") operationArray[1] = 1;
else if (request->arg("dir") == "stop") operationArray[1] = 2;
else if (request->arg("dir") == "fwd") operationArray[1] = 3;
strSerialMessage += "\"dir\":";
strSerialMessage += "\""+request->arg("dir")+"\",";
}
if (request->arg("dir") == "stop"){
response += " Motor speed set to 0 due to \"direction : stop\" option; ";
strSerialMessage += "\"motorspeed\":0,";
operationArray[2] = 0;
}
else if (!request->hasArg("motorspeed")){
response += " Motor speed not specified, setting default speed 0; ";
strSerialMessage += "\"motorspeed\":0,";
operationArray[2] = 0;
}
else{
strMotorSpeed = request->arg("motorspeed");
tmpSpeed = strMotorSpeed.toInt();
if ((tmpSpeed>255)||(tmpSpeed<0)) {
response += " Motor speed value out of range (0-255), setting default speed 0; ";
strSerialMessage += "\"motorspeed\":0,";
operationArray[2] = 0;
}
else{
response += "Motor speed: ";
response += request->arg("motorspeed")+", ";
strSerialMessage += "\"motorspeed\":";
strSerialMessage += request->arg("motorspeed")+",";
operationArray[2] = tmpSpeed;
}
}
strTime = request->arg("time");
if (strTime == ""){
response += " Time not specified: unlimited time\n";
strSerialMessage += "\"time\":0";
operationArray[3] = 0;
}
else{
response += "Time: ";
response += strTime +"\n";
strSerialMessage += "\"time\":";
strSerialMessage += strTime;
//strTime = server.arg("time");
time = strTime.toInt();
if (time > MAX_MOTOR_RUN_TIME) time = MAX_MOTOR_RUN_TIME;
operationArray[3] = time;
}
strSerialMessage += "}";
Serial.println(strSerialMessage);
strSerialMessage += "\nOperation array: ";
for(int ii=0;ii<4;ii++) {
strSerialMessage += to_string(operationArray[ii]).c_str();
strSerialMessage += "; ";
}
response += strSerialMessage + "\n";
if ((operationArray[0]==0)||(operationArray[1]==0)) {response += "Wrong motor number or direction parameter!!! \n";request->send(200, "text/json", response);}
else request->send(200, "text/json", response);
}
misc.h and misc.cpp
/*
Miscellaneous classes header for buttons, gyroscopes and program handler
*/
#ifndef MISC_H
#define MISC_H
#include <Adafruit_Sensor.h>
#include <Adafruit_MPU6050.h>
#include <ArduinoJson.h>
#include <debounce.h>
#include <vector>
using namespace std;
inline StaticJsonDocument<200> JSONboard;
const uint8_t NUMBER_OF_BUTTONS = 3;
//- - - - - - - - - - Motor stop buttons pin assignments - - - - - - - - - -
const uint8_t StopButtonPins[8] = {34, 35, 36, 39, 5, 23, 32, 33}; // ESP32 stop button pins list - input only pins
const uint8_t gyrosButtonPins[5] = {16, 17, 25, 26, 27}; // GY-521 gyroscopes AD0 address pins list
class Buttons : public Button{
private:
uint8_t buttonNumber;
uint8_t buttonPin;
uint8_t motorNumber;
uint8_t allowedDirection; // allowed direction of motor motorNumber when end-switch is pressed - MOTOR_FORWARD/MOTOR_BACKWARD
public:
Buttons(uint8_t buttonId, buttonHandler_t buttonHandler, uint8_t motorNum);
uint8_t getButtonPin(void) const {return buttonPin;}
uint8_t getButtonNumber(void) const {return buttonNumber;}
uint8_t getMotorNumber(void) const {return motorNumber;}
uint8_t getAllowedDirection(void) const {return allowedDirection;}
void setAllowedDirection(uint8_t dir);
static uint8_t buttonCount;
};
class Gyros{
private:
uint8_t motorNumber;
uint8_t gyroNumber;
float motorGyroOffset;
float motorGyroRange;
bool calibrated; // dorobit
// uint8_t channel; // channel of gyroscope on CJMCU-9548 multiplexer
uint8_t pinAD0; // Arduino to GY-521 AD0 address pin
Adafruit_MPU6050 gyro;
public:
Gyros(uint8_t motorNum, uint8_t channel);
void setGyroOffset(float offset){motorGyroOffset = offset;}
void setGyroRange(float range){motorGyroOffset = range;}
void setAD0Pin(float pin){pinAD0 = pin;}
void setCalibrated(bool calib){calibrated = calib;}
float getGyroOffset(void) const {return motorGyroOffset;}
float getGyroRange(void) const {return motorGyroRange;}
uint8_t getGyroNumber(void) const {return gyroNumber;}
uint8_t getMotorNumber(void) const {return motorNumber;}
uint8_t getAD0Pin(void) const {return pinAD0;}
bool getCalibrated(void){return calibrated;}
void gyroBegin(void){gyro.begin();}
sensors_vec_t getAccelReading(void);
//float getAccelY(void);
static uint8_t gyrosCount;
};
class ProgramSelector{
private:
bool motorGyro;
bool gyroRead;
bool iicRead;
public:
ProgramSelector(){
motorGyro=false;
gyroRead=false;
iicRead=false;
}
bool getMotorGyroControl(void){return motorGyro;}
bool getGyroRead(void){return gyroRead;}
bool getIICRead(void){return iicRead;}
void setMotorGyroControl(bool state){motorGyro=state;}
void setGyroRead(bool state){gyroRead=state;}
void setIICRead(bool state){iicRead=state;}
void setDefault(void){
motorGyro=false;
gyroRead=false;
iicRead=false;
}
};
const int ONBOARD_LED_PIN = 2;
void selectGyro(uint8_t pin);
void pollGyros(void);
void getIICScannerReading(void);
static void pollButtons(void);
static void stopButtonHandler(uint8_t btnId, uint8_t btnState);
string trimmedstring(float val, uint8_t precisionval);
inline uint8_t Buttons::buttonCount = 0;
inline uint8_t Gyros::gyrosCount = 0;
inline vector<Buttons> buttonList;
inline vector<Gyros> gyroList;
inline ProgramSelector program;
#endif
#include "misc.h"
#include "motors.h"
Buttons::Buttons(uint8_t buttonId, buttonHandler_t buttonHandler, uint8_t motorNum): Button(buttonId, buttonHandler){
buttonCount++;
if (buttonCount>NUMBER_OF_BUTTONS) Serial.println("WARNING! Current button number exceeds NUMBER_OF_BUTTONS constant!!");
else {
motorNumber=motorNum;
buttonNumber = buttonCount;
buttonPin = StopButtonPins[buttonNumber-1]; //set input pin button
allowedDirection = 0;
pinMode( buttonPin, INPUT_PULLUP);
Serial.print(" Initialized button number ");
Serial.print(buttonCount);
Serial.print(" on D1 R32 pin number ");
Serial.println(buttonPin);
}
}
void Buttons::setAllowedDirection(uint8_t dir){
if ((dir==MOTOR_BACKWARD) || (dir==MOTOR_FORWARD)) allowedDirection = dir;
else {Serial.println("Direction parameter must be MOTOR_BACKWARD or MOTOR_FORWARD, setting to 0."); allowedDirection = 0;}
}
Gyros::Gyros(uint8_t motorNum, uint8_t pin){
gyrosCount++;
gyroNumber=gyrosCount;
motorNumber = motorNum;
pinAD0 = pin;
motorGyroOffset = 0.0;
motorGyroRange = 0.5;
calibrated = false;
}
sensors_vec_t Gyros::getAccelReading(void){
sensors_event_t a, g, temp;
gyro.getEvent(&a, &g, &temp);
return a.acceleration;
}
/*
float Gyros::getAccelY(void){
int16_t accelY;
Wire.beginTransmission(0x68);
Wire.write(0x3D); // starting with register 0x3D (ACCEL_YOUT_H) [MPU-6000 and MPU-6050 Register Map and Descriptions Revision 4.2, p.40]
Wire.endTransmission(false); // the parameter indicates that the Arduino will send a restart. As a result, the connection is kept active.
Wire.requestFrom(0x68, 2, true); // Reading ACCEL_YOUT_H (0x3D) and ACCEL_YOUT_L (0x3E) only (2 x 8bit)
accelY = Wire.read()<<8;
accelY |= Wire.read();
return ((float)accelY/16384.0*9.806);
}
*/
void selectGyro(uint8_t pin){
for(auto& gyroIdx : gyroList) digitalWrite(gyroIdx.getAD0Pin(),HIGH);
if (pin != 0) digitalWrite(pin,LOW);
}
void pollGyros(void) {
sensors_vec_t acc;
float accY;
unsigned long actualTime = millis();
static unsigned long pollTime = 0;
string tmpstr;
if (actualTime - pollTime > 2000) {
for(auto& gyroIdx: gyroList){
selectGyro(gyroIdx.getAD0Pin());
acc = gyroIdx.getAccelReading();
selectGyro(0);
JSONboard["id"] = gyroIdx.getGyroNumber();
JSONboard["accX"] = acc.x;
JSONboard["accY"] = acc.y;
pollTime = actualTime;
String JSONstr;
serializeJson(JSONboard, JSONstr);
serializeJson(JSONboard, Serial);
events.send(JSONstr.c_str(), "new_readings", millis());
Serial.println();
}
}
}
void getIICScannerReading(void) {
byte error, address;
int nDevices;
unsigned long actualTime = millis();
static unsigned long pollTime = 0;
if (actualTime - pollTime > 3000) {
nDevices = 0;
for (address = 1; address < 127; address++) {
// The i2c_scanner uses the return value of
// the Write.endTransmisstion to see if
// a device did acknowledge to the address.
Wire.beginTransmission(address);
error = Wire.endTransmission();
if (error == 0){
Serial.print("I2C device found at address 0x");
if (address < 16)
Serial.print("0");
Serial.print(address, HEX);
Serial.println(" !");
nDevices++;
} else if (error == 4) {
Serial.print("Unknown error at address 0x");
if (address < 16)
Serial.print("0");
Serial.println(address, HEX);
}
}
pollTime = actualTime;
Serial.println();
}
}
static void pollButtons(void) {
// update() will call buttonHandler() if PIN transitions to a new state and stays there
// for multiple reads over 25+ ms.
for (auto& buttonIdx : buttonList) buttonIdx.update(digitalRead(buttonIdx.getButtonPin()));
}
static void stopButtonHandler(uint8_t btnId, uint8_t btnState) {
if (btnState == BTN_PRESSED) {
for (auto buttonIdx : buttonList)
if (btnId == buttonIdx.getButtonNumber()) stopMotor(buttonIdx.getMotorNumber());
} else {
Serial.print("Button ");
Serial.print(btnId);
Serial.println(" released!");
}
}
string trimmedstring(float val, uint8_t precisionval){
return to_string(val).substr(0, to_string(val).find(".") + precisionval + 1);
}
serverFunctions.h and serverFunctions.cpp
/*
Async Web Server functions
*/
#ifndef SERVERFUNCTIONS_H
#define SERVERFUNCTIONS_H
#include <WiFi.h>
#include <AsyncElegantOTA.h> // async Web Server OTA
#include <ESPmDNS.h>
#include <Wire.h>
#include <string>
#include "motors.h"
#include "misc.h"
#include "events.h"
void restServerRouting(void);
void initComm(void);
void getSettings(AsyncWebServerRequest *request);
void handleNotFound(AsyncWebServerRequest *request);
void setMotorGyro(AsyncWebServerRequest *request);
void setGyroRead(AsyncWebServerRequest *request);
void setIICRead(AsyncWebServerRequest *request);
void stopAll(AsyncWebServerRequest *request);
void getMotorControl(AsyncWebServerRequest *request);
void WiFiStationDisconnected(WiFiEvent_t event, WiFiEventInfo_t info);
void setChannel(void);
void selectMuxChannel(uint8_t bus);
/*IPAddress local_IP(192, 168, 1, 184);
IPAddress gateway(192, 168, 1, 1);
IPAddress subnet(255, 255, 0, 0);*/
inline const char* host = "esp32"; // for OTA updating
inline const char* ssid = "TP-Link_B73A";
inline const char* password = "hala12345";
// ---------- Address device through mDNS device_name- e.g. smartbed
inline const char* device_name = "async";
#endif
#include "motors.h"
#include "misc.h"
#include "serverFunctions.h"
// Define routing ---- Async WebServer
void WebServerRouting(void) {
server.on("/", HTTP_GET, [](AsyncWebServerRequest *request) {
request->send(200, F("text/html"),
F("Welcome to the ESP32 REST Web Server"));
});
server.on("/settings", HTTP_GET, getSettings);
server.on("/gyroread", HTTP_GET, setGyroRead);
server.on("/motorgyro", HTTP_GET, setMotorGyro);
server.on("/i2cread", HTTP_GET, setIICRead);
server.on("/stopall", HTTP_GET, stopAll);
server.on("/motor", HTTP_GET, getMotorControl);
server.on("/readings", HTTP_GET, [](AsyncWebServerRequest *request){
request->send_P(200, "text/html", readings_html);
});
//server.on(F("/mux"), HTTP_GET, setChannel);
}
void getSettings(AsyncWebServerRequest *request) {
String response = "{";
response += "\"ip\": \"" + WiFi.localIP().toString() + "\"";
response += ",\"gw\": \"" + WiFi.gatewayIP().toString() + "\"";
response += ",\"nm\": \"" + WiFi.subnetMask().toString() + "\"";
if (request->arg("signalStrength") == "true") {
response += ",\"signalStrengh\": \"" + String(WiFi.RSSI()) + "\"";
}
if (request->arg("chipInfo") == "true") {
response += ",\"chipId\": \"" + String(ESP.getChipModel()) + "\"";
response += ",\"flashChipId\": \"" + String(ESP.getFlashChipMode()) + "\"";
response += ",\"flashChipSize\": \"" + String(ESP.getFlashChipSize()) + "\"";
response += ",\"flashChipRealSize\": \"" + String(ESP.getFlashChipSize()) + "\"";
}
if (request->arg("freeHeap") == "true") {
response += ",\"freeHeap\": \"" + String(ESP.getFreeHeap()) + "\"";
}
response += "}";
request->send(200, "text/json", response);
}
// Manage not found URL
void handleNotFound(AsyncWebServerRequest *request) {
String message = "File Not Found\n\n";
message += "URI: ";
message += request->url();
message += "\nMethod: ";
message += (request->method() == HTTP_GET) ? "GET" : "POST";
message += "\nArguments: ";
message += request->args();
message += "\n";
for (uint8_t i = 0; i < request->args(); i++) {
message += " " + request->argName(i) + ": " + request->arg(i) + "\n";
}
request->send(404, "text/plain", message);
}
/*
void reconnectWifi(void) {
static long pollTime = 0;
static bool reconnecting = false;
long actualTime = millis();
if (actualTime - pollTime > 1000) {
if ((WiFi.status() != WL_CONNECTED)){
WiFi.disconnect();
WiFi.begin(ssid, password);
}
pollTime = actualTime;
}
}
*/
void initComm(void) {
Serial.begin(9600);
WiFi.mode(WIFI_STA);
WiFi.onEvent(WiFiStationDisconnected, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED);
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected.");
Serial.println("IP address: ");
Serial.println(WiFi.localIP());
if (MDNS.begin(device_name)) {
Serial.println("MDNS responder started");
}
AsyncElegantOTA.begin(&server); // Start ElegantOTA
WebServerRouting();
server.addHandler(&events);
server.onNotFound(handleNotFound);
// Start server
Serial.println("MAC address: ");
Serial.println(WiFi.macAddress());
server.begin();
Serial.println("HTTP server started");
}
void setMotorGyro(AsyncWebServerRequest *request) {
if (request->arg("state") == "true") {
program.setMotorGyroControl(true);
Serial.println("Motor control by gyroscopes is on");
request->send(200, "text/json", "Motor control by gyroscopes is on");
}
if (request->arg("state") == "false") {
program.setMotorGyroControl(false);
Serial.println("Motor control by gyroscopes is off");
request->send(200, "text/json", "Motor control by gyroscopes is off");
}
}
void setGyroRead(AsyncWebServerRequest *request) {
if (request->arg("state") == "true") {
program.setGyroRead(true);
Serial.println("Gyroscopes reading on");
request->send(200, "text/json", "Gyroscopes reading on");
}
if (request->arg("state") == "false") {
program.setGyroRead(false);
Serial.println("Gyroscopes reading off");
request->send(200, "text/json", "Gyroscopes reading off");
}
}
void setIICRead(AsyncWebServerRequest *request) {
if (request->arg("state") == "true") {
program.setIICRead(true);
Serial.println("I2C scanner reading on");
request->send(200, "text/json", "I2C scanner reading on");
}
if (request->arg("state") == "false") {
program.setIICRead(false);
Serial.println("I2C scanner reading off");
request->send(200, "text/json", "I2C scanner reading off");
}
}
void stopAll(AsyncWebServerRequest *request) {
for (auto& motorIdx : motorList) {
motorIdx.setMotorDirection(MOTOR_STOP);
motorIdx.runMotor();
motorIdx.setMotorState(false);
motorIdx.setMotorStopTime(0);
}
program.setMotorGyroControl(false); // turn off automatic motor control through gyroscope, manual control ON
Serial.println("Everything stopped, program step set to 0");
request->send(200, "text/json", "Everything stopped, all motors' stop time set to 0, ProgramSelector: motorGyroControl set to false;");
}
void getMotorControl(AsyncWebServerRequest *request) {
int operationArray[4] = { 0, 0, 0, 0 }; // operation array: operationArray[0] - motor number; [1] - direction; [2] - speed; [3] - time
fetchServerMotorCommand(operationArray, request);
if (operationArray[MOTOR_NUMBER] > 0)
for (auto& motorIdx : motorList)
if (motorIdx.getMotorNumber() == operationArray[MOTOR_NUMBER]) {
motorIdx.setMotorDirection(operationArray[MOTOR_DIRECTION]);
motorIdx.setMotorSpeed(operationArray[MOTOR_SPEED]);
motorIdx.setMotorStopTime(operationArray[MOTOR_TIME]);
motorIdx.runMotor();
}
}
void WiFiStationDisconnected(WiFiEvent_t event, WiFiEventInfo_t info){
Serial.println("Disconnected from WiFi access point");
Serial.print("WiFi lost connection. Reason: ");
Serial.println(info.wifi_sta_disconnected.reason);
Serial.println("Trying to Reconnect");
WiFi.begin(ssid, password);
}
/*
void setChannel(AsyncWebServerRequest *request) {
String strChannelNum = request->arg("chan");
String message = "Mux Channel set to: ";
selectMuxChannel(strChannelNum.toInt());
Serial.print("Mux Channel set to: ");
Serial.println(strChannelNum);
message += strChannelNum;
request->send(200, "text/json", message);
}
void selectMuxChannel(uint8_t bus) {
Wire.beginTransmission(0x70); // TCA9548A address is 0x70
Wire.write(1 << bus); // send byte to select bus
Wire.endTransmission();
}
*/
There is also events.h file, but it only contains HTML with gyro readings that is sent to PC