Transmettre à Arduino des coordonnées x,y à exploiter

Bonjour olpica

Voici la quittance des commandes avec OK, en plus tu as la trace du programme dans la fenêtre FB,


trace qui pourrait être réduite, une fois le programme au point.
Le programme de test FB:


'---------------------------------- Envoi de commandes arrêté
sub cmdAbort()
    PRINT
    PRINT "user abort"
    PRINT "COM closed"
    CLOSE #1

    sleep
end sub

'---------------------------------- Envois vers Arduino avec attente OK
function sendToArduino( byval toArduino as string) As boolean
    dim ackStr as string
    
    print chr$(9) & ">>>> Arduino: " & toArduino
    print #1, toArduino + chr$(10);

    DO
        LINE INPUT #1, ackStr
        
        if len(ackStr) > 1 then
            print ackStr ' Trace réception  
        end if
        
 '      if ackStr = "OK" then
       if instr(ackStr, "OK") > 0 then
            PRINT chr$(9) & "<<<< Arduino: OK"
            sendToArduino = true
            exit function
        end if

    LOOP UNTIL INKEY$ <> "" ' Pas de réception de OK
    cmdAbort
    
    sendToArduino = false
end function

'---------------------------------- Envoi de commandes X,Y
sub servoCmd( byval mpapXpos as integer, mpapYpos as integer )
    dim cmd as string : dim ackStr as string 
    dim cmdSucess as boolean

cmd = mpapXpos & "," & mpapYpos
    
    cmdSucess = sendToArduino(cmd)
end sub
    
'---------------------------------- Envoi de commandes de setup setupVal2 est optionnel
sub setupCmd( byval setup as string,  setupVal1 as integer,  setupVal2 as integer = 0)
    dim cmd as string : dim ackStr as string
    dim cmdSucess as boolean
    
    cmd = "$" & setup & setupval1
    cmd = cmd & "," & setupVal2
    
    cmdSucess = sendToArduino(cmd)
end sub

Open Com "COM5:9600,N,8,1,RS,DT,CS0,DS0,CD0" As #1 ' ouverture port com 1
sleep 3000
'-----------------------------------------------------------------------------
servoCmd(200,200)
servoCmd(400,0)
servoCmd(0,400)
servoCmd(200,200)
setupCmd ("HH", 0) ' Homing

Print "Programme fin OK"

close #1

Print "press ESC to exit"
while inkey() <> chr(27)
    sleep 20, 1
    wend

Le programme:

/*
	Name:       olpica_FreeBasicToMpap.ino
	Created:	04.08.2023
	Author:     jpbbricole/olpica
	https://forum.arduino.cc/t/transmettre-a-arduino-des-coordonnees-x-y-a-exploiter/1154805

	Transmission d'ordres depuis FreeBasic pour commander 2 servo à moteurs pas à pas
	 4.08.2023	Première ébauche. post #18
	15.08.2023	Première version complète. post #141
	19.08.2023	Ajout Warning Led (wled) et panic post #207
	24.08.2023	Ajout de la commande $LL Laser Localisation post #298
	28.08.2023	Ajout de la commande $LO pour LASER On/Off post #382
	30.08.2023	Ajout de la fonction wledCommande
	30.08.2023	Ajout de la commande $SB pour servo Break post #476
	08.09.2023	warningLed quand commande inconnue #506
	13.09.2023	Quittance des commandes avec OK #538

	Les commandes doivent se terminer avec, au minimun, un caractère Nouell Ligne (\n)
		code ASCII 10 ou 0A en hexadécimal.

	Les déplacements sont absolus : servoX.moveTo()
	Pour servoX à 250 et servoY à 720 la commande est une chaîne de caractrères contenant 250,720
	Pour ramener les servo à leur position de départ la commande est 0,0 ou 0 ou $HH
	Les valeurs peuvent être négatives -250,720
	Si le paramètre Y est manquant, comme une commande 250 ou 250, ça corespond à 250,0
*/

const String progrVersion = "$LL $LO WLED** $SB";

#include <EEPROM.h>     // Pour la sauvegarde des paramètres
#include <AccelStepper.h>     // https://www.arduino.cc/reference/en/libraries/accelstepper/
	// https://www.pjrc.com/teensy/td_libs_AccelStepper.html
	// DRV8825 https://www.pololu.com/product/2133
	// A4988 https://www.pololu.com/product/1182

#include <SoftwareSerial.h>

//------------------------------------- Serial de Free Basic (fb)
const int fbRxPin = A1;     // RX de FB, à raccorder sur TX du module FTDI CNC shield Hold
const int fbTxPin = A2; // TX de FB, à raccorder sur RX du module FTDI CNC shield Resume
SoftwareSerial fbSerial(fbRxPin, fbTxPin);     // Création de l'interface série de FB

/*
Moteur pas à pas (mpap)
CNC Shield brochage GRBL
https://blog.protoneer.co.nz/grbl-arduino-g-code-processor-pin-layout/
https://www.pololu.com/product/2133
https://blog.protoneer.co.nz/arduino-cnc-shield-v3-00-assembly-guide/
*/
const int mpapDriverType = 1;     //Stepper Driver, 2 driver pins required

const int mpapXdirPin = 5;     // Driver X DIR pin
const int mpapXstepPin = 2;     // Driver X STEP pin
const boolean mpapXdirReverse = false;      // S'il est nécessaire d'inverser le signal

const int mpapYdirPin = 6;     // Driver Y DIR pin
const int mpapYstepPin = 3;     // Driver Y STEP pin
const boolean mpapYdirReverse = false;      // S'il est nécessaire d'inverser le signal

const int mpapEnablePin = 8;     // Driver ENABLE pin, commun
const int mpapEnablePinEtatOn = LOW;     // Etat pour activer ENABLE pin

AccelStepper servoX(mpapDriverType, mpapXstepPin, mpapXdirPin);     // Création du MPAP X
AccelStepper servoY(mpapDriverType, mpapYstepPin, mpapYdirPin);

long servoPixelXpos = 0;     // Position servo X
long servoPixelYpos = 0;     // Position servo Y

const long servoXposDepart = 0;
const long servoYposDepart = 0;
boolean servoXisRunning = false;     // Si servo X n'est pas au but
boolean servoYisRunning = false;

//------------------------------------- LASER
const int laserPwmPin = 11;     // CNC Shield Limit Z+ ou Z-

const int laserOnPin = A3;     // Pour désactiver les servo CNC Shield CoolEn
const int laserOnEtatOn = LOW;     // Etat actif pour LASER On

//------------------------------------- Warning LED (wled)
const int wledPin = 12;     // CNC Shield SpnEn SpindleEnable
const int wledEtatOn = HIGH;     // Etat pour allumer la LED

//------------------------------------- Panic  au cas ou tout est planté
const int panicPin = A0;     // CNC Shield Abort Pour Factory au démarrage
const int panicEtatOn = LOW;     // Etat pour Panic ON

//------------------------------------- Mouvements (mouv) pour les états du programme
enum {mouvEtatArret, mouvEtatEnMarche, mouvEtatAuBut} mouvEtat = mouvEtatArret;     // Les divers états des mouvements

//------------------------------------- Contacts homing (chom) pour position 0
const int chomServoXpin = 9;     // CNC Shield Limit X+ ou X-
const int chomServoYpin = 10;     // CNC Shield Limit Y+ ou X-
const int chomEtatOn = LOW;     // Etat quand est home
const boolean homingIs = false;     // S'il y a homing

//------------------------------------- EEPROM
const int eePromOffset = 0;     // Position de départ

struct setupStructureDef
{
	float servosMaxSpeed;     // Vitesse maximum des servo
	float servosAcceleration;     // Accélération des servo des servo
	long servoStepsX;     // Servo nombre de pas X
	long servoStepsY;     // Servo nombre de pas X
	long pictPixeslY;     // Définition Y dse l'image
	long pictPixeslX;     // Définition X dse l'image
	int laserPwm;     // Puissance du LASER
	boolean homingOn;     // S'il y a homing
	boolean homingAuto;     // Si homing automatique au lancement du programme
	unsigned long homingWatchdog;     // Temps de surveillance du homing
	uint32_t checkKey;     // Pour contrôler si le setup a déjà été initialisée
};
setupStructureDef setupParams;
uint32_t setupCheckKey = 0xCAFEEFAC;     // Pour contrôler si l'EEPROM a déjà été initialisée

//------------------------------------- Commandes (cmd)
String cmdRx = "";       // Commande reçue du moniteur ou de Bluetooth
const String cmdSeperateur = ",";     // Séparation entre X et Y
boolean cmdRecue = false;     // Si une nouvele commande reçue du moniteur ou de Bluetooth

void setup()
{
	Serial.begin(9600);
	fbSerial.begin(9600);


	pinMode(wledPin, OUTPUT);     // LED warning
	digitalWrite(wledPin, !wledEtatOn);     // Eteindre la LED warning
	wledCommande(true, 0, 0);     // Allumer le LED de warning

	pinMode(panicPin, INPUT_PULLUP);     // Si ponté à GND, Factory
	if (digitalRead(panicPin) == panicEtatOn)     // Si procédure
	{
		setupCmd(F("$00"));     // Si panique, factory
	}

	setupRestore();
	if (setupParams.checkKey != setupCheckKey)     // Si premier démarrage
	{
		Serial.println("\n!!! Premier demarrage !!!");
		setupFactory();
		setupParams.checkKey = setupCheckKey;
		setupSave();
	}

	setupList();

	//                         DIR           STEP   ENA
	servoX.setPinsInverted(mpapXdirReverse, false, true);
	servoX.setEnablePin(mpapEnablePin);
	servoX.setMaxSpeed(setupParams.servosMaxSpeed);
	servoX.setAcceleration(setupParams.servosAcceleration);
	servoX.enableOutputs();     // Activer les signaux du MPAP

	servoX.setPinsInverted(mpapYdirReverse, false, true);
	servoX.setEnablePin(mpapEnablePin);
	servoY.setMaxSpeed(setupParams.servosMaxSpeed);
	servoY.setAcceleration(setupParams.servosAcceleration);
	servoY.enableOutputs();     // Activer les signaux du MPAP

	pinMode(chomServoXpin, INPUT_PULLUP);     // Contact homing servo X
	pinMode(chomServoYpin, INPUT_PULLUP);

	pinMode(laserPwmPin, OUTPUT);
	analogWrite(laserPwmPin, 0);     // LASER puisdsance 0
	pinMode(laserOnPin, OUTPUT);     // Commande relais LASER
	digitalWrite(laserOnPin, !laserOnEtatOn);     // LASERR OFF

	
	Serial.println("");
	setupCmd(F("$LL0,0"));     // LASER Localisation

	Serial.println(F("\nCommande de servo depuis Free Basic\n"));

	if (setupParams.homingAuto)
	{
		servoHomingXY();     // X et Y au départ
	}
	wledCommande(false, 0, 0);     // Eteindre le LED de warning

	Serial.print(F("\nSysteme pret ")); Serial.println(progrVersion);

	wledCommande(true, 1, 500);     // Eteindre le LED de warning
}

void loop()
{
	//--------------------------------- Lire les ports série
	serialEvent();     // https://www.arduino.cc/reference/en/language/functions/communication/serial/serialevent/
	fbSerialEvent();

	if (cmdRecue)
	{
		cmdTraitement(cmdRx);

		cmdRecue = false;
	}

	//--------------------------------- Où se trouvent les servo
	if (mouvEtat == mouvEtatEnMarche)
	{
		if ((servoX.distanceToGo() == 0) && (servoY.distanceToGo() == 0))     // Si X et Y à destination
		{
			mouvEtat = mouvEtatArret;
			fbAck();
		}
	}

	//--------------------------------- Fait tourner les servo si nécessaire
	servoX.run();
	servoY.run();
}

void servoPixelPositionner(long pixX, long pixY)
{
	long pixelStepsX = map(pixX, 0, setupParams.pictPixeslX, 0, setupParams.servoStepsX);     // Conversion pixels/pas moteur
	long pixelStepsY = map(pixY, 0, setupParams.pictPixeslY, 0, setupParams.servoStepsY);

	Serial.println("Pixels X = " + String(pixX) + " (" + String(pixelStepsX) + ")");
	Serial.println("\tPixels Y = " + String(pixY) + " (" + String(pixelStepsY) + ")");

	servoX.moveTo(pixelStepsX);
	servoY.moveTo(pixelStepsY);

	mouvEtat = mouvEtatEnMarche;
}

//------------------------------------- Positionnement Homing
void servoHomingXY()
{
	if (setupParams.homingOn)     // Si homing avec contacts
	{
		servoHoming(servoX, setupParams.servoStepsX, chomServoXpin);
		servoX.setMaxSpeed(setupParams.servosMaxSpeed);
		servoX.setCurrentPosition(0);

		servoHoming(servoY, setupParams.servoStepsY, chomServoYpin);
		servoY.setMaxSpeed(setupParams.servosMaxSpeed);
		servoY.setCurrentPosition(0);
	}
	else     // Retour position 0
	{
		servoX.moveTo(0);
		servoY.moveTo(0);
	}
}

void servoHoming(AccelStepper servo, long servoStepsMax, int contactHome)
{
	unsigned long homingWdMillis = millis();

	unsigned long runTempo = 50;
	unsigned long runMillis = millis();
	wledCommande(true, 0, 0);     // Allumer la LED warning

	servo.setMaxSpeed(setupParams.servosMaxSpeed / 1);     // Ralentir la vitesse de rotation

	if (digitalRead(contactHome) == chomEtatOn)     // Si déjà home
	{
		Serial.println(F("Quitter FDC > > >"));
		servo.runToNewPosition((servoStepsMax / 8));   // S'éloigner de home
	}

	Serial.println(F("Recherche FDC < < <"));
	servo.moveTo(-servoStepsMax);     // Reculer

	while (digitalRead(contactHome) != chomEtatOn)    // Tant que pas home
	{
		servo.run();

		if (millis() - runMillis >= runTempo)
		{
			wledCommande(!digitalRead(wledPin), 0, 0);
			runMillis = millis();
		}

		if (millis() - homingWdMillis >= setupParams.homingWatchdog)     // Si FDC pas trouvé
		{
			wledCommande(true, 0, 0);     // Allumer la LED warning
			Serial.println(F("\n!!! Fin de course PAS TROUVE\nREDEMARRER LE SYSTEME !!!"));
			setupParams.homingAuto = false;     // Désactiver homing automatique
			setupSave();
			while (1){}     // Tourne continuellement
		}
	}
	wledCommande(false, 0, 0);
	servo.stop();
}

void laserLocalise(int laserX, int laserY)
{
	Serial.println("LASER localise " + String(laserX) + "\t" + String(laserY));

	servoX.setCurrentPosition(map(laserX, 0, setupParams.pictPixeslX, 0, setupParams.servoStepsX));
	servoY.setCurrentPosition(map(laserY, 0, setupParams.pictPixeslY, 0, setupParams.servoStepsY));

	Serial.println("\tServo " + String(servoX.currentPosition()) + "\t" + String(servoY.currentPosition()));
}

void laserPulse(unsigned long pulseDuree)
{
	analogWrite(laserPwmPin, setupParams.laserPwm);
	delay(pulseDuree);
	analogWrite(laserPwmPin, 0);
}

//------------------------------------- Quittance FB
void fbAck()
{
	String ackCmd = "OK\r\n";
	delay(250);
	Serial.print(ackCmd);
	fbSerial.print(ackCmd);
}

//------------------------------------- Commande de la LED warning
void wledCommande(bool ledOn, int ledLoop, unsigned long ledTime)     // Commande de la LED de warning
{
	digitalWrite(wledPin, ledOn ? wledEtatOn : !wledEtatOn);     // Allumer ou éteindre selon ledOn

	if (ledLoop > 0)
	{
		for (int l = 0; l < (ledLoop *2); l ++)
		{
			delay(ledTime);
			digitalWrite(wledPin, !digitalRead(wledPin));     // Inverser la LED
		}
		digitalWrite(wledPin, !wledEtatOn);     // Eteindre
	}
}

/*
Traitement des commandes reçues de FB
Tourte commande qui ne débute pas par $ = positionnement des servo
Si commande = 0 ou 0m, ou 0,0 déclenche un homing de X et Y

Si la commande débute avec un $, c'est une commande de paramétrage void setupCmd.
*/
void cmdTraitement(String& cmdRx)
{
	Serial.println("\nCommande : " + cmdRx);
	cmdRx.toUpperCase();     // Tout en majuscules
	cmdRx.replace(" ", "");     // Supprimer les espaces

	if (cmdRx.length() >= 2)     // Si au moins 2 caratctères
	{
		if (cmdRx.startsWith("$"))
		{
			setupCmd(cmdRx);
			return;
		}

		cmdExtract2parameters(cmdRx, servoPixelXpos, servoPixelYpos);

		if (servoPixelXpos == 0 && servoPixelYpos == 0)     // Si homing
		{
			servoHomingXY();
			fbAck();
		}
		else
		{
			servoPixelPositionner(servoPixelXpos, servoPixelYpos);
		}
	}
	else
	{
		Serial.println("Commande > " + cmdRx + "< invalide!!!");
		wledCommande(true, 4, 50);     // Flasher la LED
	}
}

/*
Traitement des paramètrages reçus de FB

$SB		Servo X et Y break si 0 servo libre
$SV		Vitesse des servo X et Y
$SA		Accélération des servo X et Y
$SX		Définition servo X
$SY		Définition servo Y

$PX		Image pixels X
$PY		Image pixels Y

$LP		Laser Puissance (PWM)
$LI		Laser commande d'impulsion pendant millisecondes
$LL		Laser Localisation reçu de FB
$LO		Laser On/Off

$HH		Envoi des servo X et Y en position de départ 0,0
$HO		Si = 1 homong ON
$HA		Si = 1 homong Automatique au lancement du programme
$HW		Temps de surveillance de l'pération du homing

$$		Liste des paramètres
$00		Paramètres par défaut (factory) void setupFactory()

Les paramètres modifiés sont sauvés en EEPROM et leur effet est immédiat,
pas besoin de redémarrer.
Ces paramètres sont rapelés à chaque redémarrage.

Ces commandes ne sont pas sensibles à la casse.
*/
void setupCmd(String cmd)     // Commande setup, débutant avec $
{
	long setupParam1 = 0;
	long setupParam2 = 0;

	Serial.println("Setup : " + cmd);
	boolean setupChangeOk = true;

	cmdExtract2parameters(cmd.substring(3), setupParam1, setupParam2);     // Extraction des 2 paramètres, s'il y a

	if (cmd.startsWith(F("$SV")))     // Servos vitesse
	{
		setupParams.servosMaxSpeed = cmd.substring(3).toFloat();

		servoX.setMaxSpeed(setupParams.servosMaxSpeed);
		servoY.setMaxSpeed(setupParams.servosMaxSpeed);
	}
	else if (cmd.startsWith(F("$SA")))     // Servos Acceleration
	{
		setupParams.servosAcceleration = setupParam1;

		servoX.setAcceleration(setupParams.servosAcceleration);
		servoY.setAcceleration(setupParams.servosAcceleration);
	}
	else if (cmd.startsWith(F("$SB")))     // Seervo X et Y break
	{
		Serial.print("\tServo break ");
		if (setupParam1 == 1)     // Si X et X sous courant
		{
			servoX.enableOutputs();     // Activer les signaux du MPAP
			servoY.enableOutputs();
			Serial.println("ON");
			wledCommande(false, 0, 0);     // Allumer le LED de warning
		}
		else
		{
			servoX.disableOutputs();     // Desactiver les signaux du MPAP
			servoY.disableOutputs();
			Serial.println("OFF");
			wledCommande(true, 0, 0);     // Allumer le LED de warning
		}
	}
	else if (cmd.startsWith(F("$SX")))     // Seervo définition X
	{
		setupParams.servoStepsX = setupParam1;
	}
	else if (cmd.startsWith(F("$SY")))     // Seervo définition Y
	{
		setupParams.servoStepsY = setupParam1;
	}
	else if (cmd.startsWith(F("$LO")))     // LASER ON / OFF
	{
		digitalWrite(laserOnPin, (setupParam1 == 1) ? laserOnEtatOn : !laserOnEtatOn);     
	}
	else if (cmd.startsWith(F("$LP")))     // LASER Puissance (PWM)
	{
		setupParams.laserPwm = (int)setupParam1;
	}
	else if (cmd.startsWith(F("$LI")))     // LASER impulsion
	{
		laserPulse(setupParam1);
	}
	else if (cmd.startsWith(F("$LL")))     // Positionnement des servo en fonction de la position du LASER
	{
		laserLocalise(setupParam1, setupParam2);
	}
	else if (cmd.startsWith(F("$PX")))     // Image pixels X
	{
		setupParams.pictPixeslX = setupParam1;
	}
	else if (cmd.startsWith(F("$PY")))     // Image pixels Y
	{
		setupParams.pictPixeslY = setupParam1;
	}
	else if (cmd.startsWith(F("$HH")))     // X et Y home
	{
		servoHomingXY();
	}
	else if (cmd.startsWith(F("$HO")))     // S'il y a homing
	{
		setupParams.homingOn = setupParam1 == 1 ? true : false;
	}
	else if (cmd.startsWith(F("$HA")))     // S'il y a homing Automatique
	{
		setupParams.homingAuto = setupParam1 == 1 ? true : false;
	}
	else if (cmd.startsWith(F("$HW")))     // Homing watchdog
	{
		setupParams.homingWatchdog = setupParam1;
	}
	else if (cmd.startsWith(F("$$")))     // Paramètres liste
	{
		setupList();
	}
	else if (cmd.startsWith(F("$00")))     // Paramètres factory
	{
		unsigned long factTempo = 150;
		unsigned long factMillis = millis();

		setupParams.checkKey = setupCheckKey +1;
		setupSave();

		Serial.println(F("\n!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"));
		Serial.println(F("   LE PROGRAMME DOIT ETRE REDEMARRE"));
		Serial.println(F("!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"));

		wledCommande(true, 0, 0);

		while(1)
		{
			if (millis() - factMillis >= factTempo)
			{
				wledCommande(!digitalRead(wledPin), 0, 0);
				factMillis = millis();
			}
		}
		wledCommande(false, 0, 0);
	}
	else
	{
		Serial.print(F("Commande Setup inconnue!!! ")); Serial.println(cmd);
		setupChangeOk = false;     // Changement pas OK
		wledCommande(true, 4, 50);     // Flasher la LED
	}
	if (setupChangeOk)
	{
		setupSave();
	}
	
	fbAck();
}

void cmdExtract2parameters(String cmd, long& param1, long& param2)
{
	int sepPos = cmd.indexOf(cmdSeperateur);     // Position du séparateur de paramètres
	param1 = (long)cmd.substring(0,cmd.indexOf(cmdSeperateur)).toInt();     // Extraction de la position du servo X

	if (sepPos > 0)     // S'il y a eu un séparateur de paramètres
	{
		param2 = cmd.substring(sepPos +1).toInt();     // Extraction de la position du servo Y
	}
	else
	{
		param2 = 0;     // Si pas de scond paramètre, servoY = 0;
	}
}
//------------------------------------- Liste des aramètres
void setupList()
{
	Serial.println(F("\n > > > Parametres"));
	Serial.print(F("Servos vitesse\t$SV\t")) ; Serial.println(setupParams.servosMaxSpeed);
	Serial.print(F("Servos accel.\t$SA\t")) ; Serial.println(setupParams.servosAcceleration);
	Serial.print(F("Servo X max\t$SX\t")) ; Serial.println(setupParams.servoStepsX);
	Serial.print(F("Servo Y max\t$SY\t")) ; Serial.println(setupParams.servoStepsY);
	Serial.print(F("Bit mape X\t$PX\t")) ; Serial.println(setupParams.pictPixeslX);
	Serial.print(F("Bit mape Y\t$PY\t")) ; Serial.println(setupParams.pictPixeslY);
	Serial.print(F("LASER PWM\t$LP\t")) ; Serial.println(setupParams.laserPwm);
	Serial.print(F("Homing\t\t$HO\t")) ; Serial.println(setupParams.homingOn ? "ON" : "OFF");
	Serial.print(F("Homing Auto\t$HA\t")) ; Serial.println(setupParams.homingAuto ? "ON" : "OFF");
	Serial.print(F("Homing Watchdog\t$HW\t")) ; Serial.println(setupParams.homingWatchdog);
}

//------------------------------------- Paramètres usine
void setupFactory()
{
	Serial.println(F("\n > > > Parametres FACTORY !!!"));
	setupCmd(F("$SV2000"));     // Servos vitesse
	setupCmd(F("$SA4000"));     // Servos accélération
	setupCmd(F("$LP100"));     // LASER Puissance
	setupCmd(F("$SX6400"));     // Seervo X max (200 x microsteps 32 pour DRV8825) (200 x microsteps 16 pour A4988)
	setupCmd(F("$SY6400"));     // Seervo Y max
	setupCmd(F("$PX640"));     // Image pixels X
	setupCmd(F("$PY480"));     // Image pixels Y
	setupCmd(F("$HO0"));     // Si homing OFF
	setupCmd(F("$HA0"));     // Si homing Auto
	setupCmd(F("$HW5000"));     // Temps de surveillance du homing
}

//------------------------------------- EEPROM
void setupRestore()
{
	EEPROM.get(eePromOffset, setupParams);
}

void setupSave()
{
	EEPROM.put(eePromOffset, setupParams);
}

//------------------------------------- Communications
//------------------------------------- Ports série
void serialEvent()     // Serial
{
	if (Serial.available())
	{
		cmdRx = Serial.readStringUntil('\n');     // https://reference.arduino.cc/reference/fr/language/functions/communication/serial/readstringuntil
		cmdRx.trim();     // Pour nettoyer cmdRx  https://docs.arduino.cc/built-in-examples/strings/StringLengthTrim?

		cmdRecue = true;
	}
}

void fbSerialEvent()     // Free Basic
{
	if (fbSerial.available())
	{
		cmdRx = fbSerial.readStringUntil('\n');
		cmdRx.trim();     // Pour nettoyer cmdRx

		cmdRecue = true;
	}
}

Ca accélère pas mal l'exécution du programme, amuses toi bien :wink:

une toute belle journée à toi, ici fin des journée torrides!
jpbbricole