Skip to content

Commit

Permalink
All-Lidars example
Browse files Browse the repository at this point in the history
  • Loading branch information
Ilia O. authored and Ilia O. committed Dec 12, 2024
1 parent 60c730d commit a4b2398
Show file tree
Hide file tree
Showing 9 changed files with 199 additions and 310 deletions.
5 changes: 4 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -103,8 +103,11 @@ LidarSerial.begin(baud_rate, SERIAL_8N1, 4, 5); // GPIO4 as RX1, GPIO5 as TX1

## Release notes

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

## v0.6.0
- support for Espressif SDK 5.x (ESP32 Arduino 3.x)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,21 +16,21 @@
#error This example runs on ESP32
#endif

// 1. INCREASE Arduino IDE baud
const uint32_t SERIAL_MONITOR_BAUD = 115200;

// 2. CHANGE these to match your wiring
// 1. CHANGE these to match your wiring
// IGNORE pins absent from your Lidar model (often EN, PWM)
const uint8_t LIDAR_GPIO_EN = 19; // ESP32 GPIO connected to Lidar EN pin
const uint8_t LIDAR_GPIO_RX = 16; // ESP32 GPIO connected to Lidar RX pin
const uint8_t LIDAR_GPIO_TX = 17; // ESP32 GPIO connected to Lidar TX pin
const uint8_t LIDAR_GPIO_PWM = 15;// ESP32 GPIO connected to Lidar PWM pin

// 2. UNCOMMENT if using PWM pin and PWM LOW enables the motor
//#define INVERT_PWM_PIN

// 3. UNCOMMENT your Lidar model
//
//#define NEATO_XV11
//#define SLAMTEC_RPLIDAR_A1
//#define XIAOMI_LDS02RR
#define XIAOMI_LDS02RR
//#define YDLIDAR_SCL
//#define YDLIDAR_X2_X2L
//#define YDLIDAR_X3
Expand All @@ -39,17 +39,15 @@ const uint8_t LIDAR_GPIO_PWM = 15;// ESP32 GPIO connected to Lidar PWM pin
//#define 3IROBOTIX_DELTA_2A_115200
//#define 3IROBOTIX_DELTA_2A
//#define 3IROBOTIX_DELTA_2B
#define LDROBOT_LD14P
//#define LDROBOT_LD14P
//#define YDLIDAR_X4
//#define YDLIDAR_X4_PRO

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

// Usually you don't need to change the settings below
const uint32_t SERIAL_MONITOR_BAUD = 115200;
const uint32_t LIDAR_PWM_FREQ = 10000;
const uint8_t LIDAR_PWM_BITS = 11;
const uint8_t LIDAR_PWM_CHANNEL = 0;
const uint8_t LIDAR_PWM_CHANNEL = 2;
const uint16_t LIDAR_SERIAL_RX_BUF_LEN = 1024;

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

void setupLidar() {
#if ESP_IDF_VERSION_MAJOR >= 5
if (!ledcAttachChannel(LIDAR_GPIO_PWM, LIDAR_PWM_FREQ,
LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
Serial.println("setupLidar() ledcAttachChannel() error");
#else
if (!ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS))
Serial.println("setupLidar() ledcSetup() error");
#endif

#if defined(NEATO_XV11)
lidar = new LDS_NEATO_XV11();
Expand Down Expand Up @@ -107,8 +97,7 @@ void setupLidar() {
lidar->setInfoCallback(lidar_info_callback);
lidar->setErrorCallback(lidar_error_callback);

LidarSerial.begin(lidar->getSerialBaudRate(),
SERIAL_8N1, LIDAR_GPIO_TX, LIDAR_GPIO_RX);
LidarSerial.begin(lidar->getSerialBaudRate(), SERIAL_8N1, LIDAR_GPIO_TX, LIDAR_GPIO_RX);

lidar->init();
//lidar->stop();
Expand All @@ -117,22 +106,24 @@ void setupLidar() {
void setup() {
Serial.begin(SERIAL_MONITOR_BAUD);

Serial.println();
Serial.print("ESP IDF version ");
Serial.println(ESP_IDF_VERSION_MAJOR);

setupLidar();

Serial.print("LiDAR model ");
Serial.println(lidar->getModelName());
//Serial.print("LiDAR model ");
//Serial.println(lidar->getModelName());

Serial.print("Lidar baud rate ");
Serial.println(lidar->getSerialBaudRate());
//Serial.print("Lidar baud rate ");
//Serial.println(lidar->getSerialBaudRate());

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

if (result < 0)
Serial.println("Is the LiDAR connected to ESP32 and powered up?");

lidar->setScanTargetFreqHz(LIDAR_SCAN_FREQ_TARGET);
// Set desired rotations-per-second for some LiDAR models
// lidar->setScanTargetFreqHz(5.0f);
}

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

void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality,
bool scan_completed) {
static int i=0;

if (i % 20 == 0) {
Serial.print(i);
Serial.print(' ');
Serial.print(distance_mm);
Serial.print(' ');
Serial.println(angle_deg);
}
i++;

Serial.print(distance_mm);
Serial.print(' ');
Serial.println(angle_deg);

if (scan_completed)
Serial.println();
if (scan_completed) {
i = 0;
Serial.print("Scan completed; RPM ");
Serial.println(lidar->getCurrentScanFreqHz());
}
}

void lidar_motor_pin_callback(float value, LDS::lds_pin_t lds_pin) {
/*
Serial.print("Lidar pin ");
Serial.print(lidar->pinIDToString(lds_pin));
Serial.print(" set ");
if (lds_pin > 0)
Serial.print(value); // PWM value
else
Serial.print(lidar->pinStateToString((LDS::lds_pin_state_t)value));
Serial.print(", RPM ");
Serial.println(lidar->getCurrentScanFreqHz());
*/
int pin = (lds_pin == LDS::LDS_MOTOR_EN_PIN) ?
LIDAR_GPIO_EN : LIDAR_GPIO_PWM;
void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) {

int pin = (lidar_pin == LDS::LDS_MOTOR_EN_PIN) ? LIDAR_GPIO_EN : LIDAR_GPIO_PWM;

if (int(value) <= LDS::DIR_INPUT) {
if (value <= (float)LDS::DIR_INPUT) {

/*
Serial.print("GPIO ");
Serial.print(pin);
Serial.print(' ');
Serial.print(lidar->pinIDToString(lidar_pin));
Serial.print(" mode set to ");
Serial.println(lidar->pinStateToString(int(pin_mode)));
*/

// Configure pin direction
if (int(value) == LDS::DIR_OUTPUT_PWM) {
#if ESP_IDF_VERSION_MAJOR >= 5
if (!ledcAttachChannel(pin, LIDAR_PWM_FREQ,
LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
Serial.println("lidar_motor_pin_callback() ledcAttachChannel() error");
#else
if (value == (float)LDS::DIR_OUTPUT_PWM) {

#if ESP_IDF_VERSION_MAJOR < 5
ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS);
ledcAttachPin(pin, LIDAR_PWM_CHANNEL);
#else
if (!ledcAttachChannel(pin, LIDAR_PWM_FREQ, LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL))
Serial.println("lidar_motor_pin_callback() ledcAttachChannel() error");
#endif
} else
pinMode(pin, (int(value) == LDS::DIR_INPUT) ? INPUT : OUTPUT);
pinMode(pin, (value == (float)LDS::DIR_INPUT) ? INPUT : OUTPUT);

return;
}

if (int(value) < LDS::VALUE_PWM) // set constant output
digitalWrite(pin, (int(value) == LDS::VALUE_HIGH) ? HIGH : LOW);
else {
if (value < (float)LDS::VALUE_PWM) {
// Set constant output
// TODO invert PWM as needed
digitalWrite(pin, (value == (float)LDS::VALUE_HIGH) ? HIGH : LOW);

/*
Serial.print("GPIO ");
Serial.print(pin);
Serial.print(' ');
Serial.print(lidar->pinIDToString(lidar_pin));
Serial.print(" value set to ");
Serial.println(lidar->pinStateToString(int(value)));
*/

} else {
//Serial.print("PWM value set to ");
//Serial.print(value);

// set PWM duty cycle
#ifdef INVERT_PWM_PIN
value = 1 - value;
#endif

int pwm_value = ((1<<LIDAR_PWM_BITS)-1)*value;

#if ESP_IDF_VERSION_MAJOR < 5
ledcWrite(LIDAR_PWM_CHANNEL, pwm_value);
#else
ledcWriteChannel(LIDAR_PWM_CHANNEL, pwm_value);
#endif

//Serial.print(' ');
//Serial.println(pwm_value);
}
}

Expand Down
28 changes: 14 additions & 14 deletions examples/ldrobot_ld14p_esp32/ldrobot_ld14p_esp32.ino
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
// Copyright 2023-2024 KAIA.AI
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -18,7 +18,10 @@

#include <LDS_LDROBOT_LD14P.h>

HardwareSerial LidarSerial(2); // TX 17, RX 16
const uint8_t LIDAR_TX_PIN = 17;
const uint8_t LIDAR_RX_PIN = 16;

HardwareSerial LidarSerial(1);
LDS_LDROBOT_LD14P lidar;

void setup() {
Expand All @@ -34,13 +37,7 @@ void setup() {
Serial.print(", baud rate ");
Serial.println(baud_rate);

LidarSerial.begin(baud_rate); // Use default GPIO TX 17, RX 16
// Assign TX, RX pins
// LidarSerial.begin(baud_rate, SERIAL_8N1, rxPin, txPin);
// Details https://github.com/espressif/arduino-esp32/blob/master/cores/esp32/HardwareSerial.h
// Tutorial https://www.youtube.com/watch?v=eUPAoP7xC7A

//while (LidarSerial.read() >= 0);
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);

lidar.setScanPointCallback(lidar_scan_point_callback);
lidar.setPacketCallback(lidar_packet_callback);
Expand Down Expand Up @@ -75,16 +72,19 @@ void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality
bool scan_completed) {
static int i=0;

if ((i++ % 20 == 0) || scan_completed) {
if ((i % 20 == 0) || scan_completed) {
Serial.print(i);
Serial.print(' ');
Serial.print(distance_mm);
Serial.print(' ');
Serial.print(angle_deg);
if (scan_completed)
Serial.println('*');
else
Serial.println();
}
i++;

if (scan_completed) {
i = 0;
Serial.print("Scan completed; RPM ");
Serial.println(lidar.getCurrentScanFreqHz());
}
}

Expand Down
22 changes: 13 additions & 9 deletions examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
// Copyright 2023-2024 KAIA.AI
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -19,6 +19,9 @@
#include <LDS_LDROBOT_LD14P.h>

// ESP32-C3
const uint8_t LIDAR_TX_PIN = 5;
const uint8_t LIDAR_RX_PIN = 4;

HardwareSerial LidarSerial(1);
LDS_LDROBOT_LD14P lidar;

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

LidarSerial.begin(baud_rate, SERIAL_8N1, 4, 5); // GPIO4 as RX1, GPIO5 as TX1

//while (LidarSerial.read() >= 0);
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);

lidar.setScanPointCallback(lidar_scan_point_callback);
lidar.setPacketCallback(lidar_packet_callback);
Expand Down Expand Up @@ -72,16 +73,19 @@ void lidar_scan_point_callback(float angle_deg, float distance_mm, float quality
bool scan_completed) {
static int i=0;

if ((i++ % 20 == 0) || scan_completed) {
if ((i % 20 == 0) || scan_completed) {
Serial.print(i);
Serial.print(' ');
Serial.print(distance_mm);
Serial.print(' ');
Serial.print(angle_deg);
if (scan_completed)
Serial.println('*');
else
Serial.println();
}
i++;

if (scan_completed) {
i = 0;
Serial.print("Scan completed; RPM ");
Serial.println(lidar.getCurrentScanFreqHz());
}
}

Expand Down
22 changes: 14 additions & 8 deletions examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM
// Copyright 2023-2024 KAIA.AI
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -19,6 +19,9 @@
#include <LDS_LDROBOT_LD14P.h>

// ESP32-S3
const uint8_t LIDAR_TX_PIN = 15;
const uint8_t LIDAR_RX_PIN = 16;

HardwareSerial LidarSerial(1);
LDS_LDROBOT_LD14P lidar;

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

LidarSerial.begin(baud_rate, SERIAL_8N1, 16, 15); // GPIO16 as RX1, GPIO15 as TX1
LidarSerial.begin(baud_rate, SERIAL_8N1, LIDAR_RX_PIN, LIDAR_TX_PIN);

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

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

if ((i++ % 20 == 0) || scan_completed) {
if (i % 20 == 0) {
Serial.print(i);
Serial.print(' ');
Serial.print(distance_mm);
Serial.print(' ');
Serial.print(angle_deg);
if (scan_completed)
Serial.println('*');
else
Serial.println();
Serial.println(angle_deg);
}
i++;

if (scan_completed) {
i = 0;
Serial.print("Scan completed; RPM ");
Serial.println(lidar.getCurrentScanFreqHz());
}
}

Expand Down
Loading

0 comments on commit a4b2398

Please sign in to comment.