





Alimentation par block batteries 2 x Li-ion en série.
Les 7,4V sont admis par le chaine de puissance (MotorShield) pour l'alimentation des moteurs.
La carte Arduino est en charge de convertir en 5V et 3,3V pour la chaine d'information. Ce qui nous pose des problèmes pour l'alimentation de la pince.
Initialement prévue pour avoir 4 roues motrice, la plateforme sera finalement une plateforme 2 roues motrices à l'avant.
La bibliothèque AFmotor permet de gérer la MotorShield V1 AFmotor.h adafruit_motor_shield_library-1.0.1.zip
Utilisation d'un module PS2X
Partage du BUS I2C Caméra et Lidar
. ____ ___ ____ ____ .
/ ___| ___ __ _ _ __ |_ _| |___ \ / ___|
\___ \ / __| / _` | | '_ \ | | __) | | |
___) | | (__ | (_| | | | | | | | / __/ | |___
|____/ \___| \__,_| |_| |_| |___| |_____| \____|
Debut du scan
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... 0x29 .... .... .... .... .... ....
.... .... 0x32 .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
.... .... .... .... .... .... .... ....
Fin du Scan
2 peripheriques reconnus.
Appuyez sur le bouton Reset de l'Arduino pour recommencer.
0x29: VL53L0X
0x32: HuskyLens
Démarrage très capricieux de la caméra HuskyLens en mode I2C en raison de l'adaptation des niveaux électriques 3,3V (Huskylens) et 5V (Arduino). Une utilisation en mode serial sera à privilégier.
La solution caméra HuskyLens en I2C ne sera pas retenue.
Une structure logicielle permettant l'intégration rapide des codes des différentes équipes. Mais interdisant l'utilisation de la fonction Delay() ainsi que des fonctions bloquantes.
#define _MOTION_STOP_ 0
#define _MOTION_FORWARD_ 1
#define _MOTION_BACKWARD_ 2
#define _MOTION_GOLEFT_ 3
#define _MOTION_GORIGHT_ 4
#define _MOTION_TURNLEFT_ 5
#define _MOTION_TURNRIGHT_ 6
#define _Phase_LookingForCube_ 0
#define _Phase_LocatingCube_ 1
#define _Phase_ApprocheCube_ 2
#define _Phase_GetCube_ 3
#define _Phase_MoveCube_ 4
bool MOTION_TURBO = false;
bool NIPPER_ON = false;
int MotionMove = _MOTION_STOP_;
bool MotionModeAuto = false;
int RemotePadX = 0;
int RemotePadY = 0;
bool cubeDetected = false;
bool cubeCentered = false;
bool cubeOnLeft = false;
bool cubeOnRight = false;
bool cubeLocked = false;
bool cubeNear = false;
String RemoteKey = "None";
int16_t Camera_xCenter = -1;
int16_t Camera_yCenter = -1;
int16_t Camera_width = -1;
int16_t Camera_height = -1;
int16_t Camera_xOrigin = -1;
int16_t Camera_yOrigin = -1;
int16_t Camera_xTarget = -1;
int16_t Camera_yTarget = -1;
// int Camera_currentID = -1;
int16_t Camera_ID = -1;
float VL53L0X_distance = -1;
int currentPhase = _Phase_LocatingCube_;
int Loopcentered = 0;
#include "Wire.h"
#include "remote.h"
#include "motion.h"
#include "camera.h"
#include "distance.h"
#include "nippers.h"
#include "console.h"
bool RemoteModeAuto = false;
int CameraDetection = -1;
bool Searching = true;
bool CarryBack = false;
void setup() {
Serial.begin(115200);
Wire.begin();
Wire.setClock(100000);
setupConsole();
setupRemote();
setupMotion();
setupDistance();
setupCamera();
setupNippers();
currentPhase = _Phase_LocatingCube_;
}
void loop() {
loopRemote();
loopCamera();
loopDistance();
Serial.println(String()
+F("RemoteAuto=")+RemoteModeAuto
+F("\t MotionModeAuto=")+MotionModeAuto
+F("\t CurrentPhase=")+currentPhase
+F("\t MotionMove=")+MotionMove
+F("\t MOTION_TURBO=")+MOTION_TURBO
+F("\t xCenter=")+Camera_xCenter
+F("\t yCenter=")+Camera_yCenter
+F("\t width=")+Camera_width
+F("\t height=")+Camera_height
+F("\t ID=")+Camera_ID
+F("\t distance=")+VL53L0X_distance
+F("\t nearCube=")+cubeNear
+F("\t pince=")+NIPPER_ON
+F("\t RemoteKey=")+RemoteKey
);
if (MotionModeAuto || cubeNear || NIPPER_ON ) {
data[0] = display.encodeDigit(currentPhase);
data[1] = 0x40;
data[2] = 0x40;
data[3] = 0x40;
if(Camera_ID != -1 || cubeNear) {
// Serial.print("*** LOOKING FOR CUBE *** ");
switch(currentPhase) {
case _Phase_LookingForCube_: // 0
Serial.print(" --> OBJECT DETECTED BY CAM ");
currentPhase = _Phase_LocatingCube_;
break;
// centrage du cube
case _Phase_LocatingCube_: // 1
if(Camera_xCenter<150) {
Loopcentered = 0;
MotionMove = _MOTION_GOLEFT_;
Serial.print(" --> Need to move to LEFT (Loopcentered=");
Serial.print(Loopcentered);
Serial.print(") ");
} else if(Camera_xCenter>170) {
Loopcentered = 0;
MotionMove = _MOTION_GORIGHT_;
Serial.print(" --> Need to move to RIGHT (Loopcentered=");
Serial.print(Loopcentered);
Serial.print(") ");
} else {
MotionMove = _MOTION_STOP_;
Loopcentered +=1 ;
if(Loopcentered>6) {
Serial.print(" --> Cube centered !!! (Loopcentered=");
Serial.print(Loopcentered);
Serial.print(") ");
currentPhase = _Phase_ApprocheCube_;
}
}
break;
case _Phase_ApprocheCube_: // 2
// Serial.println("*** APPROCHE CUBE *** ");
data[1] = display.encodeDigit(((int)VL53L0X_distance / 100) % 10);
data[2] = display.encodeDigit(((int)VL53L0X_distance / 10) % 10);
data[3] = display.encodeDigit((int)VL53L0X_distance % 10);
if(cubeLocked && !cubeNear) {
if (VL53L0X_distance > 140) {
Serial.println("*** APPROCHE CUBE *** ");
MotionMove = _MOTION_BACKWARD_; // commande inversée par rapport Remote
} else {
Serial.println("*** APPROCHE CUBE (PROCHE)*** ");
MotionMove = _MOTION_STOP_;
// Secu à ajouter pour les cas de perte de cube...
cubeNear = true;
}
} else {
if(cubeNear) {
Serial.println("*** APPROCHE CUBE AVEUGLE *** ");
if (VL53L0X_distance > 17) {
display.setBrightness(1);
MotionMove = _MOTION_BACKWARD_;
} else {
Serial.println("*** CUBE DANS LA PINCE *** ");
MotionMove = _MOTION_STOP_;
currentPhase = _Phase_GetCube_;
// cubeNear = false;
display.setBrightness(3);
}
} else {
Serial.println("*** PERTE DU CUBE *** ");
MotionMove = _MOTION_STOP_;
currentPhase = _Phase_LocatingCube_;
}
}
break;
case _Phase_GetCube_: // 3
Serial.println("*** GET THE CUBE *** ");
NIPPER_ON = true;
MotionMove = _MOTION_STOP_;
motionStop();
currentPhase = _Phase_MoveCube_;
break;
case _Phase_MoveCube_: // 4
Serial.println("*** BRING BACK CUBE *** ");
MotionMove = _MOTION_STOP_;
motionStop();
MotionModeAuto = false;
break;
default:
Serial.println("*** LOST IN THE SPACE ***");
MotionMove = _MOTION_STOP_;
motionStop();
MotionModeAuto = false;
}
} else {
data[0] = 0x09;
Serial.println("*** NO OBJECT DETECTED ==> MANUAL MODE ***");
currentPhase = _Phase_LookingForCube_;
cubeNear = false;
MotionModeAuto = false;
MotionMove = _MOTION_STOP_;
////////////
////////////
reinitRobot();
////////////
////////////
}
} else {
currentPhase = _Phase_LookingForCube_;
data[0] = 0x49;
data[1] = 0x40;
data[2] = 0x40;
data[3] = 0x40;
if (Camera_ID != -1) {
data[2] = display.encodeDigit(1);
} else {
data[2] = display.encodeDigit(0);
}
}
loopConsole();
loopMotion();
loopNippers();
}
void reinitRobot() {
MotionMove = _MOTION_STOP_;
MotionModeAuto = false;
NIPPER_ON = false;
cubeNear = false;
motionStop();
currentPhase = _Phase_LookingForCube_;
}
#ifndef __ROBOTCLEANER_CAMERA_H__
#define __ROBOTCLEANER_CAMERA_H__
#define __CAMERA_DEBUG_ false
#include <Arduino.h>
#include "HUSKYLENS.h"
void switchConfig(int);
// void printResult(HUSKYLENSResult);
HUSKYLENS huskylens;
unsigned long lastSwitchTime = 0;
const unsigned long TIMEOUT = 30000; // Temps d'attente avant de changer de cible (5s)
void setupCamera() {
Serial.println("--> Setup Camera...");
// Wire.begin();
Serial3.begin(9600);
Camera_ID = 4; // 4 = Cube (ObjectTracking_Backup_4.bin), 2 = Bag (ObjectTracking_Backup_2.bin)
// On tente de se connecter jusqu'à ce que la caméra réponde
while (!huskylens.begin(Serial3)) {
Serial.println(" Erreur de connexion ! Vérifiez le câblage et le mode Serial3.");
delay(1000);
}
Serial.println(" HuskyLens connectée avec succès !");
// Initialisation en mode Tracking
huskylens.writeAlgorithm(ALGORITHM_OBJECT_TRACKING);
// Chargement de la première configuration
switchConfig(Camera_ID);
Serial.println("--< Setup Camera Ended !");
}
void loopCamera() {
if (!huskylens.request()) {
Serial.println(F("Erreur de communication."));
} else if (huskylens.available()) {
while (huskylens.available()) {
HUSKYLENSResult result = huskylens.read();
Camera_ID = -1;
cubeLocked = false;
if (result.command == COMMAND_RETURN_BLOCK) {
// result.xCenter result.yCenter result.width result.height
Camera_xCenter = result.xCenter;
Camera_yCenter = result.yCenter;
Camera_width = result.width;
Camera_height = result.height;
Camera_ID = result.ID;
cubeLocked = true;
} else if (result.command == COMMAND_RETURN_ARROW) {
// result.xOrigin result.yOrigin result.xTarget result.yTarget
Camera_xOrigin = result.xOrigin;
Camera_yOrigin = result.yOrigin;
Camera_xTarget = result.xTarget;
Camera_yTarget = result.yTarget;
cubeLocked = true;
} else {
Serial.println("Object unknown!");
}
}
} else {
Camera_xCenter = -1;
Camera_yCenter = -1;
Camera_width = -1;
Camera_height = -1;
Camera_xOrigin = -1;
Camera_yOrigin = -1;
Camera_xTarget = -1;
Camera_yTarget = -1;
Camera_ID = -1;
cubeLocked = false;
}
}
void switchConfig(int id) {
Serial.print(F(" Recherche de l'objet "));
Serial.println(id == 4 ? F("CUBE...") : F("BAG..."));
// La caméra va chercher ObjectTracking_Backup_2.bin ou ObjectTracking_Backup_4.bin à la racine de la SD
huskylens.loadModelFromSDCard(id);
Serial.println(F(" Fichier chargé."));
if (id == 4) {
huskylens.setCustomName("CUBE", 1);
} else {
huskylens.setCustomName("BAG", 1);
}
// On attend un peu que la caméra stabilise l'image après chargement
delay(8000);
if (!huskylens.isLearned()) {
Serial.println(F(" Erreur : HUSKYLENS have NOT learn something !"));
} else {
Serial.println(F(" HUSKYLENS have learn something or already known it !"));
}
}
#endif
#ifndef __ROBOTCLEANER_MOTION_H__
#define __ROBOTCLEANER_MOTION_H__
#define __MOTION_DEBUG_ false
#include <Arduino.h>
#include "remote.h"
#include <AFMotor.h>
void motionStop(void);
void motionTurnLeft(void);
void motionTurnRight(void);
void motionForward(void);
void motionBackward(void);
//Constants
const int slowSpeed=130; // Vitesse normale
const int fastSpeed=250; // Vitesse Turbo
const int joyMinValue = 10; // Zone de non réactivité du Joypad.
int _Speed = slowSpeed;
//Parameters
AF_DCMotor motorLeft(4); // Initialisation du moteur 4 motorShield
AF_DCMotor motorRight(3); // Initialisation du moteur 3 motorShield
int motorLeftSpeed = 0;
int motorRightSpeed = 0;
void setupMotion() {
Serial.println("--> Setup motion...");
if (__MOTION_DEBUG_) {
Serial.println(" ==> Test 2 Motors ...");
motorLeft.setSpeed(255);
motorLeft.run(FORWARD);
motorRight.setSpeed(255);
motorRight.run(FORWARD);
delay(2000);
}
motionStop();
Serial.println(" Motors initialised.");
Serial.println("--< Setup Motion Ended !");
}
void loopMotion() {
int joystickXValue = 0;
int joystickYValue = 0;
if (!MotionModeAuto) {
switch(MotionMove) {
case _MOTION_GOLEFT_:
motionTurnLeft();
break;
case _MOTION_GORIGHT_:
motionTurnRight();
break;
case _MOTION_FORWARD_:
motionForward();
break;
case _MOTION_BACKWARD_:
motionBackward();
break;
case _MOTION_STOP_:
motionStop();
break;
default:
Serial.println("Oups !!!");
motionStop();
}
// Gestion du point mort au milieu de joystick
if(joystickXValue>-joyMinValue & joystickXValue<joyMinValue) {
joystickXValue = 0;
}
if(joystickYValue>-joyMinValue & joystickYValue<joyMinValue) {
joystickYValue = 0;
}
if(!MOTION_TURBO) {
joystickXValue = map(RemotePadX, 0,255,-180,180);
joystickYValue = map(RemotePadY, 0,255,-180,180);
} else {
joystickXValue = map(RemotePadX, 0,255,-255,255);
joystickYValue = map(RemotePadY, 0,255,-255,255);
}
// conversion des valeurs analogiques du joystick en vitesses pour les moteurs
motorLeftSpeed = joystickYValue - joystickXValue;
motorRightSpeed = joystickYValue + joystickXValue;
// limitation des vitesses maximale et minimale des moteurs
motorLeftSpeed = constrain(motorLeftSpeed, -255, 255);
motorRightSpeed = constrain(motorRightSpeed, -255, 255);
// envoi des vitesses aux moteurs
motorLeft.setSpeed(abs(motorLeftSpeed));
motorRight.setSpeed(abs(motorRightSpeed));
// inversion des directions des moteurs si nécessaire
if (motorLeftSpeed < 0) {
motorLeft.run(BACKWARD);
} else {
motorLeft.run(FORWARD);
}
if (motorRightSpeed < 0) {
motorRight.run(BACKWARD);
} else {
motorRight.run(FORWARD);
}
if (motorLeftSpeed > -joyMinValue && motorLeftSpeed < joyMinValue) {
motorLeft.setSpeed(0);
motorLeft.run(RELEASE);
}
if (motorRightSpeed > -joyMinValue && motorRightSpeed < joyMinValue) {
motorRight.setSpeed(0);
motorRight.run(RELEASE);
}
} else {
if(!MOTION_TURBO) {
_Speed = slowSpeed;
} else {
_Speed = fastSpeed;
}
// Serial.print("MotionMove = ");
// Serial.println(MotionMove);
if(MotionMove!=0) {
if(Camera_ID != -1) {
switch(MotionMove) {
case _MOTION_GOLEFT_:
motionTurnLeft();
break;
case _MOTION_GORIGHT_:
motionTurnRight();
break;
case _MOTION_STOP_:
motionStop();
break;
case _MOTION_FORWARD_:
motionForward();
break;
case _MOTION_BACKWARD_:
motionBackward();
break;
default:
Serial.println("Oups !!!");
motionStop();
}
}
}
}
}
void motionStop() {
motorLeft.setSpeed(0);
motorLeft.run(RELEASE);
motorRight.setSpeed(0);
motorRight.run(RELEASE);
}
void motionTurnRight() {
motorLeft.setSpeed(_Speed*0.8);
motorLeft.run(BACKWARD);
motorRight.setSpeed(_Speed);
motorRight.run(FORWARD);
}
void motionTurnLeft() {
motorLeft.setSpeed(_Speed);
motorLeft.run(FORWARD);
motorRight.setSpeed(_Speed*0.8);
motorRight.run(BACKWARD);
}
void motionForward() {
motorLeft.setSpeed(_Speed);
motorLeft.run(FORWARD);
motorRight.setSpeed(_Speed);
motorRight.run(FORWARD);
}
void motionBackward() {
motorLeft.setSpeed(_Speed);
motorLeft.run(BACKWARD);
motorRight.setSpeed(_Speed);
motorRight.run(BACKWARD);
}
#endif
#ifndef __ROBOTCLEANER_NIPPERS_H__
#define __ROBOTCLEANER_NIPPERS_H__
#define __NIPPERS_DEBUG_ false
#include <Arduino.h>
#include <Servo.h>
Servo myNipper;
// Servo myAngle;
void setupNippers() {
Serial.println("--> Setup Snippers...");
myNipper.attach(10); // attaches the servo on pin 9 to the Servo object
myNipper.write(0);
delay(1000);
myNipper.write(90);
delay(1000);
myNipper.write(0);
// myAngle.attach(9); // attaches the servo on pin 9 to the Servo object
// myAngle.write(90);
Serial.println("--< Setup Snippers Ended !");
}
void loopNippers() {
if(NIPPER_ON) {
myNipper.write(90);
} else {
myNipper.write(0);
}
}
#endif
#ifndef __ROBOTCLEANER_REMOTE_H__
#define __ROBOTCLEANER_REMOTE_H__
#define __REMOTE_DEBUG_ false
#include <Arduino.h>
void motionStop(void);
void reinitRobot();
#include <PS2X_lib.h>
PS2X ps2x;
const byte dataPin = 30;
const byte commandPin = 32;
const byte attentionPin = 34;
const byte clockPin = 36;
byte type = 0;
int error = 0;
byte vibrate = 0;
void setupRemote() {
Serial.println("--> Setup Remote...");
error = ps2x.config_gamepad(clockPin, commandPin, attentionPin, dataPin, true, true); // gardez true, true à la fin même si pas de moteurs
switch(error) {
case 0:
Serial.println(" Found Controller, configured successful");
Serial.println(" Try out all the buttons, X will vibrate the controller, faster as you press harder;");
Serial.println(" holding L1 or R1 will print out the analog stick values.");
break;
case 1:
Serial.println(" No controller found, check wiring...");
break;
case 2:
Serial.println(" Controller found but not accepting commands...");
break;
case 3:
Serial.println(" Controller refusing to enter Pressures mode, may not support it. ");
break;
default:
Serial.print(" Unknown error ");
Serial.print(error);
Serial.println(".");
}
type = ps2x.readType();
switch(type) {
case 0:
Serial.println(" Unknown Controller type");
break;
case 1:
Serial.println(" DualShock Controller Found");
break;
case 2:
Serial.println(" GuitarHero Controller Found");
break;
}
ps2x.read_gamepad(); // initialisation des valeurs
delay(50);
ps2x.read_gamepad(); /* initialise les états */
Serial.println("--< Setup Remote Ended !");
}
void loopRemote() {
static uint32_t chrono = 0;
const uint32_t periode = 20ul; // la manette est assez sensible, il ne faut pas lui demander les infos trop souvent. 15ms ou 20ms ça fonctionne pour moi
if (millis() - chrono >= periode) {
int RX = 0, RY = 0, LX = 0, LY = 0;
static int PRX = 127, PRY = 128, PLX = 127, PLY = 128;
chrono += periode;
ps2x.read_gamepad(false, vibrate); /* on lit l'état de la manette */
LX = ps2x.Analog(PSS_LX); /* joystick de gauche X*/
LY = ps2x.Analog(PSS_LY); /* joystick de gauche Y */
RemotePadX = LX;
RemotePadY = LY;
RX = ps2x.Analog(PSS_RX); /* joystick de droite X */
RY = ps2x.Analog(PSS_RY); /* joystick de droite Y */
// si une des coordonnées des joystick a changé alors on imprime les nouvelles coordonnées
if ((LX != PLX) || (LY != PLY) || (RX != PRX) || (RY != PRY)) {
PLX = LX;
PLY = LY;
PRX = RX;
PRY = RY;
}
RemoteKey = "None";
if (ps2x.ButtonPressed(PSB_START)) {
RemoteKey = "START APPUI";
vibrate = 255;
}
if (ps2x.ButtonPressed(PSB_SELECT)) { RemoteKey = "SELECT APPUI"; }
if (ps2x.ButtonPressed(PSB_PAD_UP)) {
RemoteKey = "HAUT APPUI";
MotionMove = _MOTION_FORWARD_;
}
if (ps2x.ButtonPressed(PSB_PAD_RIGHT)) {
RemoteKey = "DROIT APPUI";
MotionMove = _MOTION_GORIGHT_;
}
if (ps2x.ButtonPressed(PSB_PAD_LEFT)){
RemoteKey = "GAUCHE APPUI";
MotionMove = _MOTION_GOLEFT_;
}
if (ps2x.ButtonPressed(PSB_PAD_DOWN)) {
RemoteKey = "BAS APPUI";
MotionMove = _MOTION_BACKWARD_;
}
if (ps2x.ButtonPressed(PSB_L1)) { RemoteKey = "GAUCHE 1 APPUI"; }
if (ps2x.ButtonPressed(PSB_R1)) { RemoteKey = "DROITE 1 APPUI"; }
if (ps2x.ButtonPressed(PSB_L2)) { RemoteKey = "GAUCHE 2 APPUI"; }
if (ps2x.ButtonPressed(PSB_R2)) { RemoteKey = "DROITE 2 APPUI"; }
if (ps2x.ButtonPressed(PSB_L3)) { RemoteKey = "ANALOG GAUCHE APPUI"; }
if (ps2x.ButtonPressed(PSB_R3)) { RemoteKey = "ANALOG DROITE APPUI"; }
if (ps2x.ButtonPressed(PSB_GREEN)) {
RemoteKey = "Triangle APPUI";
MOTION_TURBO = true;
}
if (ps2x.ButtonPressed(PSB_BLUE)) {
RemoteKey = "X APPUI";
MotionModeAuto = !MotionModeAuto;
}
if (ps2x.ButtonPressed(PSB_RED)) {
RemoteKey = "Cercle APPUI";
NIPPER_ON = true;
}
if (ps2x.ButtonPressed(PSB_PINK)) {
RemoteKey = "Carre APPUI";
reinitRobot();
}
if (ps2x.Button(PSB_START)) { RemoteKey = "START"; }
if (ps2x.Button(PSB_SELECT)) { RemoteKey = "SELECT"; }
if (ps2x.Button(PSB_PAD_UP)) {
RemoteKey = "HAUT";
MotionMove = _MOTION_FORWARD_;
}
if (ps2x.Button(PSB_PAD_RIGHT)) {
RemoteKey = "DROITE";
MotionMove = _MOTION_GORIGHT_;
}
if (ps2x.Button(PSB_PAD_LEFT)) {
RemoteKey = "GAUCHE";
MotionMove = _MOTION_GOLEFT_;
}
if (ps2x.Button(PSB_PAD_DOWN)) {
RemoteKey = "BAS";
MotionMove = _MOTION_BACKWARD_;
}
if (ps2x.Button(PSB_L1)) { RemoteKey = "GAUCHE 1"; }
if (ps2x.Button(PSB_R1)) { RemoteKey = "DROITE 1"; }
if (ps2x.Button(PSB_L2)) { RemoteKey = "GAUCHE 2"; }
if (ps2x.Button(PSB_R2)) { RemoteKey = "DROITE 2"; }
if (ps2x.Button(PSB_L3)) { RemoteKey = "ANALOG GAUCH"; }
if (ps2x.Button(PSB_R3)) { RemoteKey = "ANALOG DROITE"; }
if (ps2x.Button(PSB_GREEN)) { RemoteKey = "Triangle"; }
if (ps2x.Button(PSB_BLUE)) { RemoteKey = "X"; }
if (ps2x.Button(PSB_RED)) { RemoteKey = "Cercle"; }
if (ps2x.Button(PSB_PINK)) { RemoteKey = "Carre"; }
if (ps2x.ButtonReleased(PSB_START)) {
RemoteKey = "START RELACHE";
vibrate = 0;
}
if (ps2x.ButtonReleased(PSB_SELECT)) RemoteKey = "SELECT RELACHE";
if (ps2x.ButtonReleased(PSB_PAD_UP)) {
RemoteKey = "HAUT RELACHE";
MotionMove = _MOTION_STOP_;
}
if (ps2x.ButtonReleased(PSB_PAD_RIGHT)) {
RemoteKey = "DROITE RELACHE";
MotionMove = _MOTION_STOP_;
}
if (ps2x.ButtonReleased(PSB_PAD_LEFT)) {
RemoteKey = "GAUCHE RELACHE";
MotionMove = _MOTION_STOP_;
}
if (ps2x.ButtonReleased(PSB_PAD_DOWN)) {
RemoteKey = "BAS RELACHE";
MotionMove = _MOTION_STOP_;
}
if (ps2x.ButtonReleased(PSB_L1)) { RemoteKey = "GAUCHE 1 RELACHE"; }
if (ps2x.ButtonReleased(PSB_R1)) { RemoteKey = "DROITE 1 RELACHE"; }
if (ps2x.ButtonReleased(PSB_L2)) { RemoteKey = "GAUCHE 2 RELACHE"; }
if (ps2x.ButtonReleased(PSB_R2)) { RemoteKey = "DROITE 2 RELACHE"; }
if (ps2x.ButtonReleased(PSB_L3)) { RemoteKey = "ANAL GAUCHE RELACHE"; }
if (ps2x.ButtonReleased(PSB_R3)) { RemoteKey = "ANAL DROITE RELACHE"; }
if (ps2x.ButtonReleased(PSB_GREEN)) {
RemoteKey = "Triangle RELACHE";
MOTION_TURBO = false;
}
if (ps2x.ButtonReleased(PSB_BLUE)) {
MotionMove = _MOTION_STOP_;
RemoteKey = "X RELACHE";
}
if (ps2x.ButtonReleased(PSB_RED)) {
RemoteKey = "Cercle RELACHE";
NIPPER_ON = false;
}
if (ps2x.ButtonReleased(PSB_PINK)) { RemoteKey = "Carre RELACHE"; }
}
}
#endif
#ifndef __ROBOTCLEANER_DISTANCE_H__
#define __ROBOTCLEANER_DISTANCE_H__
#define __DISTANCE_DEBUG_ false
#include <Arduino.h>
const int _Correction = -90;
#include "DFRobot_VL53L0X.h"
DFRobot_VL53L0X sensor;
void setupDistance() {
Serial.println("--> Setup Distance...");
sensor.begin(0x50);
//Set to Back-to-back mode and high precision mode
sensor.setMode(sensor.eContinuous,sensor.eHigh);
//Laser rangefinder begins to work
sensor.start();
Serial.println("--< Setup Distance Ended !");
}
void loopDistance() {
// Serial.print("Distance: ");Serial.println(sensor.getDistance());
VL53L0X_distance = sensor.getDistance() + _Correction;
if (VL53L0X_distance<0) {
VL53L0X_distance = 0;
}
}
#endif
#ifndef __ROBOTCLEANER_CONSOLE_H__
#define __ROBOTCLEANER_CONSOLE_H__
#define __CONSOLE_DEBUG_ false
#include <Arduino.h>
#define CLK 43
#define DIO 45
#include <TM1637Display.h>
TM1637Display display(CLK, DIO);
uint8_t data[] = { 0x40, 0x40, 0x40, 0x40 };
uint8_t blank[] = { 0x00, 0x00, 0x00, 0x00 };
void setupConsole() {
display.clear();
display.setBrightness(3);
display.setSegments(data);
// display.showNumberHexEx(0x0000, true);
}
void loopConsole() {
display.setSegments(data);
}
#endif

| Tension V | 25% | 50% | 45% | 100% |
|---|---|---|---|---|
| 1S | 3.3 | 3.5 | 3.7 | 3.9 |
| 2S | 6.6 | 7.0 | 7.4 | 7.8 |
| 3S | 9.9 | 10.5 | 11.1 | 11.7 |
| 4S | 13.2 | 14.0 | 14.8 | 15.6 |
| 5S | 16.5 | 17.5 | 18.5 | 19.5 |
| 6S | 19.8 | 21.0 | 22.2 | 23.4 |
| 7S | 23.1 | 24.5 | 25.9 | 27.3 |
| 8S | 26.4 | 28.0 | 29.6 | 31.2 |
