Lecture LIDAR LDS02RR avec arduino et affichage avec processing +Anneau Led
Description :
Ce projet consiste à interfacer un capteur LIDAR LDS02RR avec une carte Arduino afin de mesurer les distances dans un plan à 360°.
Les données recueillies sont ensuite envoyées vers Processing pour un affichage visuel en temps réel de la détection des objets et de leur position angulaire.
En parallèle, un anneau de LED (type NeoPixel / WS2812) est utilisé pour représenter la détection selon les angles :
- Chaque LED correspond à un angle ou une zone de balayage.
- Si un objet est détecté à moins de 250 mm, la LED associée passe en rouge.
- Si la distance est supérieure à 250 mm, la LED reste verte.
Ce système permet de visualiser de manière intuitive la proximité des objets autour du capteur, aussi bien sur l’écran que via l’indication lumineuse.
Prérequis :
- 1 x Carte Arduino Nano
- 1 x Module IRF520
- 1 x Capteur laser LiDAR LDS02RR
- 1 x Anneau LED x12 RGB WS2812
- 1 x Potentiomètre 10 KΩ
- 1 x Breadboard
Version IDE :
- Arduino IDE 2.3.5
Bibliothèque :
- Adafruit_NeoPixel.h (version 1.15.2 par Adafruit)
STL :
Vidéo de démonstration :
Schéma de câblage :


Code :
Code Arduino :
#include <SoftwareSerial.h>
#include <Adafruit_NeoPixel.h>
#define PIN 9 //
#define NUMPIXELS 12 // Popular NeoPixel ring size
Adafruit_NeoPixel pixels(NUMPIXELS, PIN, NEO_GRB + NEO_KHZ800);
#define Activdetect 250
#define RX_PIN 10 // Broche RX du radar
#define MOTOR_PIN 5 // Numéro de broche du contrôleur moteur sur Arduino Uno
int VitesseMOTOR = 173; // Réglage de la vitesse moteur 0-255
#define NB_DATA 4 // Mesure 1, Mesure 2, Mesure 3, Mesure 4
#define DATA_SIZE 5 // angle, speed, distance, invalid, strengh
int Framedata[NB_DATA][DATA_SIZE];
int DataAngle[24];
#define PACKET_SIZE 22
uint8_t Trame[PACKET_SIZE]; // Buffer trame (22 octets)
unsigned int packetIndex = 0; // Packet index
bool waitPacket = true;
bool debug = 0; //Active donnée pour la console si debug = 1
int ActivErreurlecture = 0; //Filtre les données erronées si ActivErreurlecture = 0
int Erreurlecture;
int ErreurlectureDist1;
int ErreurlectureDist2;
int ErreurlectureDist3;
int ErreurlectureDist4;
SoftwareSerial lidarSerial = SoftwareSerial(RX_PIN, 3);
unsigned long previousMillis = 0;
const int interval = 350;
int sensorPin = A0;
int sensorValue = 0;
void setup() {
lidarSerial.begin(115200);
Serial.begin(115200);
pinMode(RX_PIN, INPUT);
analogWrite(MOTOR_PIN, 255);
pixels.setBrightness(100);
pixels.begin(); // INITIALIZE NeoPixel strip object (REQUIRED)
// Initialiser le tampon de paquets
for (int i = 0; i < PACKET_SIZE; i++) Trame[i] = 0;
}
void loop() {
unsigned long currentMillis = millis();
if (currentMillis - previousMillis >= interval) {
previousMillis = currentMillis;
Led();
sensorValue = analogRead(sensorPin);
VitesseMOTOR = map(sensorValue, 0, 1024, 0, 255);
for (int i = 0; i < NUMPIXELS; i++) {
DataAngle[i] = 0;
}
}
analogWrite(MOTOR_PIN, VitesseMOTOR); // Envoyer un signal PWM au contrôleur de moteur
if (lidarSerial.available() > 0) {
uint8_t BufferByte = lidarSerial.read();
if (waitPacket) {
if (BufferByte == 0xFA) {
Erreurlecture = 0;
ErreurlectureDist1 = 0;
ErreurlectureDist2 = 0;
ErreurlectureDist3 = 0;
ErreurlectureDist4 = 0;
packetIndex = 0;
waitPacket = false;
Trame[packetIndex++] = BufferByte;
}
} else {
if (Trame[0] == 0xFA) {
Trame[packetIndex++] = BufferByte;
if (packetIndex >= PACKET_SIZE) {
uint16_t calc = Checksum(Trame);
uint16_t recv = Trame[20] | (Trame[21] << 8);
if (calc != recv) {
//Serial.println("checksum invalide");
Erreurlecture = 1;
} else {
//Serial.print("valide");
}
waitPacket = true;
decodePacket(Trame, PACKET_SIZE);
if (debug == 0 && Erreurlecture == 0) {
if (ErreurlectureDist1 == 0) {
sendData1();
for (int i = 1; i < NUMPIXELS; i++) {
if (Framedata[0][0] > i * 30 && Framedata[0][0] <= (i + 1) * 30 && Framedata[0][2] < Activdetect && DataAngle[i] == 0) {
DataAngle[i] = 1;
}
}
}
if (ErreurlectureDist2 == 0) {
sendData2();
for (int i = 0; i < NUMPIXELS; i++) {
if (Framedata[1][0] > i * 30 && Framedata[1][0] <= (i + 1) * 30 && Framedata[1][2] < Activdetect && DataAngle[i] == 0) {
DataAngle[i] = 1;
}
}
}
if (ErreurlectureDist3 == 0) {
sendData3();
for (int i = 0; i < NUMPIXELS; i++) {
if (Framedata[2][0] > i * 30 && Framedata[2][0] <= (i + 1) * 30 && Framedata[2][2] < Activdetect && DataAngle[i] == 0) {
DataAngle[i] = 1;
}
}
}
if (ErreurlectureDist4 == 0) {
sendData4();
for (int i = 0; i < NUMPIXELS; i++) {
if (Framedata[3][0] > i * 30 && Framedata[3][0] <= (i + 1) * 30 && Framedata[3][2] < Activdetect && DataAngle[i] == 0) {
DataAngle[i] = 1;
}
}
}
}
if (debug == 1) DebugData(Trame, PACKET_SIZE);
}
}
}
}
}
void decodePacket(uint8_t packet[], int packetSize) {
//Remise à zero des Frame datas
for (int i = 0; i < NB_DATA; i++) {
for (int b = 0; b < DATA_SIZE; b++) {
Framedata[i][b] = 0;
}
}
for (int i = 0; i < packetSize; i++) {
int test = i;
switch (test) {
case 1:
//Angle
Framedata[0][0] = (Trame[1] - 0xA0) * 4; // Convertion de la valeur 0 ~ 360°
Framedata[1][0] = ((Trame[1] - 0xA0) * 4) + 1; // Convertion de la valeur 0 ~ 360°
Framedata[2][0] = ((Trame[1] - 0xA0) * 4) + 2; // Convertion de la valeur 0 ~ 360°
Framedata[3][0] = ((Trame[1] - 0xA0) * 4) + 3; // Convertion de la valeur 0 ~ 360°
//Filtre Angle non valide
if (ActivErreurlecture == 0 && (Framedata[0][0] > 360 || Framedata[0][0] < 0)) {
Erreurlecture = 1;
}
break;
case 2:
//Vitesse
Framedata[0][1] = ((Trame[3] << 8) | Trame[2]) / 64.f;
Framedata[1][1] = ((Trame[3] << 8) | Trame[2]) / 64.f;
Framedata[2][1] = ((Trame[3] << 8) | Trame[2]) / 64.f;
Framedata[3][1] = ((Trame[3] << 8) | Trame[2]) / 64.f;
//Filtre Vitesse non valide
if (ActivErreurlecture == 0 && (Framedata[0][1] < 50)) {
Erreurlecture = 1;
}
break;
case 4:
//Distance 1
Framedata[0][2] |= ((Trame[4 + 1] & 0x3F) << 8) | Trame[4];
//Filtre Distance non valide
if (ActivErreurlecture == 0 && (Framedata[0][2] < 100 || Framedata[0][2] > 3000)) {
ErreurlectureDist1 = 1;
}
break;
case 5:
//Ce champ indique si la mesure est invalide(invalid)
//Si ce bit est 1 → mesure invalide (le capteur n’a pas pu renvoyer de distance correcte).
//Si 0 → mesure valide (distance correcte en mm).
Framedata[0][3] = (Trame[4 + 1] & 0x80) != 0;
//Filtre mesure invalide
if (ActivErreurlecture == 0 && (Framedata[0][3] == 1)) {
ErreurlectureDist1 = 1;
}
break;
case 6:
//Force du signal réfléchi (strengh)
//Faible valeur (≈0–100) → retour faible → réflexion mauvaise ou distance longue.
//Grande valeur (>1000) → retour fort → bonne surface réfléchissante, distance fiable.
Framedata[0][4] = (Trame[4 + 2]) | ((Trame[4 + 3]) << 8);
//Filtre Force du signal
if (ActivErreurlecture == 0 && (Framedata[0][4] < 100)) {
ErreurlectureDist1 = 1;
}
break;
case 8:
//Distance 2
Framedata[1][2] |= ((Trame[8 + 1] & 0x3F) << 8) | Trame[8];
if (ActivErreurlecture == 0 && (Framedata[1][2] < 100 || Framedata[1][2] > 3000)) {
ErreurlectureDist2 = 1;
}
break;
case 9:
//invalid
Framedata[1][3] = (Trame[8 + 1] & 0x80) != 0;
if (ActivErreurlecture == 0 && (Framedata[1][3] == 1)) {
ErreurlectureDist2 = 1;
}
break;
case 10:
//strengh
Framedata[1][4] = (Trame[8 + 2]) | ((Trame[8 + 3]) << 8);
if (ActivErreurlecture == 0 && (Framedata[1][4] < 100)) {
ErreurlectureDist2 = 1;
}
break;
case 12:
//Distance 3
Framedata[2][2] |= ((Trame[12 + 1] & 0x3F) << 8) | Trame[12];
if (ActivErreurlecture == 0 && (Framedata[2][2] < 100 || Framedata[2][2] > 3000)) {
ErreurlectureDist3 = 1;
}
break;
case 13:
//invalid
Framedata[2][3] = (Trame[12 + 1] & 0x80) != 0;
if (ActivErreurlecture == 0 && (Framedata[2][3] == 1)) {
ErreurlectureDist3 = 1;
}
break;
case 14:
//strengh
Framedata[2][4] = (Trame[12 + 2]) | ((Trame[12 + 3]) << 8);
if (ActivErreurlecture == 0 && (Framedata[2][4] < 100)) {
ErreurlectureDist3 = 1;
}
break;
case 16:
//Distance 4
Framedata[3][2] |= ((Trame[16 + 1] & 0x3F) << 8) | Trame[16];
if (ActivErreurlecture == 0 && (Framedata[3][2] < 100 || Framedata[3][2] > 3000)) {
ErreurlectureDist4 = 1;
}
break;
case 17:
//invalid
Framedata[3][3] = (Trame[16 + 1] & 0x80) != 0;
if (ActivErreurlecture == 0 && (Framedata[3][3] == 1)) {
ErreurlectureDist4 = 1;
}
break;
case 18:
//strengh
Framedata[3][4] = (Trame[16 + 2]) | ((Trame[16 + 3]) << 8);
if (ActivErreurlecture == 0 && (Framedata[3][4] < 100)) {
ErreurlectureDist4 = 1;
}
break;
default:
break;
}
}
}
int sendData1() {
//[angle1, distance 1,vitesse 1, invalid1, strengh1]
Serial.print(Framedata[0][0]);
Serial.print(",");
Serial.print(Framedata[0][2]);
Serial.print(",");
Serial.println(Framedata[0][1]);
}
int sendData2() {
//[angle2, distance 2,vitesse 2, invalid2, strengh2]
Serial.print(Framedata[1][0]);
Serial.print(",");
Serial.print(Framedata[1][2]);
Serial.print(",");
Serial.println(Framedata[1][1]);
}
int sendData3() {
//[angle3, distance 3,vitesse 3, invalid3, strengh3]
Serial.print(Framedata[2][0]);
Serial.print(",");
Serial.print(Framedata[2][2]);
Serial.print(",");
Serial.println(Framedata[2][1]);
}
int sendData4() {
//[angle4, distance 4,vitesse 4, invalid4, strengh4]
Serial.print(Framedata[3][0]);
Serial.print(",");
Serial.print(Framedata[3][2]);
Serial.print(",");
Serial.println(Framedata[3][1]);
}
int DebugData(uint8_t packet[], int packetSize) {
for (int i = 0; i < packetSize; i++) {
Serial.print("0x");
Serial.print(packet[i]);
Serial.print('\t');
}
Serial.println("");
for (int i = 0; i < packetSize; i++) {
Serial.print(packet[i], HEX);
Serial.print('\t');
}
Serial.println("");
for (int i = 0; i < NB_DATA; i++) {
Serial.print("Angle ");
Serial.print(i + 1);
Serial.print(" : ");
Serial.print(Framedata[i][0]);
Serial.print('\t');
Serial.print("Dist ");
Serial.print(i + 1);
Serial.print(" : ");
Serial.print(Framedata[i][2]);
Serial.print('\t');
Serial.print("RPM ");
Serial.print(i + 1);
Serial.print(" : ");
Serial.print(Framedata[i][1]);
Serial.print('\t');
Serial.print("Invalid ");
Serial.print(i + 1);
Serial.print(" : ");
Serial.print(Framedata[i][3]);
Serial.print('\t');
Serial.print("Strength ");
Serial.print(i + 1);
Serial.print(" : ");
Serial.print(Framedata[i][4]);
Serial.println('\t');
}
}
uint16_t Checksum(const uint8_t *data20) {
uint16_t words[10];
for (int i = 0; i < 10; i++) {
words[i] = data20[2 * i] | (data20[2 * i + 1] << 8);
}
uint32_t chk32 = 0;
for (int i = 0; i < 10; i++) {
chk32 = (chk32 << 1) + words[i];
chk32 &= 0xFFFFFFFF;
}
uint16_t checksum = ((chk32 & 0x7FFF) + (chk32 >> 15)) & 0x7FFF;
return checksum;
}
int Led() {
for (int i = 0; i < NUMPIXELS; i++) {
if (DataAngle[i] == 1) {
pixels.setPixelColor(i, pixels.Color(150, 0, 0));
} else {
pixels.setPixelColor(i, pixels.Color(0, 150, 0));
}
pixels.show();
}
}
Code Processing :
import processing.serial.*;
import java.util.ArrayList;
// Classe pour stocker l'angle, la distance et le temps de vie de chaque point
class ScanPoint {
float angle;
float distance;
int lifetime; // Temps de vie restant (en frames)
ScanPoint(float a, float d, int lt) {
angle = a;
distance = d;
lifetime = lt;
}
}
// L'objet Serial pour la communication
Serial myPort;
String data = "";
// Variables pour stocker les données lues
float currentAngle = 0;
float currentDistance = 0;
float currentSpeed = 0;
// Constantes pour les limites de distance (en mm)
final float MIN_DIST = 10; // 10 mm (Distance minimale mesurable)
final float MAX_DIST = 250; // 250 mm (Distance maximale mesurable)
// Rayon maximal pour l'affichage (en pixels)
final float MAX_DRAW_RADIUS = 300;
// Centre du radar
float centerX, centerY;
// Liste pour stocker tous les points scannés avec leur temps de vie
ArrayList<ScanPoint> scanHistory = new ArrayList<ScanPoint>();
// Les points vivent pendant 100 frames (pour un effacement plus long)
final int POINT_LIFETIME = 100;
// Opacité du fondu d'arrière-plan (plus petit = plus de rémanence)
final int FADE_OPACITY = 10;
void setup() {
size(1050, 700);
smooth();
frameRate(60);
// Le centre est décalé vers la gauche
// Ajustement de centerX pour laisser de la place aux étiquettes d'angle
centerX = (height - 50) / 2 + 30;
centerY = height / 2;
println(Serial.list());
// --- CONFIGURATION DU PORT SÉRIE ---
try {
myPort = new Serial(this, "COM4", 115200);
myPort.bufferUntil('\n');
} catch (Exception e) {
println("Erreur d'ouverture du port série: " + e.getMessage());
println("Vérifiez le nom du port et s'il est déjà utilisé.");
}
background(0); // Fond noir initial
}
void draw() {
// 1. Mise à jour de l'arrière-plan (effet de rémanence)
fill(0, FADE_OPACITY);
rect(0, 0, width, height);
pushMatrix();
translate(centerX, centerY);
// 2. Dessin de l'échelle du radar (lignes de grille)
noFill();
stroke(50, 200, 50, 150); // Vert foncé pour la grille
strokeWeight(1);
// Cercles de distance
ellipse(0, 0, MAX_DRAW_RADIUS * 2, MAX_DRAW_RADIUS * 2);
float halfRadius = map(100, MIN_DIST, MAX_DIST, 0, MAX_DRAW_RADIUS);
ellipse(0, 0, halfRadius * 2, halfRadius * 2);
float minRadius = map(MIN_DIST, MIN_DIST, MAX_DIST, 0, MAX_DRAW_RADIUS);
ellipse(0, 0, minRadius * 2, minRadius * 2);
// Étiquettes de distance
fill(50, 200, 50);
textSize(12);
textAlign(CENTER);
text("250 mm", MAX_DRAW_RADIUS - 30, -5);
text("100 mm", halfRadius - 20, -5);
text("10 mm", minRadius - 15, -5);
// Lignes d'angle (tous les 45 degrés)
stroke(50, 200, 50, 100);
for (int a = 0; a < 360; a += 45) {
float x_line = MAX_DRAW_RADIUS * cos(radians(a));
float y_line = MAX_DRAW_RADIUS * sin(radians(a));
line(0, 0, x_line, y_line);
}
// MISE À JOUR : AFFICHAGE DE L'ÉCHELLE DES ANGLES (de 0° à 360° complet)
float angleTextRadius = MAX_DRAW_RADIUS + 25; // Rayon légèrement plus grand pour le texte
textSize(14);
fill(0, 200, 0); // Vert pour les étiquettes d'angle
// Boucle de 0 à 359 par pas de 30 degrés.
// Remarque : 360° est la même position que 0°, on affiche donc 0° une seule fois.
for (int a = 0; a < 360; a += 30) {
// Utiliser 0° pour l'affichage à la place de 360° pour la lisibilité
int displayAngle = a == 360 ? 0 : a;
// Calculer la position (x, y) pour le texte sur le cercle extérieur
float x_text = angleTextRadius * cos(radians(a));
float y_text = angleTextRadius * sin(radians(a));
// Ajuster l'alignement pour que le texte soit centré sur le point
if (a == 0) textAlign(LEFT); // 0°/360° est à droite, on décale le texte à gauche du point
else if (a == 180) textAlign(RIGHT); // 180° est à gauche, on décale le texte à droite du point
else textAlign(CENTER); // Ailleurs : centrer
// Afficher l'angle
text(displayAngle + "°", x_text, y_text);
}
// 3. --- DESSIN ET MISE À JOUR DE L'HISTORIQUE DES POINTS ---
ArrayList<ScanPoint> updatedHistory = new ArrayList<ScanPoint>();
for (int i = 0; i < scanHistory.size(); i++) {
ScanPoint p = scanHistory.get(i);
// Calculer la position et la transparence
float drawRadius = map(p.distance, MIN_DIST, MAX_DIST, 0, MAX_DRAW_RADIUS);
float angleInRadians = radians(p.angle);
float x = drawRadius * cos(angleInRadians);
float y = drawRadius * sin(angleInRadians);
// Transparence basée sur le temps de vie (alpha max 255)
float alpha = map(p.lifetime, 0, POINT_LIFETIME, 0, 255);
// Dessiner le point
stroke(255, 0, 0, alpha); // Rouge, avec transparence
strokeWeight(3);
point(x, y);
// Mettre à jour le temps de vie
p.lifetime--;
// Garder le point s'il a encore du temps de vie
if (p.lifetime > 0) {
updatedHistory.add(p);
}
}
scanHistory = updatedHistory; // Mettre à jour l'historique
// 4. Dessin de la ligne de balayage actuelle (vert vif)
float currentDrawRadius = map(currentDistance, MIN_DIST, MAX_DIST, 0, MAX_DRAW_RADIUS);
float currentAngleInRadians = radians(currentAngle);
float currentX = currentDrawRadius * cos(currentAngleInRadians);
float currentY = currentDrawRadius * sin(currentAngleInRadians);
stroke(0, 255, 0, 255); // Vert vif (totalement opaque)
strokeWeight(2);
line(0, 0, currentX, currentY);
popMatrix();
// 5. --- AFFICHAGE DE LA LÉGENDE ET DES VALEURS ---
float legendX = 2 * centerX + 10;
float legendY = 50;
fill(255);
textSize(24);
textAlign(LEFT);
text("LÉGENDE ET DONNÉES", legendX, legendY);
// Section des données actuelles
textSize(16);
text("Données Actuelles:", legendX, legendY + 40);
fill(0, 255, 0); // Vert pour les données en direct
text("Angle (θ): " + nf(currentAngle, 0, 2) + "°", legendX, legendY + 65);
text("Distance (D): " + nf(currentDistance, 0, 2) + " mm", legendX, legendY + 90);
text("Vitesse (V): " + nf(currentSpeed, 0, 2) + " m/s", legendX, legendY + 115);
// Séparateur
stroke(255);
line(legendX, legendY + 135, legendX + 250, legendY + 135);
// Section de la Légende Graphique
fill(255);
text("Légende Graphique:", legendX, legendY + 165);
// Ligne de balayage actuelle
stroke(0, 255, 0, 255);
strokeWeight(2);
line(legendX, legendY + 190, legendX + 20, legendY + 190);
fill(255);
text("Balayage/Mesure Actuelle", legendX + 30, legendY + 195);
// Point historique
stroke(255, 0, 0, 255);
strokeWeight(3);
point(legendX + 10, legendY + 225);
fill(255);
text("Point Historique (s'estompe)", legendX + 30, legendY + 230);
// Échelle de distance
stroke(50, 200, 50, 150);
strokeWeight(1);
noFill();
ellipse(legendX + 10, legendY + 260, 20, 20);
fill(255);
text("Grille de Distance (10-1000 mm)", legendX + 30, legendY + 265);
}
void serialEvent(Serial p) {
// Lecture et parsing des données
try {
data = p.readStringUntil('\n');
} catch (Exception e) {
return;
}
if (data != null) {
data = trim(data);
if (data.contains(",")) {
String[] values = split(data, ',');
if (values.length == 3) {
try {
currentAngle = float(values[0]);
currentDistance = float(values[1]);
currentSpeed = float(values[2]);
currentAngle = currentAngle % 360;
if (currentAngle < 0) {
currentAngle += 360;
}
currentDistance = constrain(currentDistance, MIN_DIST, MAX_DIST);
// Ajouter le point à l'historique
ScanPoint newPoint = new ScanPoint(currentAngle, currentDistance, POINT_LIFETIME);
scanHistory.add(newPoint);
} catch (NumberFormatException e) {
println("Erreur de format de nombre: " + data);
}
}
}
}
}
