chore(server): ✏️ fix typos in comments
This commit is contained in:
parent
a1d53fcd59
commit
b61220ecd2
|
@ -3,7 +3,7 @@
|
||||||
#include <ESPAsyncWebSrv.h>
|
#include <ESPAsyncWebSrv.h>
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
|
||||||
//Définition des ports pour controler les moteurs
|
// Définition des ports pour contrôler les moteurs
|
||||||
// Moteur gauche :
|
// Moteur gauche :
|
||||||
#define IN1a 27
|
#define IN1a 27
|
||||||
#define IN2a 14
|
#define IN2a 14
|
||||||
|
@ -23,17 +23,18 @@ const char* password = "test12345";
|
||||||
int delayTime = 3;
|
int delayTime = 3;
|
||||||
|
|
||||||
// Variables de commande :
|
// Variables de commande :
|
||||||
bool commandRunning = false; //Une commande doit etre éxécutée
|
bool commandRunning = false; // Une commande doit être exécutée
|
||||||
bool stopCommand = false; //La commande doit etre stoppée
|
bool stopCommand = false; // La commande doit être stoppée
|
||||||
String globalCommand; // Nom de la commande
|
String globalCommand; // Nom de la commande
|
||||||
int globalValue; // Valeur (nombre de pas à effectuer)
|
int globalValue; // Valeur (nombre de pas à effectuer)
|
||||||
|
|
||||||
// Création du serveur asynchrone :
|
// Création du serveur asynchrone :
|
||||||
AsyncWebServer server(80);
|
AsyncWebServer server(80);
|
||||||
|
|
||||||
//Code éxécuté au démarrage (paramétrage) :
|
// Code exécuté au démarrage (paramétrage) :
|
||||||
void setup() {
|
void setup()
|
||||||
//On indique que les ports de controle des moteurs sont des sorties (output)
|
{
|
||||||
|
// On indique que les ports de contrôle des moteurs sont des sorties (output)
|
||||||
pinMode(IN1a, OUTPUT);
|
pinMode(IN1a, OUTPUT);
|
||||||
pinMode(IN2a, OUTPUT);
|
pinMode(IN2a, OUTPUT);
|
||||||
pinMode(IN3a, OUTPUT);
|
pinMode(IN3a, OUTPUT);
|
||||||
|
@ -44,44 +45,50 @@ void setup() {
|
||||||
pinMode(IN3b, OUTPUT);
|
pinMode(IN3b, OUTPUT);
|
||||||
pinMode(IN4b, 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(); // Connexion au wifi
|
||||||
serverConfig(); // Configuration du serveur
|
serverConfig(); // Configuration du serveur
|
||||||
server.begin(); // Démarrage du serveur
|
server.begin(); // Démarrage du serveur
|
||||||
}
|
}
|
||||||
|
|
||||||
//Code éxécuté en boucle jusqu'à l'extinction du robot
|
// Code exécuté en boucle jusqu'à l'extinction du robot
|
||||||
void loop() {
|
void loop()
|
||||||
if (commandRunning){
|
{
|
||||||
if (!stopCommand){
|
if (commandRunning)
|
||||||
|
{
|
||||||
|
if (!stopCommand)
|
||||||
|
{
|
||||||
chooseCommand(); // Appeler la fonction "chooseCommand()"
|
chooseCommand(); // Appeler la fonction "chooseCommand()"
|
||||||
if (globalValue>0){ //S'il reste des pas à effectuer alors on l'affiche et on enlève un pas
|
if (globalValue > 0)
|
||||||
|
{ // S'il reste des pas à effectuer alors on l'affiche et on enlève un pas
|
||||||
Serial.print(globalCommand);
|
Serial.print(globalCommand);
|
||||||
Serial.print(": ");
|
Serial.print(": ");
|
||||||
Serial.println(globalValue);
|
Serial.println(globalValue);
|
||||||
globalValue--;
|
globalValue--;
|
||||||
}
|
}
|
||||||
else{ //Sinon on stoppe les moteurs
|
else
|
||||||
|
{ // Sinon on stoppe les moteurs
|
||||||
Serial.println("stop");
|
Serial.println("stop");
|
||||||
commandRunning = false;
|
commandRunning = false;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
stopMotors();
|
stopMotors();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else
|
||||||
|
{
|
||||||
Serial.println("stop");
|
Serial.println("stop");
|
||||||
commandRunning = false;
|
commandRunning = false;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
stopMotors();
|
stopMotors();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Configuration du serveur asynchrone
|
// Configuration du serveur asynchrone
|
||||||
void serverConfig(){
|
void serverConfig()
|
||||||
server.on("/get",HTTP_GET,[](AsyncWebServerRequest *request){
|
{
|
||||||
|
server.on("/get", HTTP_GET, [](AsyncWebServerRequest *request)
|
||||||
|
{
|
||||||
String command;
|
String command;
|
||||||
float value;
|
float value;
|
||||||
if (request->hasParam("command")) {
|
if (request->hasParam("command")) {
|
||||||
|
@ -100,59 +107,66 @@ void serverConfig(){
|
||||||
Serial.print(command);
|
Serial.print(command);
|
||||||
Serial.print(": ");
|
Serial.print(": ");
|
||||||
Serial.println(value);
|
Serial.println(value);
|
||||||
request->send(200, "text/plain", command);
|
request->send(200, "text/plain", command); });
|
||||||
});
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Fonction pour convertir une longueur en cm vers un nombre de pas moteur.
|
// Fonction pour convertir une longueur en cm vers un nombre de pas moteur.
|
||||||
int convertLengthToSteps(float length){
|
int convertLengthToSteps(float length)
|
||||||
|
{
|
||||||
float result = length * 512 / (4 * 3.1415);
|
float result = length * 512 / (4 * 3.1415);
|
||||||
return int(result);
|
return int(result);
|
||||||
}
|
}
|
||||||
|
|
||||||
// fonction pour convertir une rotation en degrés vers un nombre de pas moteur
|
// fonction pour convertir une rotation en degrés vers un nombre de pas moteur
|
||||||
int convertRotToSteps(int rotation){
|
int convertRotToSteps(int rotation)
|
||||||
|
{
|
||||||
int result = convertLengthToSteps(rotation * 3.1415 / 180 * 7.8);
|
int result = convertLengthToSteps(rotation * 3.1415 / 180 * 7.8);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Lorsqu'une commande arrive au serveur, cette fonction permet
|
// Lorsqu'une commande arrive au serveur, cette fonction permet
|
||||||
void requestCheck(String command, float value){
|
void requestCheck(String command, float value)
|
||||||
if (command=="forward"){
|
{
|
||||||
|
if (command == "forward")
|
||||||
|
{
|
||||||
globalCommand = "forward";
|
globalCommand = "forward";
|
||||||
commandRunning = true;
|
commandRunning = true;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
globalValue = convertLengthToSteps(value);
|
globalValue = convertLengthToSteps(value);
|
||||||
}
|
}
|
||||||
else if (command=="backward"){
|
else if (command == "backward")
|
||||||
|
{
|
||||||
globalCommand = "backward";
|
globalCommand = "backward";
|
||||||
commandRunning = true;
|
commandRunning = true;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
globalValue = convertLengthToSteps(value);
|
globalValue = convertLengthToSteps(value);
|
||||||
}
|
}
|
||||||
else if (command=="left"){
|
else if (command == "left")
|
||||||
|
{
|
||||||
globalCommand = "left";
|
globalCommand = "left";
|
||||||
commandRunning = true;
|
commandRunning = true;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
globalValue = convertRotToSteps(value);
|
globalValue = convertRotToSteps(value);
|
||||||
}
|
}
|
||||||
else if (command=="right"){
|
else if (command == "right")
|
||||||
|
{
|
||||||
globalCommand = "right";
|
globalCommand = "right";
|
||||||
commandRunning = true;
|
commandRunning = true;
|
||||||
stopCommand = false;
|
stopCommand = false;
|
||||||
globalValue = convertRotToSteps(value);
|
globalValue = convertRotToSteps(value);
|
||||||
}
|
}
|
||||||
else if (command=="stop"){
|
else if (command == "stop")
|
||||||
|
{
|
||||||
globalCommand = "stop";
|
globalCommand = "stop";
|
||||||
commandRunning = true;
|
commandRunning = true;
|
||||||
stopCommand = true;
|
stopCommand = true;
|
||||||
}
|
}
|
||||||
if (value==0){
|
if (value == 0)
|
||||||
|
{
|
||||||
globalValue = 474;
|
globalValue = 474;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void connectWiFi()
|
void connectWiFi()
|
||||||
{
|
{
|
||||||
WiFi.mode(WIFI_AP);
|
WiFi.mode(WIFI_AP);
|
||||||
|
@ -162,31 +176,28 @@ void connectWiFi()
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void chooseCommand()
|
||||||
|
{
|
||||||
|
if (globalCommand == "forward")
|
||||||
|
{
|
||||||
void chooseCommand(){
|
|
||||||
if (globalCommand=="forward"){
|
|
||||||
forward();
|
forward();
|
||||||
}
|
}
|
||||||
else if (globalCommand=="left"){
|
else if (globalCommand == "left")
|
||||||
|
{
|
||||||
left();
|
left();
|
||||||
}
|
}
|
||||||
else if (globalCommand=="right"){
|
else if (globalCommand == "right")
|
||||||
|
{
|
||||||
right();
|
right();
|
||||||
}
|
}
|
||||||
else if (globalCommand=="backward"){
|
else if (globalCommand == "backward")
|
||||||
|
{
|
||||||
backward();
|
backward();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void forward()
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
void forward(){
|
|
||||||
digitalWrite(IN4a, HIGH);
|
digitalWrite(IN4a, HIGH);
|
||||||
digitalWrite(IN3a, LOW);
|
digitalWrite(IN3a, LOW);
|
||||||
digitalWrite(IN2a, LOW);
|
digitalWrite(IN2a, LOW);
|
||||||
|
@ -225,7 +236,8 @@ void forward(){
|
||||||
delay(delayTime);
|
delay(delayTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void backward(){
|
void backward()
|
||||||
|
{
|
||||||
digitalWrite(IN4a, LOW);
|
digitalWrite(IN4a, LOW);
|
||||||
digitalWrite(IN3a, LOW);
|
digitalWrite(IN3a, LOW);
|
||||||
digitalWrite(IN2a, LOW);
|
digitalWrite(IN2a, LOW);
|
||||||
|
@ -264,7 +276,8 @@ void backward(){
|
||||||
delay(delayTime);
|
delay(delayTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void right(){
|
void right()
|
||||||
|
{
|
||||||
digitalWrite(IN4a, HIGH);
|
digitalWrite(IN4a, HIGH);
|
||||||
digitalWrite(IN3a, LOW);
|
digitalWrite(IN3a, LOW);
|
||||||
digitalWrite(IN2a, LOW);
|
digitalWrite(IN2a, LOW);
|
||||||
|
@ -303,7 +316,8 @@ void right(){
|
||||||
delay(delayTime);
|
delay(delayTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void left(){
|
void left()
|
||||||
|
{
|
||||||
digitalWrite(IN4a, LOW);
|
digitalWrite(IN4a, LOW);
|
||||||
digitalWrite(IN3a, LOW);
|
digitalWrite(IN3a, LOW);
|
||||||
digitalWrite(IN2a, LOW);
|
digitalWrite(IN2a, LOW);
|
||||||
|
@ -342,8 +356,8 @@ void left(){
|
||||||
delay(delayTime);
|
delay(delayTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void stopMotors(void)
|
||||||
void stopMotors(void) {
|
{
|
||||||
digitalWrite(IN4a, LOW);
|
digitalWrite(IN4a, LOW);
|
||||||
digitalWrite(IN3a, LOW);
|
digitalWrite(IN3a, LOW);
|
||||||
digitalWrite(IN2a, LOW);
|
digitalWrite(IN2a, LOW);
|
||||||
|
@ -354,4 +368,3 @@ void stopMotors(void) {
|
||||||
digitalWrite(IN2b, LOW);
|
digitalWrite(IN2b, LOW);
|
||||||
digitalWrite(IN1b, LOW);
|
digitalWrite(IN1b, LOW);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue