@@ -47,13 +47,32 @@ volatile int vieuxCount=0; //stocke l'ancienne valeur de count pour ensuite fair
4747volatile byte state=LOW;
4848float mesures[3 ]; // tableau de mesures pour lisser
4949
50- // // I2C
50+ // I2C
5151union floatToBytes {
5252 byte valueBuffer[4 ];
5353 float valueReading;
5454 } converter;
5555
56- // //Voltage
56+ // struct pour la fréquence d'éxécution des fonctions
57+ struct Task {
58+ unsigned long period;
59+ unsigned long last;
60+ void (*run)();
61+ };
62+
63+ enum DriveState {
64+ DRIVE_STOP,
65+ DRIVE_FORWARD,
66+ DRIVE_REV_ARM_1, // neutre
67+ DRIVE_REV_ARM_2, // reverse fort
68+ DRIVE_REV_ARM_3, // retour neutre
69+ DRIVE_REVERSE
70+ };
71+
72+ DriveState driveState = DRIVE_STOP;
73+ unsigned long driveTimer = 0 ;
74+
75+ // Voltage
5776volatile bool dataReceived = false ;
5877volatile char receivedData[32 ]; // Buffer to hold received data
5978volatile int receivedLength = 0 ;
@@ -70,9 +89,9 @@ float voltage_NiMh = 0; // variable to store the value read
7089
7190int out;
7291int marche_avant = 1 ; // on initie la marche avant au début (0 étant la marche arriérer)
73- float marche_arriere_time = 0 ;
92+ unsigned long marche_arriere_time = 0 ;
7493
75- float dernier_input = millis();
94+ unsigned long dernier_input = millis();
7695// direction millieu 1851
7796// tout a gaucge 1231
7897// tout a droite 2471
@@ -113,42 +132,27 @@ float getSpeed(float dt){
113132
114133
115134void blink (){ // on compte tous les fronts
116- // Serial.print(count);
117135 count++;
118136}
119137
120138
121139float PID (float cons, float mes, float dt,float old_out) {
122140
123-
124141 if ( old_out <= 0 && cons > 0 ){ // pour pouvoir sauter directement dans la plage de pwm ou la roue bouge et une transition plus fluide entre marche arriere et avant
125142 integral = 2500 ; // valeur experimentale
126143 }
127144 else if (old_out >= 0 && cons <0 ){ // pour pouvoir sauter directement dans la plage de pwm où la roue bouge et une transition plus fluide entre marche avant et arriere
128145 integral = -5000 ; // valeur experimentale
129146 }
130147
131-
132- // Adjust the measured speed based on the sign of the desired speed
133- float adjustedMes = (cons < 0 ) ? -mes : mes;
134-
135- // Calculate the error
136- float e = cons - adjustedMes;
137-
138- // Proportional term
139- float P = Kp * e;
140-
141- // Integral term
142- integral = integral + e * dt;
143- float I = Ki * integral;
144-
145- // Derivative term
146- derivee = (e - vieuxEcart) / dt;
148+ float adjustedMes = (cons < 0 ) ? -mes : mes; // Adjust the measured speed based on the sign of the desired speed
149+ float e = cons - adjustedMes; // Calculate the error
150+ float P = Kp * e; // Proportional term
151+ integral = integral + e * dt; // Integral term
152+ float I = Ki * integral;
153+ derivee = (e - vieuxEcart) / dt; // Derivative term
147154 vieuxEcart = e;
148155 float D = Kd * derivee;
149-
150- // Garde en mémoir pour passer out à 0 directe lorsque l'on change de sens pour ne pas attendre qu'elle change de sens tout seul (que c'est long mdr
151-
152156 return P + I + D;
153157}
154158
@@ -164,112 +168,91 @@ void calculateVoltage(){
164168 // Serial.println(voltage_NiMh);
165169}
166170
167- /*
168- float direction_compensation(float dir_recue, float anciene_dir){
169- if (anciene_dir > )
170- }*/
171-
172- void programme_principal (){
173- calculateVoltage ();
174- // Commandes pour debugger
175- #if 0
176- command=Serial.read();
177- switch (command){ //pour regler les parametres
178- case 'a':
179- Vcons+=200;
180- break;
181- case 'z':
182- Vcons-=200;
183- break;
184- case 's':
185- Vcons=-1000;
186- break;
187- case 'd':
188- Vcons=2000;
189- break;
190- case 'q':
191- Vcons=0;
192- break;
193- case 'b':
194- dir+=10;
195- break;
196- case 'n':
197- dir-=100;
198- break;
199- case 'j':
200- dir+=10;
201- break;
202- case 'k':
203- dir-=10;
204- break;
205- }
206- #endif
207-
208-
209- // Propulsion de la voiture
210- int deltaT = millis ()-vieuxTemps; // temps qui est passé pendant un loop (en millisecondes)
211- vitesse=getMeanSpeed (deltaT); // on recup la vitesse lissée
212-
171+ void updateDirection (){
172+ // Update direction
173+ dir = map (dir_recue,-dir_max,dir_max,dir_min_pwm,dir_max_pwm); // remape en degré
174+ direction.writeMicroseconds (dir);
175+ }
213176
214- if (Vcons == 0 ){
215- out = 0 ;
216- moteur.writeMicroseconds (out+1500 );
217- /*
218- Serial.print("out:");
219- Serial.print(out);
220- */
221- marche_arriere_time = millis ();
177+ void updateSpeed () {
178+ unsigned long now = millis ();
179+ float dt = (now - vieuxTemps) * 0 .001f ;
180+ if (dt <= 0 ) dt = 0 .001f ;
181+
182+ vitesse = getMeanSpeed (now - vieuxTemps);
183+
184+ switch (driveState) {
185+
186+ case DRIVE_STOP:
187+ moteur.writeMicroseconds (1500 );
188+ integral = 0 ;
189+ out = 0 ;
190+
191+ if (Vcons > 0 ) {
192+ driveState = DRIVE_FORWARD;
193+ }
194+ else if (Vcons < 0 ) {
195+ driveState = DRIVE_REV_ARM_1;
196+ driveTimer = now;
197+ }
198+ break ;
199+
200+ case DRIVE_FORWARD:
201+ out = PID (Vcons, vitesse, dt, out);
202+ moteur.writeMicroseconds (constrain (1500 + out, 1500 , 2000 ));
203+
204+ if (Vcons == 0 ) {
205+ driveState = DRIVE_STOP;
206+ }
207+ else if (Vcons < 0 ) {
208+ driveState = DRIVE_REV_ARM_1;
209+ driveTimer = now;
210+ }
211+ break ;
212+
213+ case DRIVE_REV_ARM_1: // neutre court
214+ moteur.writeMicroseconds (1500 );
215+ if (now - driveTimer >= 10 ) {
216+ driveState = DRIVE_REV_ARM_2;
217+ driveTimer = now;
218+ }
219+ break ;
220+
221+ case DRIVE_REV_ARM_2: // reverse fort (armement ESC)
222+ moteur.writeMicroseconds (1000 );
223+ if (now - driveTimer >= 150 ) {
224+ driveState = DRIVE_REV_ARM_3;
225+ driveTimer = now;
226+ }
227+ break ;
228+
229+ case DRIVE_REV_ARM_3: // retour neutre
230+ moteur.writeMicroseconds (1500 );
231+ if (now - driveTimer >= 10 ) {
232+ driveState = DRIVE_REVERSE; // 🔒 marche arrière ENGAGÉE
233+ }
234+ break ;
235+
236+ case DRIVE_REVERSE:
237+ out = PID (-Vcons, vitesse, dt, out);
238+ moteur.writeMicroseconds (constrain (1500 - out, 500 , 1500 ));
239+
240+ if (Vcons == 0 ){
241+ moteur.writeMicroseconds (1500 );
242+ integral = 0 ;
243+ out = 0 ;
244+ }
245+ else if (Vcons > 0 ) {
246+ driveState = DRIVE_FORWARD;
247+ }
248+ break ;
222249 }
223- else if (Vcons>0 ){
224-
225- out = PID (Vcons,vitesse,float (deltaT)/1e3 ,out);
226- moteur.writeMicroseconds (constrain (1500 + out,1500 ,2000 ));
227- /*
228- Serial.print("out:");
229- Serial.print(constrain(1500 + out,500,2000));
230- */
231- marche_avant = 1 ; // on est en marche avant
232-
233- } else if ( Vcons<0 && old_Vcons>=0 && marche_avant == 1 ){ // on vériefie si il faut enclencher la marche arrière
234- out = PID (-8000 ,vitesse,float (deltaT)/1e3 ,out);
235- moteur.writeMicroseconds (constrain (1500 + out,500 ,1500 ));
236- delay (150 );
237- out = PID (0 ,vitesse,float (deltaT)/1e3 ,out);
238- moteur.writeMicroseconds (constrain (1500 + out,1500 ,2000 ));
239- delay (10 );
240- marche_avant = 0 ; // on est passée en marche arrière
241- marche_arriere_time = millis ();
242250
243- } else {
244- if (vitesse==0 && Vcons<0 && millis ()- marche_arriere_time > 500 ){ // vérifie si on est bien passée en marche arrière car bug parfois et si non on passe en marche arriere
245-
246-
247- out = PID (-8000 ,vitesse,float (deltaT)/1e3 ,out);
248- moteur.writeMicroseconds (constrain (1500 + out,500 ,1500 ));
249- delay (150 );
250- out = PID (0 ,vitesse,float (deltaT)/1e3 ,out);
251- moteur.writeMicroseconds (constrain (1500 + out,1500 ,2000 ));
252- delay (10 );
253- }
254-
255- out = PID (Vcons,vitesse,float (deltaT)/1e3 ,out);
256- moteur.writeMicroseconds (constrain (1500 + out,500 ,1500 ));
257- /*
258- Serial.print("out:");
259- Serial.print(constrain(1500 + out,500,2000));
260- */
261- }
262-
263- old_Vcons = Vcons;
251+ vieuxTemps = now;
264252
265253
266- // Direction de la voiture
267- dir = map (dir_recue,-dir_max,dir_max,dir_min_pwm,dir_max_pwm); // remape en degré
268- direction.writeMicroseconds (dir);
269-
270254
271- // print debug
272- #if 1
255+ #if 0
273256 Serial.print("temps en marche arriere: ");
274257 Serial.print(millis()- marche_arriere_time);
275258 Serial.print(",integrale");
@@ -282,16 +265,11 @@ void programme_principal(){
282265 Serial.print(vitesse);
283266 Serial.print(",Directino en degré:");
284267 Serial.print(dir_recue);
285- // Serial.print(", Ki : ");
286- // Serial.print(Ki);
287- // Serial.print(", Kp: ");
288- // Serial.print(Kp);
289- // Serial.print(", ");
290268 Serial.print(",out2:");
291269 Serial.println(out);
292270 #endif
293- delay (10 );
294271}
272+
295273void receiveEvent (int byteCount){
296274 // Ignorer le premier octet "commande" du Raspberry
297275 if (Wire.available ()) Wire.read (); // skip cmd byte
@@ -339,9 +317,22 @@ void setup() {
339317}
340318
341319
320+ Task tasks[] = {
321+ {5 , 0 , updateDirection}, // 200 Hz
322+ {20 , 0 , updateSpeed}, // 50 Hz
323+ {500 , 0 , calculateVoltage} // 2 Hz
324+ };
325+
342326void loop () {
343- if (millis ()-dernier_input < 150 ){ // on vérifie si on a recue une commande dans les 100 dernière millisecondes sinon on arrete
344- programme_principal ();
327+ unsigned long now = millis ();
328+
329+ if (now - dernier_input < 150 ){ // on vérifie si on a recue une commande dans les 100 dernière millisecondes sinon on arrete
330+ for (auto &t : tasks) {
331+ if (now - t.last >= t.period ) {
332+ t.last = now;
333+ t.run ();
334+ }
335+ }
345336 }
346337 else {
347338 moteur.writeMicroseconds (1500 );
0 commit comments