Compare commits

..

10 commits

11 changed files with 409 additions and 441 deletions

20
README.md Normal file
View file

@ -0,0 +1,20 @@
# Fork "Mon premier robot"
Tentative de re-factorisation du code et d'amélioration de UI web du robot de
l'[Atelier Printemps 2024 - MON PREMIER ROBOT](https://projets.cohabit.fr/redmine/projects/ateliers/wiki/Atelier_Printemps_2024).
## Usage
Ouvrir le workspace [robot.code-workspace](./robot.code-workspace) dans VS Code
pour un environnement déjà configurer.
### Client
Testé dans Chrome (pc/android) et Firefox (pc) avec
[live server](https://marketplace.visualstudio.com/items?itemName=ritwickdey.LiveServer).
### Server
Compilé avec la cli [Platform IO](https://platformio.org/)
(`cd ./server && pio run`). Testé avec le simulateur [Wokwi](https://wokwi.com/)
en ligne et sur VS Code.

3
client/.vscode/extensions.json vendored Normal file
View file

@ -0,0 +1,3 @@
{
"recommendations": ["ritwickdey.liveserver"]
}

9
client/README.md Normal file
View file

@ -0,0 +1,9 @@
# Client
Code pour l'interface utilisateur via le web.
## Usage
Ouvrir [index.html](./index.html) dans un navigateur ou avec
[Live Server](https://marketplace.visualstudio.com/items?itemName=ritwickdey.LiveServer)
sur VS Code.

View file

@ -15,7 +15,7 @@ export async function sendCommand(command, value) {
const endpoint = getEndpoint() const endpoint = getEndpoint()
const url = new URL(`/get?command=${command}&value=${value}`, endpoint) const url = new URL(`/get?command=${command}&value=${value}`, endpoint)
const response = await fetch(url, { const response = await fetch(url, {
mode: 'no-cors' mode: 'no-cors',
}) })
const text = await response.text() const text = await response.text()
console.log(text) console.log(text)
@ -58,9 +58,9 @@ export async function testEndpoint(endpoint) {
try { try {
const url = new URL('/get', endpoint) const url = new URL('/get', endpoint)
const response = await fetch(url, { const response = await fetch(url, {
mode: 'no-cors' mode: 'no-cors',
}) })
if (response.ok) return if (response.ok || response.status === 0) alert('Connection réussie')
} catch (cause) { } catch (cause) {
alert(`Impossible de joindre l'adresse "${endpoint}"`) alert(`Impossible de joindre l'adresse "${endpoint}"`)
throw new Error(`unable to connect to robot at ${endpoint}`, { throw new Error(`unable to connect to robot at ${endpoint}`, {

12
server/README.md Normal file
View file

@ -0,0 +1,12 @@
# Server
Code pour l'ESP32 (code embarqué dans le robot).
## Usage
Commenter un des 2 points d'entrée dans [src](./src/) et lancer `pio run` ou
équivalent. Mettre à jour la configuration WiFi dans [config](./src/config.h) et
[server](./src/server.hpp) pour téléverser vers l'ESP32. Sinon lancer le
simulateur [Wokwi](https://docs.wokwi.com/vscode/getting-started) dans VS Code
ou copier le code pour le lancer dans le navigateur sur
[wokwi.com](https://wokwi.com/).

View file

@ -1,228 +1,26 @@
//Définition des ports pour controler les moteurs // Libraries locales pour configurer et contrôler le robot.
//Moteur gauche : #include "config.h" // Configuration des entrées/sorties et delais.
#define IN1a 27 #include "controls.h" // Fonctions pour se déplacer.
#define IN2a 14 #include "convert.h" // Utilitaires pour convertir des mesures en steps.
#define IN3a 12
#define IN4a 13
//Moteur droit :
#define IN1b 5
#define IN2b 18
#define IN3b 19
#define IN4b 21
//Temps d'attente entre deux impulsions :
int delayTime = 3;
//Code éxécuté au démarrage (paramétrage) :
void setup() {
//On indique que les ports de controle des moteurs sont des sorties (output)
pinMode(IN1a, OUTPUT);
pinMode(IN2a, OUTPUT);
pinMode(IN3a, OUTPUT);
pinMode(IN4a, OUTPUT);
pinMode(IN1b, OUTPUT);
pinMode(IN2b, OUTPUT);
pinMode(IN3b, OUTPUT);
pinMode(IN4b, OUTPUT);
// Code exécuté au démarrage (paramétrage) :
void setup()
{
setupPins(); // Configure les pins de l'ESP32
Serial.begin(115200); // Démarrage d'une communication Série avec l'ordinateur s'il est connecté Serial.begin(115200); // Démarrage d'une communication Série avec l'ordinateur s'il est connecté
} }
//Code éxécuté en boucle jusqu'à l'extinction du robot // Code exécuté en boucle jusqu'à l'extinction du robot
void loop() { void loop()
{
// Exemple de commande : // Exemple de commande :
for (int i=0; i<50; i++){ for (int i = 0; i < 50; i++)
{
forward(); forward();
} }
int rotation_steps = convertRotToSteps(46); int rotation_steps = convertRotToSteps(46);
for (int i=0; i<rotation_steps; i++){ for (int i = 0; i < rotation_steps; i++)
{
left(); left();
} }
} }
//Fonction pour convertir une longueur en cm vers un nombre de pas moteur.
int convertLengthToSteps(float length){
float result = length*512/(4*3.1415);
return int(result);
}
//fonction pour convertir une rotation en degrés vers un nombre de pas moteur
int convertRotToSteps(int rotation){
int result = convertLengthToSteps(rotation*3.1415/180*7.8);
return result;
}
void forward(){
digitalWrite(IN4a, HIGH);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, HIGH);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, HIGH);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, HIGH);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, HIGH);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, HIGH);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, HIGH);
digitalWrite(IN4b, HIGH);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
}
void backward(){
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, HIGH);
digitalWrite(IN4b, HIGH);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, HIGH);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, HIGH);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, HIGH);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, HIGH);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, HIGH);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, HIGH);
delay(delayTime);
}
void right(){
digitalWrite(IN4a, HIGH);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, HIGH);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, HIGH);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, HIGH);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, HIGH);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, HIGH);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, HIGH);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, HIGH);
delay(delayTime);
}
void left(){
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, HIGH);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, HIGH);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, HIGH);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, HIGH);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, HIGH);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, HIGH);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
digitalWrite(IN4a, HIGH);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, HIGH);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
delay(delayTime);
}
void stopMotors(void) {
digitalWrite(IN4a, LOW);
digitalWrite(IN3a, LOW);
digitalWrite(IN2a, LOW);
digitalWrite(IN1a, LOW);
digitalWrite(IN4b, LOW);
digitalWrite(IN3b, LOW);
digitalWrite(IN2b, LOW);
digitalWrite(IN1b, LOW);
}

View file

@ -3,36 +3,14 @@
#include <ESPAsyncWebServer.h> #include <ESPAsyncWebServer.h>
#include <WiFi.h> #include <WiFi.h>
// Définition des ports pour contrôler les moteurs // Libraries locales pour configurer et contrôler le robot.
// Moteur gauche : #include "config.h" // Configuration des entrées/sorties et delais.
#define IN1a 27 #include "controls.h" // Fonctions pour se déplacer.
#define IN2a 14 #include "convert.h" // Utilitaires pour convertir des mesures en steps.
#define IN3a 12 #include "server.hpp" // Configure et demarre le server HTTP.
#define IN4a 13
// Moteur droit :
#define IN1b 5
#define IN2b 18
#define IN3b 19
#define IN4b 21
// Paramètres de connexion wifi : // État global de la commande en cours
// const char *ssid = "ESP32"; command_t command = {.running = false, .stopped = false};
// const char *password = "test12345";
// For simulator only
const char *ssid = "Wokwi-GUEST";
const char *password = "";
// Temps d'attente entre deux impulsions :
int delayTime = 3;
// Variables de commande :
struct command_t
{
bool running; // Une commande doit être exécutée
bool stopped; // La commande doit être stoppée
String name; // Nom de la commande
int value; // Valeur (nombre de pas à effectuer)
} command = {false, false};
// Création du serveur asynchrone : // Création du serveur asynchrone :
AsyncWebServer server(80); AsyncWebServer server(80);
@ -40,20 +18,10 @@ AsyncWebServer server(80);
// Code exécuté au démarrage (paramétrage) : // Code exécuté au démarrage (paramétrage) :
void setup() void setup()
{ {
// On indique que les ports de contrôle des moteurs sont des sorties (output) setupPins(); // Configure les pins de l'ESP32
pinMode(IN1a, OUTPUT);
pinMode(IN2a, OUTPUT);
pinMode(IN3a, OUTPUT);
pinMode(IN4a, OUTPUT);
pinMode(IN1b, OUTPUT);
pinMode(IN2b, OUTPUT);
pinMode(IN3b, OUTPUT);
pinMode(IN4b, OUTPUT);
Serial.begin(115200); // Démarrage d'une communication Série avec l'ordinateur s'il est connecté Serial.begin(115200); // Démarrage d'une communication Série avec l'ordinateur s'il est connecté
connectWiFi(); // Connexion au wifi connectWiFi(WiFi); // Connexion au wifi
serverConfig(); // Configuration du serveur serverConfig(server, command); // Configuration du serveur
server.begin(); // Démarrage du serveur server.begin(); // Démarrage du serveur
} }
@ -76,7 +44,7 @@ void loop()
} }
// Sinon executer la commande en cours // Sinon executer la commande en cours
chooseCommand(); // Appeler la fonction "chooseCommand()" updateCommand(command); // Met à jour la commande global
if (command.value > 0) if (command.value > 0)
{ // S'il reste des pas à effectuer alors on l'affiche et on enlève un pas { // S'il reste des pas à effectuer alors on l'affiche et on enlève un pas
Serial.print(command.name); Serial.print(command.name);
@ -86,113 +54,8 @@ void loop()
} }
} }
// Configuration du serveur asynchrone // Met à jour l'état du robot en fonction de la commande en cours.
void serverConfig() void updateCommand(command_t &command)
{
server.on("/get", HTTP_GET, [](AsyncWebServerRequest *request)
{
String commandName;
float commandValue;
// Parse request params and update command and value
parseRequestParams(request, commandName, commandValue);
Serial.print(commandName);
Serial.print(": ");
Serial.println(commandValue);
request->send(200, "text/plain", commandName); });
}
void parseRequestParams(AsyncWebServerRequest *request, String &commandName, float &commandValue)
{
// Stop here with error message if wrong command
if (!request->hasParam("command"))
{
commandName = "No command provided";
return;
}
// Update command from params
commandName = request->getParam("command")->value();
// Update value from params and use "0" as default
commandValue = request->hasParam("value") ? request->getParam("value")->value().toFloat() : 0;
requestCheck(commandName, commandValue);
}
// Fonction pour convertir une longueur en cm vers un nombre de pas moteur.
int convertLengthToSteps(float length)
{
float result = length * 512 / (4 * 3.1415);
return int(result);
}
// fonction pour convertir une rotation en degrés vers un nombre de pas moteur
int convertRotToSteps(int rotation)
{
int result = convertLengthToSteps(rotation * 3.1415 / 180 * 7.8);
return result;
}
// Lorsqu'une commande arrive au serveur, cette fonction permet
void requestCheck(String commandName, float commandValue)
{
if (commandName == "stop")
{
command.name = "stop";
command.running = true;
command.stopped = true;
}
else
{
setGlobals(commandName, commandValue);
}
if (commandValue == 0)
{
command.value = 474;
}
}
void setGlobals(String commandName, float commandValue)
{
// Assert command before updating globals
if (commandName != "forward" && commandName != "backward" && commandName != "left" && commandName != "right")
{
return;
}
// Update globals
command.name = commandName;
command.running = true;
command.stopped = false;
command.value = convertLengthToSteps(commandValue);
}
void connectWiFi()
{
// For simulator only
WiFi.mode(WIFI_STA);
WiFi.begin(ssid, password);
if (WiFi.waitForConnectResult() != WL_CONNECTED)
{
Serial.printf("WiFi Failed!\n");
return;
}
Serial.println(" Connected!");
Serial.print("IP Address: ");
Serial.println(WiFi.localIP());
// WiFi.mode(WIFI_AP);
// WiFi.softAP(ssid, password);
// Serial.print("[+] AP Created with IP Gateway ");
// Serial.println(WiFi.softAPIP());
// Serial.println("");
}
void chooseCommand()
{ {
if (command.name == "forward") if (command.name == "forward")
{ {
@ -211,68 +74,3 @@ void chooseCommand()
backward(); backward();
} }
} }
void writeMotor(uint8_t left, uint8_t right)
{
digitalWrite(IN4a, left & 0b1000);
digitalWrite(IN3a, left & 0b0100);
digitalWrite(IN2a, left & 0b0010);
digitalWrite(IN1a, left & 0b0001);
digitalWrite(IN4b, right & 0b1000);
digitalWrite(IN3b, right & 0b0100);
digitalWrite(IN2b, right & 0b0010);
digitalWrite(IN1b, right & 0b0001);
}
void forward()
{
writeMotor(0b1000, 0b0001);
delay(delayTime);
writeMotor(0b0100, 0b0010);
delay(delayTime);
writeMotor(0b0010, 0b0100);
delay(delayTime);
writeMotor(0b0001, 0b1000);
delay(delayTime);
}
void backward()
{
writeMotor(0b0001, 0b1000);
delay(delayTime);
writeMotor(0b0010, 0b0100);
delay(delayTime);
writeMotor(0b0100, 0b0010);
delay(delayTime);
writeMotor(0b1000, 0b0001);
delay(delayTime);
}
void right()
{
writeMotor(0b1000, 0b1000);
delay(delayTime);
writeMotor(0b0100, 0b0100);
delay(delayTime);
writeMotor(0b0010, 0b0010);
delay(delayTime);
writeMotor(0b0001, 0b0001);
delay(delayTime);
}
void left()
{
writeMotor(0b0001, 0b0001);
delay(delayTime);
writeMotor(0b0010, 0b0010);
delay(delayTime);
writeMotor(0b0100, 0b0100);
delay(delayTime);
writeMotor(0b1000, 0b1000);
delay(delayTime);
}
void stopMotors(void)
{
writeMotor(0b0000, 0b0000);
}

25
server/src/config.h Normal file
View file

@ -0,0 +1,25 @@
/************************************
Fichier de configuration du robot
************************************/
// Définition des ports pour contrôler les moteurs
// Moteur gauche :
#define IN1a 27
#define IN2a 14
#define IN3a 12
#define IN4a 13
// Moteur droit :
#define IN1b 5
#define IN2b 18
#define IN3b 19
#define IN4b 21
// Paramètres de connexion wifi :
// #define WIFI_SSID "ESP32"
// #define WIFI_PASSWORD "test12345"
// For simulator only
#define WIFI_SSID "Wokwi-GUEST"
#define WIFI_PASSWORD ""
// Temps d'attente entre deux impulsions :
#define DELAY_TIME 3

117
server/src/controls.h Normal file
View file

@ -0,0 +1,117 @@
/*******************************************
Initialisation et fonctions de déplacement
*******************************************/
/**
* @brief Configure les ports de contrôle des moteurs sont des sorties (output).
*
*/
void setupPins()
{
pinMode(IN1a, OUTPUT);
pinMode(IN2a, OUTPUT);
pinMode(IN3a, OUTPUT);
pinMode(IN4a, OUTPUT);
pinMode(IN1b, OUTPUT);
pinMode(IN2b, OUTPUT);
pinMode(IN3b, OUTPUT);
pinMode(IN4b, OUTPUT);
}
/**
* @brief Applique une configuration aux moteurs.
* @brief Chaque configuration est sur 1 octet.
*
* Exemple
* ```
* writeMotor(0b0010, 0b1100);
* ```
*
* @param left Configuration du moteur droit (ex: `0b1100`).
* @param right Configuration du moteur droit (ex: `0b0101`).
*/
void writeMotor(uint8_t left, uint8_t right)
{
digitalWrite(IN4a, left & 0b1000);
digitalWrite(IN3a, left & 0b0100);
digitalWrite(IN2a, left & 0b0010);
digitalWrite(IN1a, left & 0b0001);
digitalWrite(IN4b, right & 0b1000);
digitalWrite(IN3b, right & 0b0100);
digitalWrite(IN2b, right & 0b0010);
digitalWrite(IN1b, right & 0b0001);
}
/**
* @brief Commande pour faire avancer le robot.
*
*/
void forward()
{
writeMotor(0b1000, 0b0001);
delay(DELAY_TIME);
writeMotor(0b0100, 0b0010);
delay(DELAY_TIME);
writeMotor(0b0010, 0b0100);
delay(DELAY_TIME);
writeMotor(0b0001, 0b1000);
delay(DELAY_TIME);
}
/**
* @brief Commande pour faire reculer le robot.
*
*/
void backward()
{
writeMotor(0b0001, 0b1000);
delay(DELAY_TIME);
writeMotor(0b0010, 0b0100);
delay(DELAY_TIME);
writeMotor(0b0100, 0b0010);
delay(DELAY_TIME);
writeMotor(0b1000, 0b0001);
delay(DELAY_TIME);
}
/**
* @brief Commande pour faire tourner le robot à droite.
*
*/
void right()
{
writeMotor(0b1000, 0b1000);
delay(DELAY_TIME);
writeMotor(0b0100, 0b0100);
delay(DELAY_TIME);
writeMotor(0b0010, 0b0010);
delay(DELAY_TIME);
writeMotor(0b0001, 0b0001);
delay(DELAY_TIME);
}
/**
* @brief Commande pour faire tourner le robot à gauche.
*
*/
void left()
{
writeMotor(0b0001, 0b0001);
delay(DELAY_TIME);
writeMotor(0b0010, 0b0010);
delay(DELAY_TIME);
writeMotor(0b0100, 0b0100);
delay(DELAY_TIME);
writeMotor(0b1000, 0b1000);
delay(DELAY_TIME);
}
/**
* @brief Commande pour arrêter les moteurs du robot.
*
*/
void stopMotors()
{
writeMotor(0b0000, 0b0000);
}

39
server/src/convert.h Normal file
View file

@ -0,0 +1,39 @@
/*********************************************
Utilitaires de conversions physique -> steps
*********************************************/
/**
* @brief Convertit une longueur en cm vers un nombre de pas moteur.
*
* Exemple
* ```
* float distance = 22.3; //cm
* int steps = convertLengthToSteps(distance);
* ```
*
* @param length
* @return int
*/
int convertLengthToSteps(float length)
{
float result = length * 512 / (4 * 3.1415);
return int(result);
}
/**
* @brief Convertit une rotation en degrés vers un nombre de pas moteur.
*
* Exemple
* ```
* float angle = 45; //deg
* int steps = convertRotToSteps(angle);
* ```
*
* @param rotation Angle en degrés.
* @return int Nombres de pas pour les moteurs.
*/
int convertRotToSteps(int rotation)
{
int result = convertLengthToSteps(rotation * 3.1415 / 180 * 7.8);
return result;
}

147
server/src/server.hpp Normal file
View file

@ -0,0 +1,147 @@
/************************************
Configuration et handlers du server
************************************/
/**
* @brief Type de la variable globale command
*
*/
struct command_t
{
bool running; // Une commande doit être exécutée
bool stopped; // La commande doit être stoppée
String name; // Nom de la commande
int value; // Valeur (nombre de pas à effectuer)
};
/**
* @brief Met à jour la command globale.
* @internal
*
* @param commandName Nom de la nouvelle commande.
* @param commandValue Valeur de la nouvelle commande.
* @param globalCommand Commande globale (courante).
*/
void setGlobals(String commandName, float commandValue, command_t &globalCommand)
{
// Assert command before updating globals
if (commandName != "forward" && commandName != "backward" && commandName != "left" && commandName != "right")
{
return;
}
// Update globals
globalCommand.name = commandName;
globalCommand.running = true;
globalCommand.stopped = false;
globalCommand.value = convertLengthToSteps(commandValue);
}
/**
* @brief Lorsqu'une commande arrive au serveur, cette fonction permet.
* @internal
*
* @param commandName Nom de la commande.
* @param commandValue Valeur de la command (si 0 assigné à 474).
*/
void requestCheck(String commandName, float commandValue, command_t &globalCommand)
{
if (commandName == "stop")
{
globalCommand.name = "stop";
globalCommand.running = true;
globalCommand.stopped = true;
}
else
{
setGlobals(commandName, commandValue, globalCommand);
}
if (commandValue == 0)
{
globalCommand.value = 474;
}
}
/**
* @brief Parse la requête GET (vers "/get") du serveur et résout le nom de la commande et sa valeur.
*
* Exemple :
* ```
* String commandName;
* float commandValue;
* parseRequestParams(request, commandName, commandValue);
* ```
*
* @param request Requête contenant la commande.
* @param commandName Nom de la commande à assigner.
* @param commandValue Valeur de la commande à assigner.
* @param globalCommand Commande globale (courante) à mettre à jour.
*
*/
void parseRequestParams(AsyncWebServerRequest *request, String &commandName, float &commandValue, command_t &globalCommand)
{
// Stop here with error message if wrong command
if (!request->hasParam("command"))
{
commandName = "No command provided";
return;
}
// Update command from params
commandName = request->getParam("command")->value();
// Update value from params and use "0" as default
commandValue = request->hasParam("value") ? request->getParam("value")->value().toFloat() : 0;
requestCheck(commandName, commandValue, globalCommand);
}
/**
* @brief Configuration du serveur asynchrone.
*
* @param server Serveur à configurer.
* @param globalCommand Commande globale (courante) à mettre à jour lors des requêtes.
*/
void serverConfig(AsyncWebServer &server, command_t &globalCommand)
{
server.on("/get", HTTP_GET, [&globalCommand](AsyncWebServerRequest *request)
{
String commandName;
float commandValue;
// Parse request params and update command and value
parseRequestParams(request, commandName, commandValue, globalCommand);
Serial.print(commandName);
Serial.print(": ");
Serial.println(commandValue);
request->send(200, "text/plain", commandName); });
}
/**
* @brief Démarre le point d'accès WiFi.
*
* @param WiFi WiFi à configurer.
*/
void connectWiFi(WiFiClass &WiFi)
{
// For simulator only
WiFi.mode(WIFI_STA);
WiFi.begin(WIFI_SSID, WIFI_PASSWORD);
if (WiFi.waitForConnectResult() != WL_CONNECTED)
{
Serial.printf("WiFi Failed!\n");
return;
}
Serial.println(" Connected!");
Serial.print("IP Address: ");
Serial.println(WiFi.localIP());
// WiFi.mode(WIFI_AP);
// WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
// Serial.print("[+] AP Created with IP Gateway ");
// Serial.println(WiFi.softAPIP());
// Serial.println("");
}