From 0fda7b554c714bb16ba734ea383b8cabafc408ca Mon Sep 17 00:00:00 2001 From: Willem Oldemans Date: Sat, 4 Nov 2023 21:20:45 +0100 Subject: [PATCH] abstractions --- .gitignore | 2 + platformio.ini | 1 + src/Motors.cpp | 173 +++++++++++++++ src/config.h | 21 ++ src/html.cpp | 219 +++++++++++++++++++ src/html.h | 5 + src/main.cpp | 526 ++-------------------------------------------- src/motors.h | 46 ++++ src/webserver.cpp | 96 +++++++++ src/webserver.h | 29 +++ 10 files changed, 606 insertions(+), 512 deletions(-) create mode 100644 src/Motors.cpp create mode 100644 src/config.h create mode 100644 src/html.cpp create mode 100644 src/html.h create mode 100644 src/motors.h create mode 100644 src/webserver.cpp create mode 100644 src/webserver.h diff --git a/.gitignore b/.gitignore index 89cc49c..ca54ea2 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,5 @@ .vscode/c_cpp_properties.json .vscode/launch.json .vscode/ipch +**.DS_Store +.vscode/extensions.json diff --git a/platformio.ini b/platformio.ini index b6649a8..2f0f776 100644 --- a/platformio.ini +++ b/platformio.ini @@ -12,6 +12,7 @@ platform = espressif32 board = esp32dev framework = arduino +monitor_speed = 115200 lib_deps = me-no-dev/AsyncTCP@^1.1.1 madhephaestus/ESP32Servo@^1.1.0 diff --git a/src/Motors.cpp b/src/Motors.cpp new file mode 100644 index 0000000..b973eb2 --- /dev/null +++ b/src/Motors.cpp @@ -0,0 +1,173 @@ +#include "motors.h" + +bool removeArmMomentum = false; + +Servo bucketServo; +Servo auxServo; + +std::vector motorPins = +{ + {32, 33}, //RIGHT_MOTOR Pins (IN1, IN2) + {26, 25}, //LEFT_MOTOR Pins + {19, 22}, //ARM_MOTOR pins +}; + +void setUpPinModes() +{ + + for (int i = 0; i < motorPins.size(); i++) + { + pinMode(motorPins[i].pinIN1, OUTPUT); + pinMode(motorPins[i].pinIN2, OUTPUT); + } + moveCar(STOP, false); + bucketServo.attach(bucketServoPin); + auxServo.attach(auxServoPin); + auxControl(150); + bucketTilt(140); +} + +void rotateMotor(int motorNumber, int motorDirection) +{ + if (motorDirection == FORWARD) + { + digitalWrite(motorPins[motorNumber].pinIN1, HIGH); + digitalWrite(motorPins[motorNumber].pinIN2, LOW); + } + else if (motorDirection == BACKWARD) + { + digitalWrite(motorPins[motorNumber].pinIN1, LOW); + digitalWrite(motorPins[motorNumber].pinIN2, HIGH); + } + else + { + if(removeArmMomentum) + { + digitalWrite(motorPins[ARM_MOTOR].pinIN1, HIGH); + digitalWrite(motorPins[ARM_MOTOR].pinIN2, LOW); + delay(10); + digitalWrite(motorPins[motorNumber].pinIN1, LOW); + digitalWrite(motorPins[motorNumber].pinIN2, LOW); + delay(5); + digitalWrite(motorPins[ARM_MOTOR].pinIN1, HIGH); + digitalWrite(motorPins[ARM_MOTOR].pinIN2, LOW); + delay(10); + removeArmMomentum = false; + } + digitalWrite(motorPins[motorNumber].pinIN1, LOW); + digitalWrite(motorPins[motorNumber].pinIN2, LOW); + } +} + +void setMomentum(bool val) +{ + removeArmMomentum = val; +} + + +void bucketTilt(int bucketServoValue) +{ + bucketServo.write(bucketServoValue); +} +void auxControl(int auxServoValue) +{ + auxServo.write(auxServoValue); +} + + + +void moveCar(int inputValue, bool horizontal) +{ + Serial.printf("Got value as %d\n", inputValue); + if(!(horizontal)) + { + switch(inputValue) + { + + case UP: + rotateMotor(RIGHT_MOTOR, FORWARD); + rotateMotor(LEFT_MOTOR, FORWARD); + break; + + case DOWN: + rotateMotor(RIGHT_MOTOR, BACKWARD); + rotateMotor(LEFT_MOTOR, BACKWARD); + break; + + case LEFT: + rotateMotor(RIGHT_MOTOR, BACKWARD); + rotateMotor(LEFT_MOTOR, FORWARD); + break; + + case RIGHT: + rotateMotor(RIGHT_MOTOR, FORWARD); + rotateMotor(LEFT_MOTOR, BACKWARD); + break; + + case STOP: + rotateMotor(ARM_MOTOR, STOP); + rotateMotor(RIGHT_MOTOR, STOP); + rotateMotor(LEFT_MOTOR, STOP); + break; + + case ARMUP: + rotateMotor(ARM_MOTOR, FORWARD); + break; + + case ARMDOWN: + rotateMotor(ARM_MOTOR, BACKWARD); + setMomentum(true); + break; + + default: + rotateMotor(ARM_MOTOR, STOP); + rotateMotor(RIGHT_MOTOR, STOP); + rotateMotor(LEFT_MOTOR, STOP); + break; + } + }else { + switch(inputValue) + { + case UP: + rotateMotor(RIGHT_MOTOR, BACKWARD); + rotateMotor(LEFT_MOTOR, FORWARD); + break; + + case DOWN: + rotateMotor(RIGHT_MOTOR, FORWARD); + rotateMotor(LEFT_MOTOR, BACKWARD); + break; + + case LEFT: + rotateMotor(RIGHT_MOTOR, BACKWARD); + rotateMotor(LEFT_MOTOR, BACKWARD); + break; + + case RIGHT: + rotateMotor(RIGHT_MOTOR, FORWARD); + rotateMotor(LEFT_MOTOR, FORWARD); + break; + + case STOP: + rotateMotor(ARM_MOTOR, STOP); + rotateMotor(RIGHT_MOTOR, STOP); + rotateMotor(LEFT_MOTOR, STOP); + break; + + case ARMUP: + rotateMotor(ARM_MOTOR, FORWARD); + break; + + case ARMDOWN: + rotateMotor(ARM_MOTOR, BACKWARD); + setMomentum(true); + break; + + default: + rotateMotor(ARM_MOTOR, STOP); + rotateMotor(RIGHT_MOTOR, STOP); + rotateMotor(LEFT_MOTOR, STOP); + break; + } + } +} diff --git a/src/config.h b/src/config.h new file mode 100644 index 0000000..14a4dc0 --- /dev/null +++ b/src/config.h @@ -0,0 +1,21 @@ +//config + + +//Pin configuration +#define RMOTOR_IN1 32 +#define RMOTOR_IN2 33 +#define LMOTOR_IN1 26 +#define LMOTOR_IN2 25 +#define ARM_IN1 19 +#define ARM_IN2 22 + +#define bucketServoPin 23 +#define auxServoPin 17 + +//defaults + +#define default_auxControl 150 +#define default_bucketTilt 140 + + + diff --git a/src/html.cpp b/src/html.cpp new file mode 100644 index 0000000..66602be --- /dev/null +++ b/src/html.cpp @@ -0,0 +1,219 @@ +#include "html.h" + +const char htmlHomePage[] PROGMEM = R"HTMLHOMEPAGE( + + + + + + + + + +
+ + +
+

MINISKIDI

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Bucket: +
+ +
+
AUX: +
+ +
+
+ + + + +)HTMLHOMEPAGE"; \ No newline at end of file diff --git a/src/html.h b/src/html.h new file mode 100644 index 0000000..136f092 --- /dev/null +++ b/src/html.h @@ -0,0 +1,5 @@ +#pragma once + +#include +//declare here, define in cpp to prevent multiple declarations +extern const char htmlHomePage[] PROGMEM; diff --git a/src/main.cpp b/src/main.cpp index f09de98..40769bb 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,530 +1,32 @@ //make sure to upload with ESP32 Dev Module selected as the board under tools>Board>ESP32 Arduino #include -#ifdef ESP32 #include -#include //by dvarrel -#elif defined(ESP8266) -#include //by dvarrel -#endif -#include //by dvarrel - -#include //by Kevin Harrington -#include -#include - -const char* ssid = "MiniSkidi"; - -#define bucketServoPin 23 - -#define auxServoPin 22 - -Servo bucketServo; -Servo auxServo; -struct MOTOR_PINS -{ - int pinIN1; - int pinIN2; -}; - -std::vector motorPins = -{ - {32, 33}, //RIGHT_MOTOR Pins (IN1, IN2) - {26, 25}, //LEFT_MOTOR Pins - {19, 21}, //ARM_MOTOR pins -}; - -#define UP 1 -#define DOWN 2 -#define LEFT 3 -#define RIGHT 4 -#define ARMUP 5 -#define ARMDOWN 6 -#define STOP 0 - - -#define RIGHT_MOTOR 1 -#define LEFT_MOTOR 0 -#define ARM_MOTOR 2 - -#define FORWARD 1 -#define BACKWARD -1 - -bool horizontalScreen;//When screen orientation is locked vertically this rotates the D-Pad controls so that forward would now be left. -bool removeArmMomentum = false; - - - -AsyncWebServer server(80); -AsyncWebSocket wsCarInput("/CarInput"); - -const char* htmlHomePage PROGMEM = R"HTMLHOMEPAGE( - - - - - - - - - -
- - -
-

MINISKIDI

- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
Bucket: -
- -
-
AUX: -
- -
-
- - - - -)HTMLHOMEPAGE"; - - -void rotateMotor(int motorNumber, int motorDirection) -{ - if (motorDirection == FORWARD) - { - digitalWrite(motorPins[motorNumber].pinIN1, HIGH); - digitalWrite(motorPins[motorNumber].pinIN2, LOW); - } - else if (motorDirection == BACKWARD) - { - digitalWrite(motorPins[motorNumber].pinIN1, LOW); - digitalWrite(motorPins[motorNumber].pinIN2, HIGH); - } - else - { - if(removeArmMomentum) - { - digitalWrite(motorPins[ARM_MOTOR].pinIN1, HIGH); - digitalWrite(motorPins[ARM_MOTOR].pinIN2, LOW); - delay(10); - digitalWrite(motorPins[motorNumber].pinIN1, LOW); - digitalWrite(motorPins[motorNumber].pinIN2, LOW); - delay(5); - digitalWrite(motorPins[ARM_MOTOR].pinIN1, HIGH); - digitalWrite(motorPins[ARM_MOTOR].pinIN2, LOW); - delay(10); - removeArmMomentum = false; - } - digitalWrite(motorPins[motorNumber].pinIN1, LOW); - digitalWrite(motorPins[motorNumber].pinIN2, LOW); - } -} - -void moveCar(int inputValue) -{ - Serial.printf("Got value as %d\n", inputValue); - if(!(horizontalScreen)) - { - switch(inputValue) - { - - case UP: - rotateMotor(RIGHT_MOTOR, FORWARD); - rotateMotor(LEFT_MOTOR, FORWARD); - break; - - case DOWN: - rotateMotor(RIGHT_MOTOR, BACKWARD); - rotateMotor(LEFT_MOTOR, BACKWARD); - break; - - case LEFT: - rotateMotor(RIGHT_MOTOR, BACKWARD); - rotateMotor(LEFT_MOTOR, FORWARD); - break; - - case RIGHT: - rotateMotor(RIGHT_MOTOR, FORWARD); - rotateMotor(LEFT_MOTOR, BACKWARD); - break; - - case STOP: - rotateMotor(ARM_MOTOR, STOP); - rotateMotor(RIGHT_MOTOR, STOP); - rotateMotor(LEFT_MOTOR, STOP); - break; - - case ARMUP: - rotateMotor(ARM_MOTOR, FORWARD); - break; - - case ARMDOWN: - rotateMotor(ARM_MOTOR, BACKWARD); - removeArmMomentum = true; - break; - - default: - rotateMotor(ARM_MOTOR, STOP); - rotateMotor(RIGHT_MOTOR, STOP); - rotateMotor(LEFT_MOTOR, STOP); - break; - } - }else { - switch(inputValue) - { - case UP: - rotateMotor(RIGHT_MOTOR, BACKWARD); - rotateMotor(LEFT_MOTOR, FORWARD); - break; - - case DOWN: - rotateMotor(RIGHT_MOTOR, FORWARD); - rotateMotor(LEFT_MOTOR, BACKWARD); - break; - - case LEFT: - rotateMotor(RIGHT_MOTOR, BACKWARD); - rotateMotor(LEFT_MOTOR, BACKWARD); - break; - - case RIGHT: - rotateMotor(RIGHT_MOTOR, FORWARD); - rotateMotor(LEFT_MOTOR, FORWARD); - break; - - case STOP: - rotateMotor(ARM_MOTOR, STOP); - rotateMotor(RIGHT_MOTOR, STOP); - rotateMotor(LEFT_MOTOR, STOP); - break; - - case ARMUP: - rotateMotor(ARM_MOTOR, FORWARD); - break; - - case ARMDOWN: - rotateMotor(ARM_MOTOR, BACKWARD); - removeArmMomentum = true; - break; - - default: - rotateMotor(ARM_MOTOR, STOP); - rotateMotor(RIGHT_MOTOR, STOP); - rotateMotor(LEFT_MOTOR, STOP); - break; - } - } -} - - -void bucketTilt(int bucketServoValue) -{ - bucketServo.write(bucketServoValue); -} -void auxControl(int auxServoValue) -{ - auxServo.write(auxServoValue); -} - - -void handleRoot(AsyncWebServerRequest *request) -{ - request->send_P(200, "text/html", htmlHomePage); -} - -void handleNotFound(AsyncWebServerRequest *request) -{ - request->send(404, "text/plain", "File Not Found"); -} - -void onCarInputWebSocketEvent(AsyncWebSocket *server, - AsyncWebSocketClient *client, - AwsEventType type, - void *arg, - uint8_t *data, - size_t len) -{ - switch (type) - { - case WS_EVT_CONNECT: - Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str()); - break; - case WS_EVT_DISCONNECT: - Serial.printf("WebSocket client #%u disconnected\n", client->id()); - moveCar(STOP); - break; - case WS_EVT_DATA: - AwsFrameInfo *info; - info = (AwsFrameInfo*)arg; - if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) - { - std::string myData = ""; - myData.assign((char *)data, len); - std::istringstream ss(myData); - std::string key, value; - std::getline(ss, key, ','); - std::getline(ss, value, ','); - Serial.printf("Key [%s] Value[%s]\n", key.c_str(), value.c_str()); - int valueInt = atoi(value.c_str()); - if (key == "MoveCar") - { - moveCar(valueInt); - } - else if (key == "AUX") - { - auxControl(valueInt); - } - else if (key == "Bucket") - { - bucketTilt(valueInt); - } - else if (key =="Switch") - { - if(!(horizontalScreen)) - { - horizontalScreen = true; - } - else{ - horizontalScreen = false; - } - } - } - break; - case WS_EVT_PONG: - case WS_EVT_ERROR: - break; - default: - break; - } -} - -void setUpPinModes() -{ - - for (int i = 0; i < motorPins.size(); i++) - { - pinMode(motorPins[i].pinIN1, OUTPUT); - pinMode(motorPins[i].pinIN2, OUTPUT); - } - moveCar(STOP); - bucketServo.attach(bucketServoPin); - auxServo.attach(auxServoPin); - auxControl(150); - bucketTilt(140); -} +#include "motors.h" +#include "webserver.h" +const char* ssid = "iot"; +const char* pwd = "Rijnstraat214"; void setup(void) { setUpPinModes(); Serial.begin(115200); - - WiFi.softAP(ssid ); - IPAddress IP = WiFi.softAPIP(); + WiFi.mode(WIFI_STA); + WiFi.begin(ssid,pwd ); + if (WiFi.waitForConnectResult() != WL_CONNECTED) + { + Serial.printf("WiFi Failed!\n"); + return; + } + IPAddress IP = WiFi.localIP(); Serial.print("AP IP address: "); Serial.println(IP); - server.on("/", HTTP_GET, handleRoot); - server.onNotFound(handleNotFound); - - wsCarInput.onEvent(onCarInputWebSocketEvent); - server.addHandler(&wsCarInput); - - server.begin(); - Serial.println("HTTP server started"); - + setup_webserver(); } void loop() { - wsCarInput.cleanupClients(); + loop_webserver(); } \ No newline at end of file diff --git a/src/motors.h b/src/motors.h new file mode 100644 index 0000000..1076892 --- /dev/null +++ b/src/motors.h @@ -0,0 +1,46 @@ +#pragma once + +#include +#include + +#include //by Kevin Harrington + + +#define RIGHT_MOTOR 1 +#define LEFT_MOTOR 0 +#define ARM_MOTOR 2 + +#define FORWARD 1 +#define BACKWARD -1 + +#define bucketServoPin 23 + +#define auxServoPin 17 + +#define UP 1 +#define DOWN 2 +#define LEFT 3 +#define RIGHT 4 +#define ARMUP 5 +#define ARMDOWN 6 +#define STOP 0 + + +struct MOTOR_PINS +{ + int pinIN1; + int pinIN2; +}; + +//general functions +void setUpPinModes(); +void moveCar(int inputValue, bool horizontal); + + +//motor functions +void rotateMotor(int motorNumber, int motorDirection); +void setMomentum(bool val); + +//Servo functions +void bucketTilt(int bucketServoValue); +void auxControl(int auxServoValue); \ No newline at end of file diff --git a/src/webserver.cpp b/src/webserver.cpp new file mode 100644 index 0000000..54fc1fc --- /dev/null +++ b/src/webserver.cpp @@ -0,0 +1,96 @@ +#include "webserver.h" + + + +bool horizontalScreen;//When screen orientation is locked vertically this rotates the D-Pad controls so that forward would now be left. + +AsyncWebServer server(80); +AsyncWebSocket wsCarInput("/CarInput"); + +void loop_webserver() +{ + wsCarInput.cleanupClients(); +} + +void setup_webserver() +{ + server.on("/", HTTP_GET, handleRoot); + server.onNotFound(handleNotFound); + + wsCarInput.onEvent(onCarInputWebSocketEvent); + server.addHandler(&wsCarInput); + + server.begin(); + Serial.println("HTTP server started"); +} + +void handleRoot(AsyncWebServerRequest *request) +{ + request->send_P(200, "text/html", htmlHomePage); +} + +void handleNotFound(AsyncWebServerRequest *request) +{ + request->send(404, "text/plain", "File Not Found"); +} + +void onCarInputWebSocketEvent(AsyncWebSocket *server, + AsyncWebSocketClient *client, + AwsEventType type, + void *arg, + uint8_t *data, + size_t len) +{ + switch (type) + { + case WS_EVT_CONNECT: + Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str()); + break; + case WS_EVT_DISCONNECT: + Serial.printf("WebSocket client #%u disconnected\n", client->id()); + moveCar(STOP, horizontalScreen); + break; + case WS_EVT_DATA: + AwsFrameInfo *info; + info = (AwsFrameInfo*)arg; + if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) + { + std::string myData = ""; + myData.assign((char *)data, len); + std::istringstream ss(myData); + std::string key, value; + std::getline(ss, key, ','); + std::getline(ss, value, ','); + Serial.printf("Key [%s] Value[%s]\n", key.c_str(), value.c_str()); + int valueInt = atoi(value.c_str()); + if (key == "MoveCar") + { + moveCar(valueInt, horizontalScreen); + } + else if (key == "AUX") + { + auxControl(valueInt); + } + else if (key == "Bucket") + { + bucketTilt(valueInt); + } + else if (key =="Switch") + { + if(!(horizontalScreen)) + { + horizontalScreen = true; + } + else{ + horizontalScreen = false; + } + } + } + break; + case WS_EVT_PONG: + case WS_EVT_ERROR: + break; + default: + break; + } +} \ No newline at end of file diff --git a/src/webserver.h b/src/webserver.h new file mode 100644 index 0000000..ba42677 --- /dev/null +++ b/src/webserver.h @@ -0,0 +1,29 @@ +#pragma once + +#include +#include "html.h" +#include "motors.h" + +#ifdef ESP32 +#include +#include //by dvarrel +#elif defined(ESP8266) +#include //by dvarrel +#endif +#include //by dvarrel + +#include +#include + + +void loop_webserver(); +void setup_webserver(); + +void handleRoot(AsyncWebServerRequest *request); +void handleNotFound(AsyncWebServerRequest *request); +void onCarInputWebSocketEvent(AsyncWebSocket *server, + AsyncWebSocketClient *client, + AwsEventType type, + void *arg, + uint8_t *data, + size_t len); \ No newline at end of file