Compare commits

...

2 Commits

Author SHA1 Message Date
7f2af55e02 Code refactorisé - déplacements relatifs OK 2025-02-24 22:45:57 +01:00
9023ae64bc Déplacements relatifs fonctionnels 2025-02-22 16:27:32 +01:00
4 changed files with 113 additions and 239 deletions

View File

@ -1,14 +1,19 @@
#include <M5Core2.h> #include <M5Core2.h>
#include <Wire.h> #include <Wire.h>
#include <WiFi.h> #include <WiFi.h>
#include <WebServer.h>
#include <math.h> #include <math.h>
#include "Communication_chassis.h"
#include "ServerWeb.h"
#define WIRE Wire #define WIRE Wire
#define Rad_Deg 57.2957795130823 #define Rad_Deg 57.2957795130823
#define MOUVEMENT_FINI 0x4
#define MOUVEMENT_EN_COURS 0x2
#define gst_server; #define gst_server;
const char* ssid = "riombotique"; const char* ssid = "riombotique";
const char* password = "password"; const char* password = "password";
@ -21,10 +26,10 @@ IPAddress subnet(255, 255, 255, 0);
// IPAddress local_IP(192, 168, 1, 99); // IPAddress local_IP(192, 168, 1, 99);
// IPAddress gateway(192, 168, 1, 1); // IPAddress gateway(192, 168, 1, 1);
// IPAddress subnet(255, 255, 255, 0); // IPAddress subnet(255, 255, 255, 0);
WebServer server(80);
const int16_t I2C_MASTER = 0x42; const int16_t I2C_MASTER = 0x42;
const int16_t I2C_SLAVE_chassi = 0x55;
const int16_t I2C_SLAVE_trian = 0x30; const int16_t I2C_SLAVE_trian = 0x30;
uint8_t test = 32; uint8_t test = 32;
uint32_t i = 0; uint32_t i = 0;
@ -79,78 +84,6 @@ char* tableau[] = {"Lecture serveur", "Prise position", "Verif mvmt end ou cmd",
char* statu[] = {"/..","./.","../"}; char* statu[] = {"/..","./.","../"};
int index_statu=0; int index_statu=0;
struct chassis_reception_t {
char status;
};
struct chassis_emission_t {
char status;
int translation_x, translation_y, rotation_y;
};
#define FORM \
"<!DOCTYPE html>\n" \
"<html>\n" \
"<head>\n" \
"<meta charset=\"UTF-8\">\n" \
"<title>A simple form</title>\n" \
"</head>\n" \
"<body>\n" \
"<form action=\"/form\" method=\"post\">\n" \
"<br>" \
"<label for=\"X\">X : en mm</label>\n" \
"<br>" \
"<input type=\"text\" id=\"X\" name=\"X\">\n" \
"<br>" \
"<label for=\"Y\">Y : en mm</label>\n" \
"<br>" \
"<input type=\"text\" id=\"Y\" name=\"Y\">\n" \
"<br>" \
"<label for=\"R\">Rotation : en degres</label>\n" \
"<br>" \
"<input type=\"text\" id=\"R\" name=\"R\">\n" \
"<br>" \
"<label for=\"V\">Vitesse : </label>\n" \
"<br>" \
"<input type=\"text\" id=\"V\" name=\"V\" value=\"2000\">\n" \
"<br>" \
"<br>" \
"<label for=\"A\">Accel : </label>\n" \
"<br>" \
"<input type=\"text\" id=\"A\" name=\"A\"value=\"1500\">\n" \
"<br>" \
"<br>" \
"<input type=\"submit\" value=\" Vas-Y \">\n" \
"<br>" \
"<br>" \
"<input type=\"reset\" value=\"Reset\">\n" \
"<br>" \
"<br>" \
"<input type=\"submit\" value=\" STOP \">\n" \
"</form>\n" \
"</body>\n" \
"</html>\n"
void handleForm() {
String message;
message += FORM;
server.send(200, "text/html", message);
String myString0 = server.arg("X"); //positon de cmd en X mm
// x= myString0.toInt() * coef_mvt/10;
xA= myString0.toInt();
String myString1 = server.arg("Y"); //positon de cmd en Y mm
// y= myString1.toInt() * coef_mvt/10;
yA= myString1.toInt();
String myString2 = server.arg("R"); //positon de cmd en Rotation Deg °
rot= myString2.toInt() * 13.88888;
String myString3 = server.arg("V"); // Vitesse de cmd en
vit= myString3.toInt();
String myString4 = server.arg("A"); // Acceleration de cmd
acc= myString4.toInt();
}
void setup() { void setup() {
// put your setup code here, to run once: // put your setup code here, to run once:
@ -159,7 +92,7 @@ void setup() {
M5.Lcd.setTextSize(2); M5.Lcd.setTextSize(2);
M5.Lcd.print("Bonjour\nEcran\n\nRecherche Wifi"); M5.Lcd.print("Bonjour\nEcran\n\nRecherche Wifi");
Initialisation_wifi(); Initialisation_wifi();
server.on("/form", handleForm); Web_init();
WIRE.begin(); WIRE.begin();
M5.Lcd.clear(); M5.Lcd.clear();
@ -174,20 +107,8 @@ void setup() {
//} //}
// MemPosition_X = 800; // MemPosition_X = 800;
// MemPosition_Y = 800; // MemPosition_Y = 800;
M5.Lcd.clear(); affichage_standard_init();
M5.Lcd.setCursor(0, 0);M5.Lcd.print("Pos");M5.Lcd.setCursor(50, 0);M5.Lcd.print("X :");M5.Lcd.setCursor(150, 0);M5.Lcd.print("|Xp:");
M5.Lcd.setCursor(0, 20);M5.Lcd.print("n-1");
M5.Lcd.setCursor(50, 20);M5.Lcd.print("Y :");M5.Lcd.setCursor(150, 20);M5.Lcd.print("|Yp:");
M5.Lcd.setCursor(0, 40);M5.Lcd.print("Pos");
M5.Lcd.setCursor(50, 40);M5.Lcd.print("X :");
M5.Lcd.setCursor(0, 60);M5.Lcd.print("Act");
M5.Lcd.setCursor(50, 60);M5.Lcd.print("Y :");
M5.Lcd.setCursor(10, 80);M5.Lcd.print("Trans I2C");
M5.Lcd.setCursor(10, 100);M5.Lcd.print("Triangulation ");
M5.Lcd.setCursor(10, 120);M5.Lcd.print("AngleRad");
M5.Lcd.setCursor(10, 140);M5.Lcd.print("Tol x:");
M5.Lcd.setCursor(10, 160);M5.Lcd.print("Tol y:");
M5.Lcd.setCursor(10, 180);M5.Lcd.print("Case");
//M5.Lcd.setCursor(10, 200);M5.Lcd.print("cmd :"); //M5.Lcd.setCursor(10, 200);M5.Lcd.print("cmd :");
} }
@ -197,31 +118,9 @@ void loop() {
static int64_t time; static int64_t time;
struct chassis_reception_t chassis_reception; struct chassis_reception_t chassis_reception;
Serial.println("Scan_chassis"); strategie();
affichage_resultats();
erreur = Scan_Chassi(&chassis_reception); delay(10);
Serial.println("fin Scan_chassis");
// Si le chassis est disponible
// Attente 1 seconde avant d'envoyer un messa
Serial.println("if 0x04");
if(chassis_reception.status == 0x04 && wait == 0){
time = esp_timer_get_time();
wait = 1;
}
Serial.println("wait 1s");
if(wait == 1 && esp_timer_get_time() > time + 1000000){
Serial.println("send_Chassis");
send_Chassis();
wait = 0;
}
//strategie();
//affichage_resultats();
//delay(500);
} }
void affichage_resultats() { void affichage_resultats() {
@ -256,7 +155,7 @@ void Initialisation_wifi(){
if (test_wifi > 10) break; if (test_wifi > 10) break;
} }
if (WiFi.status() == WL_CONNECTED) { if (WiFi.status() == WL_CONNECTED) {
server.begin();
Serial.println("Server started"); Serial.println("Server started");
delay(500); delay(500);
M5.Lcd.clear(); M5.Lcd.clear();
@ -273,7 +172,6 @@ void Initialisation_wifi(){
while(1); while(1);
} }
IPAddress myIP = WiFi.softAPIP(); IPAddress myIP = WiFi.softAPIP();
server.begin();
M5.Lcd.clear(); M5.Lcd.clear();
M5.Lcd.setCursor(10,10); M5.Lcd.setCursor(10,10);
M5.Lcd.print("Creation Hotspot ;-)"); M5.Lcd.print("Creation Hotspot ;-)");
@ -285,6 +183,23 @@ void Initialisation_wifi(){
delay(1500); delay(1500);
} }
void affichage_standard_init(){
M5.Lcd.clear();
M5.Lcd.setCursor(0, 0);M5.Lcd.print("Pos");M5.Lcd.setCursor(50, 0);M5.Lcd.print("X :");M5.Lcd.setCursor(150, 0);M5.Lcd.print("|Xp:");
M5.Lcd.setCursor(0, 20);M5.Lcd.print("n-1");
M5.Lcd.setCursor(50, 20);M5.Lcd.print("Y :");M5.Lcd.setCursor(150, 20);M5.Lcd.print("|Yp:");
M5.Lcd.setCursor(0, 40);M5.Lcd.print("Pos");
M5.Lcd.setCursor(50, 40);M5.Lcd.print("X :");
M5.Lcd.setCursor(0, 60);M5.Lcd.print("Act");
M5.Lcd.setCursor(50, 60);M5.Lcd.print("Y :");
M5.Lcd.setCursor(10, 80);M5.Lcd.print("Trans I2C");
M5.Lcd.setCursor(10, 100);M5.Lcd.print("Triangulation ");
M5.Lcd.setCursor(10, 120);M5.Lcd.print("AngleRad");
M5.Lcd.setCursor(10, 140);M5.Lcd.print("Tol x:");
M5.Lcd.setCursor(10, 160);M5.Lcd.print("Tol y:");
M5.Lcd.setCursor(10, 180);M5.Lcd.print("Case");
}
void affiche_erreur(char * chaine1, char * chaine2){ void affiche_erreur(char * chaine1, char * chaine2){
M5.Lcd.clear(); M5.Lcd.clear();
M5.Lcd.setCursor(10,10); M5.Lcd.setCursor(10,10);
@ -309,10 +224,19 @@ void affiche_msg(char * chaine1, char * chaine2){
void strategie(){ void strategie(){
struct chassis_reception_t chassis_reception; struct chassis_reception_t chassis_reception;
struct chassis_emission_t chassis_emission;
switch(index_Maitre){ switch(index_Maitre){
case 0 : //--------------------------------------------------------------------------------------------------------- case 0 : //---------------------------------------------------------------------------------------------------------
server.handleClient(); //************* Lecture des données recu pour coordoné (X,Y,rotation) /// Lecture des commandes venant du serveur web et envoi des commandes au chassis
if(vit!=0 && !corrige){ Web_gestion();
M5.update();
/// Si on a une réponse du client
/// On lit la réponse
if(Web_nouveau_message()){
if(Web_type_requete() == WEB_DEPLACEMENT_RELATIF){
chassis_emission = Web_get_donnees();
send_Chassis(&chassis_emission);
}
Serial.printf("vit:%d, corrige: %d\n", vit, corrige); Serial.printf("vit:%d, corrige: %d\n", vit, corrige);
MemCmd_X = xA; //Memorisation de la comande pour comparaison avec arrivé MemCmd_X = xA; //Memorisation de la comande pour comparaison avec arrivé
MemCmd_Y = yA; MemCmd_Y = yA;
@ -320,6 +244,41 @@ void strategie(){
//index_Maitre = 1; // Bloc le serveur WEB si on n'a pas la triangulation //index_Maitre = 1; // Bloc le serveur WEB si on n'a pas la triangulation
index_Maitre = 2; index_Maitre = 2;
} }
if(M5.BtnA.read() == 1){
// Déplacement en X
chassis_emission.translation_x_mm = 2000;
chassis_emission.translation_y_mm = 0;
chassis_emission.rotation_z_rad = 0;
chassis_emission.vitesse = 2000;
chassis_emission.acceleration = 1500;
send_Chassis(&chassis_emission);
index_Maitre = 2;
}
if(M5.BtnB.read() == 1){
// Déplacement en Y
chassis_emission.translation_x_mm = 0;
chassis_emission.translation_y_mm = 2000;
chassis_emission.rotation_z_rad = 0;
chassis_emission.vitesse = 2000;
chassis_emission.acceleration = 1500;
send_Chassis(&chassis_emission);
index_Maitre = 2;
}
if(M5.BtnC.read() == 1){
// Rotation
chassis_emission.translation_x_mm = 0;
chassis_emission.translation_y_mm = 0;
chassis_emission.rotation_z_rad = 100;
chassis_emission.vitesse = 2000;
chassis_emission.acceleration = 1500;
send_Chassis(&chassis_emission);
index_Maitre = 2;
}
break; break;
case 1 : //--------------------------------------------------------------------------------------------------------- case 1 : //---------------------------------------------------------------------------------------------------------
@ -334,30 +293,24 @@ void strategie(){
//Si position Pas OK ****************** //Si position Pas OK ******************
break; break;
case 2 : //--------------------------------------------------------------------------------------------------------- case 2 : // Deplacement relatif en cours
Scan_Chassi(&chassis_reception); //Verif de la fin de mouvement remonté par le chassis Scan_chassis(&chassis_reception); //Verif de la fin de mouvement remonté par le chassis
// Pour l'instant, Scan_chassis bloque le programme en cas de problème de communication
if(Err_Chassi_com !=0){ if(Err_Chassi_com !=0){
affiche_erreur("case 2", "Err_Chassi_com !=0");
for(int j=0; j<10; j++){ for(int j=0; j<10; j++){
affichage_resultats(); affichage_resultats();
Scan_Chassi(&chassis_reception); Scan_chassis(&chassis_reception);
//delay(500); //delay(500);
} }
// ********************************* ERREUR DE COM FATAL *********************** // ********************************* ERREUR DE COM FATAL ***********************
} }
if(Mvt_finit==0){ if(chassis_reception.status != MOUVEMENT_FINI){
send_Chassis(); //Envoie des coordonées à atteindre
while(Mvt_finit!=1){
Scan_Chassi(&chassis_reception); //Verif de la fin de mouvement remonté par le chassis (time out ?**********)
delay(50);
}
Scan_Chassi(&chassis_reception); //Verif de la fin de mouvement remonté par le chassis (time out ?**********)
}else{ }else{
send_Chassis_RAZ(); //Envoie des coordonées à atteindre send_Chassis_RAZ(); // Immobilisation du robot
index_Maitre = 0; // On attend l'ordre suivant
} }
//M5.Lcd.clear();
index_Maitre = 0;
break; break;
} }
} }
@ -404,31 +357,6 @@ void compar_cinematique(){
} }
} }
/// @brief Lit l'état du chassis en I2C
/// @return renvoi 0 si tout s'est bien passé, un code d'erreur sinon
int Scan_Chassi(struct chassis_reception_t * chassis_reception){
unsigned char tampon2[10];
//(Adresse I2c, Adresse dans le registre, tampon, longueur de donnée)
//Serial.println("avant lire registre");
error = I2C_lire_registre(I2C_SLAVE_chassi, 0, tampon2, 8);
if (error !=0){
Err_Chassi_com =1;IndexErr = 2;
affiche_erreur("Scan_Chassi", "Erreur I2C");
while(1);
}else{
Err_Chassi_com =0;
IndexErr = 0;
int valeur;
Mvt_finit = (0x04 == tampon2[0] & 0x04);
char chaine[32];
sprintf(chaine, "tampon2: %x %x %x %x %x %x %x %x\n", tampon2[0], tampon2[1], tampon2[2], tampon2[3], tampon2[4],
tampon2[5], tampon2[6], tampon2[7]);
affiche_msg("Scan_Chassi", chaine);
chassis_reception->status = tampon2[0];
}
return 0;
}
/// @brief Récupère position (X, Y) et l'orientation du robot /// @brief Récupère position (X, Y) et l'orientation du robot
void Scan_Triangulation(){ void Scan_Triangulation(){
@ -459,38 +387,7 @@ void Scan_Triangulation(){
} }
} }
void send_Chassis_RAZ(){
uint8_t RAZ_Message[11]={0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
error = I2C_ecrire_registre(I2C_SLAVE_chassi, 0, RAZ_Message, 11);
}
void send_Chassis(){
//if(nbr_essai<=10){
Cmd_Angle = MemCmd_A;
// Prévient le chassis d'un nouveau mouvement avec le 2eme bit du premier Octet
Mot[0] = 2;
//y*=-1;
//y = y*direction;
Mot[1] = cmd_chassi_x >>8; Mot[2] = cmd_chassi_x;
Mot[3] = cmd_chassi_y >>8; Mot[4] = cmd_chassi_y;
//Serial.println(y);
Mot[5] = Cmd_Angle >>8; Mot[6] = Cmd_Angle;
Mot[7] = vit >>8; Mot[8] = vit;
Mot[9] = acc >>8; Mot[10] = acc;
error = I2C_ecrire_registre(I2C_SLAVE_chassi, 0, Mot, 11);
if (error !=0){Err_Cha_send =1; IndexErr = 5;}
else{Err_Cha_send =0;IndexErr = 0;}
if(error==0){ //si pas d'erreur de transmission alors RAZ des valeurs
nbr_essai ++;
cmd_chassi_x = 0;
cmd_chassi_y = 0;
Cmd_Angle = 0;
vit = 0;
acc = 0;
}
}
void scan_I2C_bus(){ void scan_I2C_bus(){
char error, address; char error, address;

View File

@ -17,7 +17,7 @@
#define serialP; #define serialP;
#define gst_I2C; #define gst_I2C;
byte * I2C_memory; volatile byte * I2C_memory;
//********************************************************************* //*********************************************************************
//******************** Integration et config Moteur ******************* //******************** Integration et config Moteur *******************
@ -52,9 +52,9 @@ int com[] = {0, 0, 0};
// -------------- Direction des moteurs ( pour un sens de marche commun ) // -------------- Direction des moteurs ( pour un sens de marche commun )
int dirX= +1; int dirX= +1;
int dirY= -1; int dirY= +1;
int dirZ= +1; int dirZ= +1;
int dirA= -1; int dirA= +1;
int cli_led=0; // initial value of input int cli_led=0; // initial value of input
int Move = 0; int Move = 0;
@ -84,17 +84,10 @@ int h=0;
void setup() void setup()
{ {
pinMode(Men,OUTPUT); pinMode(Men,OUTPUT);
digitalWrite(Men, LOW);// Low Level Enable stop();
#ifdef serialP #ifdef serialP
Serial.begin(115200); Serial.begin(115200);
#endif #endif
pinMode(LED_BUILTIN, OUTPUT);
for(int i=0; i<6;i++){
digitalWrite(LED_BUILTIN, LOW);
delay(150);
digitalWrite(LED_BUILTIN, HIGH);
delay(150);
}
// X // X
stepperX.setMaxSpeed(vitesse); stepperX.setAcceleration(accel); stepperX.setMaxSpeed(vitesse); stepperX.setAcceleration(accel);
@ -109,18 +102,17 @@ void setup()
//Serial.println(Men); //Serial.println(Men);
I2C_Slave_init(0x55); I2C_Slave_init(0x55);
I2C_memory = get_i2c_data(); I2C_memory = get_i2c_data();
I2C_memory[0] = 0x1;
I2C_memory[1] = 0x2;
I2C_memory[2] = 0x3;
I2C_memory[3] = 0x4;
I2C_memory[4] = 0x5;
I2C_memory[5] = 0x6;
I2C_memory[6] = 0x7;
I2C_memory[7] = 0x8;
//digitalWrite(Men, LOW);// Low Level Enable //digitalWrite(Men, LOW);// Low Level Enable
pinMode(pul1, OUTPUT);
pinMode(pul2, OUTPUT);
pinMode(pul3, OUTPUT);
pinMode(pul4, OUTPUT); pinMode(pul4, OUTPUT);
pinMode(dir1, OUTPUT);
pinMode(dir2, OUTPUT);
pinMode(dir3, OUTPUT);
pinMode(dir4, OUTPUT);
} }
@ -135,17 +127,6 @@ void loop()
} }
Serial.printf("\n"); Serial.printf("\n");
// Reset octet 0 à 0 au bout d'une seconede
if(I2C_memory[0] !=0 && wait == 0){
time = esp_timer_get_time();
wait = 1;
}
if(esp_timer_get_time() > time + 1000000 && wait == 1){
I2C_memory[0] = 0x4;
wait = 0;
}
/*
if(((I2C_memory[0] & 0x02)==2) && Modif_Mvt==0){ if(((I2C_memory[0] & 0x02)==2) && Modif_Mvt==0){
Modif_Mvt = 1; Modif_Mvt = 1;
@ -162,6 +143,7 @@ void loop()
} }
Position_Calculation(); //************* Calcul du Vecteur XY (incrémental) Position_Calculation(); //************* Calcul du Vecteur XY (incrémental)
Mvmt(); //************* Envoie de la position à ateindre pour chaque moteur + Execution du mouvement Mvmt(); //************* Envoie de la position à ateindre pour chaque moteur + Execution du mouvement
stop(); // Servo Off
I2C_memory[0] = 0x04; I2C_memory[0] = 0x04;
I2C_envoi_8bits(I2C_memory[0] ,0); I2C_envoi_8bits(I2C_memory[0] ,0);
@ -180,17 +162,17 @@ void loop()
} }
//Dé-asservissement des moteurs //Dé-asservissement des moteurs
stop(); // Servo Off
*/
} }
void Position_Calculation(){ void Position_Calculation(){
PosX = Target[0]; PosX = Target[0];
AxeX[0] = {PosX}; //x AxeX[0] = {PosX}; //x
AxeX[1] = {-PosX}; //y AxeX[1] = {PosX}; //y
AxeX[2] = {-PosX}; //z AxeX[2] = {-PosX}; //z
AxeX[3] = {PosX}; //a AxeX[3] = {-PosX}; //a
PosY = Target[1]; PosY = Target[1];
AxeY[0] = {PosY}; //x AxeY[0] = {PosY}; //x
AxeY[1] = {PosY}; //y AxeY[1] = {PosY}; //y
@ -199,8 +181,8 @@ void Position_Calculation(){
Rot = Target[2]; Rot = Target[2];
AxeRot[0] = {-Rot}; //x AxeRot[0] = {-Rot}; //x
AxeRot[1] = {Rot}; //y AxeRot[1] = {Rot}; //y
AxeRot[2] = {-Rot}; //z AxeRot[2] = {Rot}; //z
AxeRot[3] = {Rot}; //a AxeRot[3] = {-Rot}; //a
vitesse = Target[3]; vitesse = Target[3];
accel = Target[4]; accel = Target[4];
@ -261,14 +243,8 @@ void Mvmt(){
// Serial.print(stepperX.distanceToGo());Serial.print("/");Serial.print(stepperY.distanceToGo());Serial.print("/");Serial.print(stepperZ.distanceToGo());Serial.print("/");Serial.print(stepperA.distanceToGo());Serial.print("\t");Serial.print(Interrupt);Serial.print("\t");Serial.println(Modif_Mvt); // Serial.print(stepperX.distanceToGo());Serial.print("/");Serial.print(stepperY.distanceToGo());Serial.print("/");Serial.print(stepperZ.distanceToGo());Serial.print("/");Serial.print(stepperA.distanceToGo());Serial.print("\t");Serial.print(Interrupt);Serial.print("\t");Serial.println(Modif_Mvt);
// delay(100); // delay(100);
#endif #endif
if(esp_timer_get_time() > time + 100000){
time = esp_timer_get_time();
digitalWrite(LED_BUILTIN, cli_led);
cli_led = !cli_led;
}
} }
} }
digitalWrite(LED_BUILTIN, HIGH);
// if(Modif_Mvt == 1){ // if(Modif_Mvt == 1){
// Position_Calculation(); // Position_Calculation();
// Serial.println("\t\tRe Calculation !!!"); // Serial.println("\t\tRe Calculation !!!");

View File

@ -20,7 +20,6 @@ void onRequest(){
} }
void onReceive(int len){ void onReceive(int len){
digitalWrite(LED_BUILTIN, LOW);
memoire_I2C_index = Wire.read(); memoire_I2C_index = Wire.read();
while(Wire.available()){ while(Wire.available()){
nouveau_message=true; nouveau_message=true;

View File

@ -1,10 +1,12 @@
Test de la liaison I2C entre le châssis et le cerveau Déplacement fonctionnel
===================================================== =======================
Ce code permet de tester la communication I2C entre le châssis et le cerveau. Le cerveau demande 8 octet au châssis. Côté cerveau, un serveur web qui permet d'envoyer un ordre de déplacement relatif au châssis.
Si l'octet 0 vaut 4, au bout d'une seconde, le cerveau envoi une trame pour réinitialise l'octet à 2.
Le châssis scrute l'octet 0 et si celui-ci vaut 2, il attend une seconde puis le passe à 1. Calibration des sens des moteurs pour les translations en X, Y et pour la rotation.
Calibration des translations non effectuées.
Le châssis envoie l'état de sa mémoire par la liaison USB. Vidéo réalisée le 24 février 2024, paramètres :
Le cerveau affiche l'état de sa mémoire sur l'écran. - vitesse : 2000
- acceleration : 1500