Skip to content

Commit a4b2398

Browse files
Ilia O.Ilia O.
authored andcommitted
All-Lidars example
1 parent 60c730d commit a4b2398

File tree

9 files changed

+199
-310
lines changed

9 files changed

+199
-310
lines changed

README.md

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -103,8 +103,11 @@ LidarSerial.begin(baud_rate, SERIAL_8N1, 4, 5); // GPIO4 as RX1, GPIO5 as TX1
103103

104104
## Release notes
105105

106-
## v0.6.1 in debug
106+
## v0.6.1
107107
- added an all-in-one example sketch for all supported Lidar models
108+
- pre-configured for LDS02RR
109+
- bugfixed Espressif SDK 5.x (ESP32 Arduino 3.x) build
110+
- examples cleanup
108111

109112
## v0.6.0
110113
- support for Espressif SDK 5.x (ESP32 Arduino 3.x)

examples/all_lidars_esp32/all_lidars_esp32.ino renamed to examples/all_lidars_lds02rr_esp32/all_lidars_lds02rr_esp32.ino

Lines changed: 86 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -16,21 +16,21 @@
1616
#error This example runs on ESP32
1717
#endif
1818

19-
// 1. INCREASE Arduino IDE baud
20-
const uint32_t SERIAL_MONITOR_BAUD = 115200;
21-
22-
// 2. CHANGE these to match your wiring
19+
// 1. CHANGE these to match your wiring
2320
// IGNORE pins absent from your Lidar model (often EN, PWM)
2421
const uint8_t LIDAR_GPIO_EN = 19; // ESP32 GPIO connected to Lidar EN pin
2522
const uint8_t LIDAR_GPIO_RX = 16; // ESP32 GPIO connected to Lidar RX pin
2623
const uint8_t LIDAR_GPIO_TX = 17; // ESP32 GPIO connected to Lidar TX pin
2724
const uint8_t LIDAR_GPIO_PWM = 15;// ESP32 GPIO connected to Lidar PWM pin
2825

26+
// 2. UNCOMMENT if using PWM pin and PWM LOW enables the motor
27+
//#define INVERT_PWM_PIN
28+
2929
// 3. UNCOMMENT your Lidar model
3030
//
3131
//#define NEATO_XV11
3232
//#define SLAMTEC_RPLIDAR_A1
33-
//#define XIAOMI_LDS02RR
33+
#define XIAOMI_LDS02RR
3434
//#define YDLIDAR_SCL
3535
//#define YDLIDAR_X2_X2L
3636
//#define YDLIDAR_X3
@@ -39,17 +39,15 @@ const uint8_t LIDAR_GPIO_PWM = 15;// ESP32 GPIO connected to Lidar PWM pin
3939
//#define 3IROBOTIX_DELTA_2A_115200
4040
//#define 3IROBOTIX_DELTA_2A
4141
//#define 3IROBOTIX_DELTA_2B
42-
#define LDROBOT_LD14P
42+
//#define LDROBOT_LD14P
4343
//#define YDLIDAR_X4
4444
//#define YDLIDAR_X4_PRO
4545

46-
// 4. Optional/Advanced
47-
float LIDAR_SCAN_FREQ_TARGET = 5.0f; // Set desired rotations-per-second for some LiDAR models
4846

49-
// Usually you don't need to change the settings below
47+
const uint32_t SERIAL_MONITOR_BAUD = 115200;
5048
const uint32_t LIDAR_PWM_FREQ = 10000;
5149
const uint8_t LIDAR_PWM_BITS = 11;
52-
const uint8_t LIDAR_PWM_CHANNEL = 0;
50+
const uint8_t LIDAR_PWM_CHANNEL = 2;
5351
const uint16_t LIDAR_SERIAL_RX_BUF_LEN = 1024;
5452

5553
#include "lds_all_models.h"
@@ -58,14 +56,6 @@ HardwareSerial LidarSerial(1);
5856
LDS *lidar;
5957

6058
void setupLidar() {
61-
#if ESP_IDF_VERSION_MAJOR >= 5
62-
if (!ledcAttachChannel(LIDAR_GPIO_PWM, LIDAR_PWM_FREQ,
63-
LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
64-
Serial.println("setupLidar() ledcAttachChannel() error");
65-
#else
66-
if (!ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS))
67-
Serial.println("setupLidar() ledcSetup() error");
68-
#endif
6959

7060
#if defined(NEATO_XV11)
7161
lidar = new LDS_NEATO_XV11();
@@ -107,8 +97,7 @@ void setupLidar() {
10797
lidar->setInfoCallback(lidar_info_callback);
10898
lidar->setErrorCallback(lidar_error_callback);
10999

110-
LidarSerial.begin(lidar->getSerialBaudRate(),
111-
SERIAL_8N1, LIDAR_GPIO_TX, LIDAR_GPIO_RX);
100+
LidarSerial.begin(lidar->getSerialBaudRate(), SERIAL_8N1, LIDAR_GPIO_TX, LIDAR_GPIO_RX);
112101

113102
lidar->init();
114103
//lidar->stop();
@@ -117,22 +106,24 @@ void setupLidar() {
117106
void setup() {
118107
Serial.begin(SERIAL_MONITOR_BAUD);
119108

109+
Serial.println();
110+
Serial.print("ESP IDF version ");
111+
Serial.println(ESP_IDF_VERSION_MAJOR);
112+
120113
setupLidar();
121114

122-
Serial.print("LiDAR model ");
123-
Serial.println(lidar->getModelName());
115+
//Serial.print("LiDAR model ");
116+
//Serial.println(lidar->getModelName());
124117

125-
Serial.print("Lidar baud rate ");
126-
Serial.println(lidar->getSerialBaudRate());
118+
//Serial.print("Lidar baud rate ");
119+
//Serial.println(lidar->getSerialBaudRate());
127120

128121
LDS::result_t result = lidar->start();
129122
Serial.print("startLidar() result: ");
130123
Serial.println(lidar->resultCodeToString(result));
131124

132-
if (result < 0)
133-
Serial.println("Is the LiDAR connected to ESP32 and powered up?");
134-
135-
lidar->setScanTargetFreqHz(LIDAR_SCAN_FREQ_TARGET);
125+
// Set desired rotations-per-second for some LiDAR models
126+
// lidar->setScanTargetFreqHz(5.0f);
136127
}
137128

138129
int lidar_serial_read_callback() {
@@ -151,52 +142,88 @@ size_t lidar_serial_write_callback(const uint8_t * buffer, size_t length) {
151142

152143
void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality,
153144
bool scan_completed) {
145+
static int i=0;
146+
147+
if (i % 20 == 0) {
148+
Serial.print(i);
149+
Serial.print(' ');
150+
Serial.print(distance_mm);
151+
Serial.print(' ');
152+
Serial.println(angle_deg);
153+
}
154+
i++;
154155

155-
Serial.print(distance_mm);
156-
Serial.print(' ');
157-
Serial.println(angle_deg);
158-
159-
if (scan_completed)
160-
Serial.println();
156+
if (scan_completed) {
157+
i = 0;
158+
Serial.print("Scan completed; RPM ");
159+
Serial.println(lidar->getCurrentScanFreqHz());
160+
}
161161
}
162162

163-
void lidar_motor_pin_callback(float value, LDS::lds_pin_t lds_pin) {
164-
/*
165-
Serial.print("Lidar pin ");
166-
Serial.print(lidar->pinIDToString(lds_pin));
167-
Serial.print(" set ");
168-
if (lds_pin > 0)
169-
Serial.print(value); // PWM value
170-
else
171-
Serial.print(lidar->pinStateToString((LDS::lds_pin_state_t)value));
172-
Serial.print(", RPM ");
173-
Serial.println(lidar->getCurrentScanFreqHz());
174-
*/
175-
int pin = (lds_pin == LDS::LDS_MOTOR_EN_PIN) ?
176-
LIDAR_GPIO_EN : LIDAR_GPIO_PWM;
163+
void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) {
164+
165+
int pin = (lidar_pin == LDS::LDS_MOTOR_EN_PIN) ? LIDAR_GPIO_EN : LIDAR_GPIO_PWM;
177166

178-
if (int(value) <= LDS::DIR_INPUT) {
167+
if (value <= (float)LDS::DIR_INPUT) {
168+
169+
/*
170+
Serial.print("GPIO ");
171+
Serial.print(pin);
172+
Serial.print(' ');
173+
Serial.print(lidar->pinIDToString(lidar_pin));
174+
Serial.print(" mode set to ");
175+
Serial.println(lidar->pinStateToString(int(pin_mode)));
176+
*/
179177

180178
// Configure pin direction
181-
if (int(value) == LDS::DIR_OUTPUT_PWM) {
182-
#if ESP_IDF_VERSION_MAJOR >= 5
183-
if (!ledcAttachChannel(pin, LIDAR_PWM_FREQ,
184-
LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
185-
Serial.println("lidar_motor_pin_callback() ledcAttachChannel() error");
186-
#else
179+
if (value == (float)LDS::DIR_OUTPUT_PWM) {
180+
181+
#if ESP_IDF_VERSION_MAJOR < 5
182+
ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS);
187183
ledcAttachPin(pin, LIDAR_PWM_CHANNEL);
184+
#else
185+
if (!ledcAttachChannel(pin, LIDAR_PWM_FREQ, LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
186+
Serial.println("lidar_motor_pin_callback() ledcAttachChannel() error");
188187
#endif
189188
} else
190-
pinMode(pin, (int(value) == LDS::DIR_INPUT) ? INPUT : OUTPUT);
189+
pinMode(pin, (value == (float)LDS::DIR_INPUT) ? INPUT : OUTPUT);
190+
191191
return;
192192
}
193193

194-
if (int(value) < LDS::VALUE_PWM) // set constant output
195-
digitalWrite(pin, (int(value) == LDS::VALUE_HIGH) ? HIGH : LOW);
196-
else {
194+
if (value < (float)LDS::VALUE_PWM) {
195+
// Set constant output
196+
// TODO invert PWM as needed
197+
digitalWrite(pin, (value == (float)LDS::VALUE_HIGH) ? HIGH : LOW);
198+
199+
/*
200+
Serial.print("GPIO ");
201+
Serial.print(pin);
202+
Serial.print(' ');
203+
Serial.print(lidar->pinIDToString(lidar_pin));
204+
Serial.print(" value set to ");
205+
Serial.println(lidar->pinStateToString(int(value)));
206+
*/
207+
208+
} else {
209+
//Serial.print("PWM value set to ");
210+
//Serial.print(value);
211+
197212
// set PWM duty cycle
213+
#ifdef INVERT_PWM_PIN
214+
value = 1 - value;
215+
#endif
216+
198217
int pwm_value = ((1<<LIDAR_PWM_BITS)-1)*value;
218+
219+
#if ESP_IDF_VERSION_MAJOR < 5
199220
ledcWrite(LIDAR_PWM_CHANNEL, pwm_value);
221+
#else
222+
ledcWriteChannel(LIDAR_PWM_CHANNEL, pwm_value);
223+
#endif
224+
225+
//Serial.print(' ');
226+
//Serial.println(pwm_value);
200227
}
201228
}
202229

examples/ldrobot_ld14p_esp32/ldrobot_ld14p_esp32.ino

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
1+
// Copyright 2023-2024 KAIA.AI
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -18,7 +18,10 @@
1818

1919
#include <LDS_LDROBOT_LD14P.h>
2020

21-
HardwareSerial LidarSerial(2); // TX 17, RX 16
21+
const uint8_t LIDAR_TX_PIN = 17;
22+
const uint8_t LIDAR_RX_PIN = 16;
23+
24+
HardwareSerial LidarSerial(1);
2225
LDS_LDROBOT_LD14P lidar;
2326

2427
void setup() {
@@ -34,13 +37,7 @@ void setup() {
3437
Serial.print(", baud rate ");
3538
Serial.println(baud_rate);
3639

37-
LidarSerial.begin(baud_rate); // Use default GPIO TX 17, RX 16
38-
// Assign TX, RX pins
39-
// LidarSerial.begin(baud_rate, SERIAL_8N1, rxPin, txPin);
40-
// Details https://github.com/espressif/arduino-esp32/blob/master/cores/esp32/HardwareSerial.h
41-
// Tutorial https://www.youtube.com/watch?v=eUPAoP7xC7A
42-
43-
//while (LidarSerial.read() >= 0);
40+
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);
4441

4542
lidar.setScanPointCallback(lidar_scan_point_callback);
4643
lidar.setPacketCallback(lidar_packet_callback);
@@ -75,16 +72,19 @@ void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality
7572
bool scan_completed) {
7673
static int i=0;
7774

78-
if ((i++ % 20 == 0) || scan_completed) {
75+
if ((i % 20 == 0) || scan_completed) {
7976
Serial.print(i);
8077
Serial.print(' ');
8178
Serial.print(distance_mm);
8279
Serial.print(' ');
8380
Serial.print(angle_deg);
84-
if (scan_completed)
85-
Serial.println('*');
86-
else
87-
Serial.println();
81+
}
82+
i++;
83+
84+
if (scan_completed) {
85+
i = 0;
86+
Serial.print("Scan completed; RPM ");
87+
Serial.println(lidar.getCurrentScanFreqHz());
8888
}
8989
}
9090

examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
1+
// Copyright 2023-2024 KAIA.AI
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -19,6 +19,9 @@
1919
#include <LDS_LDROBOT_LD14P.h>
2020

2121
// ESP32-C3
22+
const uint8_t LIDAR_TX_PIN = 5;
23+
const uint8_t LIDAR_RX_PIN = 4;
24+
2225
HardwareSerial LidarSerial(1);
2326
LDS_LDROBOT_LD14P lidar;
2427

@@ -35,9 +38,7 @@ void setup() {
3538
Serial.print(", baud rate ");
3639
Serial.println(baud_rate);
3740

38-
LidarSerial.begin(baud_rate, SERIAL_8N1, 4, 5); // GPIO4 as RX1, GPIO5 as TX1
39-
40-
//while (LidarSerial.read() >= 0);
41+
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);
4142

4243
lidar.setScanPointCallback(lidar_scan_point_callback);
4344
lidar.setPacketCallback(lidar_packet_callback);
@@ -72,16 +73,19 @@ void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality
7273
bool scan_completed) {
7374
static int i=0;
7475

75-
if ((i++ % 20 == 0) || scan_completed) {
76+
if ((i % 20 == 0) || scan_completed) {
7677
Serial.print(i);
7778
Serial.print(' ');
7879
Serial.print(distance_mm);
7980
Serial.print(' ');
8081
Serial.print(angle_deg);
81-
if (scan_completed)
82-
Serial.println('*');
83-
else
84-
Serial.println();
82+
}
83+
i++;
84+
85+
if (scan_completed) {
86+
i = 0;
87+
Serial.print("Scan completed; RPM ");
88+
Serial.println(lidar.getCurrentScanFreqHz());
8589
}
8690
}
8791

examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino

Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
1+
// Copyright 2023-2024 KAIA.AI
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -19,6 +19,9 @@
1919
#include <LDS_LDROBOT_LD14P.h>
2020

2121
// ESP32-S3
22+
const uint8_t LIDAR_TX_PIN = 15;
23+
const uint8_t LIDAR_RX_PIN = 16;
24+
2225
HardwareSerial LidarSerial(1);
2326
LDS_LDROBOT_LD14P lidar;
2427

@@ -35,7 +38,7 @@ void setup() {
3538
Serial.print(", baud rate ");
3639
Serial.println(baud_rate);
3740

38-
LidarSerial.begin(baud_rate, SERIAL_8N1, 16, 15); // GPIO16 as RX1, GPIO15 as TX1
41+
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);
3942

4043
//while (LidarSerial.read() >= 0);
4144

@@ -72,16 +75,19 @@ void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality
7275
bool scan_completed) {
7376
static int i=0;
7477

75-
if ((i++ % 20 == 0) || scan_completed) {
78+
if (i % 20 == 0) {
7679
Serial.print(i);
7780
Serial.print(' ');
7881
Serial.print(distance_mm);
7982
Serial.print(' ');
80-
Serial.print(angle_deg);
81-
if (scan_completed)
82-
Serial.println('*');
83-
else
84-
Serial.println();
83+
Serial.println(angle_deg);
84+
}
85+
i++;
86+
87+
if (scan_completed) {
88+
i = 0;
89+
Serial.print("Scan completed; RPM ");
90+
Serial.println(lidar.getCurrentScanFreqHz());
8591
}
8692
}
8793

0 commit comments

Comments
 (0)