@@ -89,7 +89,6 @@ float voltage_NiMh = 0; // variable to store the value read
8989
9090int out;
9191int marche_avant = 1 ; // on initie la marche avant au début (0 étant la marche arriérer)
92- unsigned long marche_arriere_time = 0 ;
9392
9493unsigned long dernier_input = millis();
9594// direction millieu 1851
@@ -124,10 +123,8 @@ float getMeanSpeed(float dt){
124123
125124float getSpeed (float dt){
126125 int N = count - vieuxCount; // nombre de fronts montant et descendands après chaque loop
127- float V = ((float )N/(float )nb_trous)*distanceUnTour/(dt*1e-3 ); // 16 increments -> 1 tour de la roue et 1 tour de roue = 79 mm
128126 vieuxCount=count;
129- vieuxTemps=millis ();
130- return V;
127+ return ((float )N/(float )nb_trous)*distanceUnTour/(dt*1e-3 ); // 16 increments -> 1 tour de la roue et 1 tour de roue = 79 mm ;
131128}
132129
133130
@@ -180,6 +177,7 @@ void updateSpeed() {
180177 if (dt <= 0 ) dt = 0 .001f ;
181178
182179 vitesse = getMeanSpeed (now - vieuxTemps);
180+ vieuxTemps = now;
183181
184182 switch (driveState) {
185183
@@ -229,13 +227,14 @@ void updateSpeed() {
229227 case DRIVE_REV_ARM_3: // retour neutre
230228 moteur.writeMicroseconds (1500 );
231229 if (now - driveTimer >= 10 ) {
232- driveState = DRIVE_REVERSE; // 🔒 marche arrière ENGAGÉE
230+ driveState = DRIVE_REVERSE; // marche arrière ENGAGÉE
233231 }
234232 break ;
235233
236234 case DRIVE_REVERSE:
237- out = PID (-Vcons, vitesse, dt, out);
238- moteur.writeMicroseconds (constrain (1500 - out, 500 , 1500 ));
235+ float cons = abs (Vcons);
236+ out = PID (cons, vitesse, dt, out);
237+ moteur.writeMicroseconds (constrain (1430 - out, 500 , 1500 ));
239238
240239 if (Vcons == 0 ){
241240 moteur.writeMicroseconds (1500 );
@@ -248,13 +247,11 @@ void updateSpeed() {
248247 break ;
249248 }
250249
251- vieuxTemps = now;
250+
252251
253252
254253
255254 #if 0
256- Serial.print("temps en marche arriere: ");
257- Serial.print(millis()- marche_arriere_time);
258255 Serial.print(",integrale");
259256 Serial.print(integral);
260257 Serial.print(",const:");
@@ -283,9 +280,11 @@ void receiveEvent(int byteCount){
283280 buffer[i] = Wire.read ();
284281 }
285282
286- float * vals = (float *)buffer;
287- Vcons = vals[0 ]; // reçue en milimetre par secondes
288- dir_recue = vals[1 ]; // reçue en degré.
283+ float v, d;
284+ memcpy (&v, buffer, 4 );
285+ memcpy (&d, buffer + 4 , 4 );
286+ Vcons = v; // reçue en milimetre par secondes
287+ dir_recue = d; // reçue en degré.
289288 } else {
290289 while (Wire.available ()) Wire.read (); // vide le buffer
291290 }
@@ -338,6 +337,9 @@ void loop() {
338337 moteur.writeMicroseconds (1500 );
339338 dir = map (0 ,-dir_max,dir_max,dir_min_pwm,dir_max_pwm);
340339 direction.writeMicroseconds (dir);
340+ driveState = DRIVE_STOP;
341+ integral=0 ;
342+ out=0 ;
341343 }
342344}
343345
0 commit comments