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)
2421const uint8_t LIDAR_GPIO_EN = 19 ; // ESP32 GPIO connected to Lidar EN pin
2522const uint8_t LIDAR_GPIO_RX = 16 ; // ESP32 GPIO connected to Lidar RX pin
2623const uint8_t LIDAR_GPIO_TX = 17 ; // ESP32 GPIO connected to Lidar TX pin
2724const 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 ;
5048const uint32_t LIDAR_PWM_FREQ = 10000 ;
5149const uint8_t LIDAR_PWM_BITS = 11 ;
52- const uint8_t LIDAR_PWM_CHANNEL = 0 ;
50+ const uint8_t LIDAR_PWM_CHANNEL = 2 ;
5351const uint16_t LIDAR_SERIAL_RX_BUF_LEN = 1024 ;
5452
5553#include " lds_all_models.h"
@@ -58,14 +56,6 @@ HardwareSerial LidarSerial(1);
5856LDS *lidar;
5957
6058void 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() {
117106void 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
138129int lidar_serial_read_callback () {
@@ -151,52 +142,88 @@ size_t lidar_serial_write_callback(const uint8_t * buffer, size_t length) {
151142
152143void 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
0 commit comments