diff --git a/README.md b/README.md index 5f7da72..9425703 100644 --- a/README.md +++ b/README.md @@ -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) diff --git a/examples/all_lidars_esp32/all_lidars_esp32.ino b/examples/all_lidars_lds02rr_esp32/all_lidars_lds02rr_esp32.ino similarity index 64% rename from examples/all_lidars_esp32/all_lidars_esp32.ino rename to examples/all_lidars_lds02rr_esp32/all_lidars_lds02rr_esp32.ino index 47a067b..691a485 100644 --- a/examples/all_lidars_esp32/all_lidars_esp32.ino +++ b/examples/all_lidars_lds02rr_esp32/all_lidars_lds02rr_esp32.ino @@ -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 @@ -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" @@ -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(); @@ -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(); @@ -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() { @@ -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< -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() { @@ -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); @@ -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()); } } diff --git a/examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino b/examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino index ec58996..4986d65 100644 --- a/examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino +++ b/examples/ldrobot_ld14p_esp32c3/ldrobot_ld14p_esp32c3.ino @@ -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. @@ -19,6 +19,9 @@ #include // ESP32-C3 +const uint8_t LIDAR_TX_PIN = 5; +const uint8_t LIDAR_RX_PIN = 4; + HardwareSerial LidarSerial(1); LDS_LDROBOT_LD14P lidar; @@ -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); @@ -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()); } } diff --git a/examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino b/examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino index 30b5bef..1152648 100644 --- a/examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino +++ b/examples/ldrobot_ld14p_esp32s3/ldrobot_ld14p_esp32s3.ino @@ -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. @@ -19,6 +19,9 @@ #include // ESP32-S3 +const uint8_t LIDAR_TX_PIN = 15; +const uint8_t LIDAR_RX_PIN = 16; + HardwareSerial LidarSerial(1); LDS_LDROBOT_LD14P lidar; @@ -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); @@ -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()); } } diff --git a/examples/lds_basic_esp32/lds_basic_esp32.ino b/examples/lds_basic_esp32/lds_basic_esp32.ino deleted file mode 100644 index 0ba1070..0000000 --- a/examples/lds_basic_esp32/lds_basic_esp32.ino +++ /dev/null @@ -1,159 +0,0 @@ -// Copyright 2023-2024 REMAKE.AI, KAIA.AI, MAKERSPET.COM -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef ESP32 - #error This example runs on ESP32 -#endif - -#include -//#include - -const uint8_t LDS_MOTOR_EN_PIN = 19; // ESP32 Dev Kit LiDAR enable pin -const uint8_t LDS_MOTOR_PWM_PIN = 15; // LiDAR motor speed control using PWM -#define LDS_MOTOR_PWM_FREQ 10000 -#define LDS_MOTOR_PWM_BITS 11 -#define LDS_MOTOR_PWM_CHANNEL 2 // ESP32 PWM channel for LiDAR motor speed control - -HardwareSerial LidarSerial(2); // TX 17, RX 16 -LDS_YDLIDAR_X4 lidar; // Uncomment your LiDAR model -//LDS_DELTA_2G lidar; - -void setup() { - Serial.begin(115200); - - Serial.print("LiDAR model "); - Serial.println(lidar.getModelName()); - - Serial.print("LiDAR RX buffer size "); // default 128 hw + 256 sw - Serial.print(LidarSerial.setRxBufferSize(1024)); // must be before .begin() - - uint32_t baud_rate = lidar.getSerialBaudRate(); - 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); - - lidar.setScanPointCallback(lidar_scan_point_callback); - lidar.setPacketCallback(lidar_packet_callback); - lidar.setSerialWriteCallback(lidar_serial_write_callback); - lidar.setSerialReadCallback(lidar_serial_read_callback); - lidar.setMotorPinCallback(lidar_motor_pin_callback); - lidar.init(); - - LDS::result_t result = lidar.start(); - Serial.print("LiDAR start() result: "); - Serial.println(lidar.resultCodeToString(result)); - - if (result < 0) - Serial.println("WARNING: is LDS connected to ESP32?"); -} - -int lidar_serial_read_callback() { - int c = LidarSerial.read(); -// Uncomment below for debug -/* - if (c < 0) - return c; - - if (c < 16) - Serial.print('0'); - Serial.print(c, HEX); - - static int i=0; - if (i++ % 16 == 0) - Serial.println(); - else - Serial.print(' '); -*/ - return c; -} - -size_t lidar_serial_write_callback(const uint8_t * buffer, size_t length) { - return LidarSerial.write(buffer, 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) || 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(); - } -} - -void lidar_info_callback(LDS::info_t code, String info) { - Serial.print("LDS info "); - Serial.print(lidar.infoCodeToString(code)); - Serial.print(": "); - Serial.println(info); -} - -void lidar_error_callback(LDS::result_t code, String aux_info) { - Serial.print("LDS error "); - Serial.print(lidar.resultCodeToString(code)); - Serial.print(": "); - Serial.println(aux_info); -} - -void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) { - int pin = (lidar_pin == LDS::LDS_MOTOR_EN_PIN) ? - LDS_MOTOR_EN_PIN : LDS_MOTOR_PWM_PIN; - - if (value <= (float)LDS::DIR_INPUT) { - // Configure pin direction - if (value == (float)LDS::DIR_OUTPUT_PWM) { - ledcSetup(LDS_MOTOR_PWM_CHANNEL, LDS_MOTOR_PWM_FREQ, LDS_MOTOR_PWM_BITS); - ledcAttachPin(pin, LDS_MOTOR_PWM_CHANNEL); - } else - pinMode(pin, (value == (float)LDS::DIR_INPUT) ? INPUT : OUTPUT); - return; - } - - if (value < LDS::VALUE_PWM) // set constant output - digitalWrite(pin, (value == (float)LDS::VALUE_HIGH) ? HIGH : LOW); - else { // set PWM duty cycle - int pwm_value = ((1< -const uint8_t LDS_MOTOR_EN_PIN = 19; // ESP32 Dev Kit LiDAR enable pin -const uint8_t LDS_MOTOR_PWM_PIN = 15; // LiDAR motor speed control using PWM -#define LDS_MOTOR_PWM_FREQ 10000 -#define LDS_MOTOR_PWM_BITS 11 -#define LDS_MOTOR_PWM_CHANNEL 2 // ESP32 PWM channel for LiDAR motor speed control +const uint8_t LIDAR_EN_PIN = 19; // ESP32 Dev Kit LiDAR enable pin +const uint8_t LIDAR_PWM_PIN = 15; // LiDAR motor speed control using PWM +const uint8_t LIDAR_TX_PIN = 17; +const uint8_t LIDAR_RX_PIN = 16; -HardwareSerial LidarSerial(2); // TX 17, RX 16 +#define LIDAR_PWM_FREQ 10000 +#define LIDAR_PWM_BITS 11 +#define LIDAR_PWM_CHANNEL 2 // ESP32 PWM channel for LiDAR motor speed control + +HardwareSerial LidarSerial(1); LDS_YDLIDAR_X2_X2L lidar; void setup() { @@ -40,13 +43,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); @@ -78,17 +75,20 @@ 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) || 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()); } } @@ -108,27 +108,32 @@ void lidar_error_callback(LDS::result_t code, String aux_info) { void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) { int pin = (lidar_pin == LDS::LDS_MOTOR_EN_PIN) ? - LDS_MOTOR_EN_PIN : LDS_MOTOR_PWM_PIN; + LIDAR_EN_PIN : LIDAR_PWM_PIN; if (value <= (float)LDS::DIR_INPUT) { // Configure pin direction if (value == (float)LDS::DIR_OUTPUT_PWM) { - #if ESP_IDF_VERSION_MAJOR >= 5 - ledcAttachChannel(pin, LDS_MOTOR_PWM_FREQ, LDS_MOTOR_PWM_BITS, LDS_MOTOR_PWM_CHANNEL); + #if ESP_IDF_VERSION_MAJOR < 5 + ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS); + ledcAttachPin(pin, LIDAR_PWM_CHANNEL); #else - ledcSetup(LDS_MOTOR_PWM_CHANNEL, LDS_MOTOR_PWM_FREQ, LDS_MOTOR_PWM_BITS); - ledcAttachPin(pin, LDS_MOTOR_PWM_CHANNEL); + ledcAttachChannel(pin, LIDAR_PWM_FREQ, LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL); #endif } else pinMode(pin, (value == (float)LDS::DIR_INPUT) ? INPUT : OUTPUT); return; } - if (value < LDS::VALUE_PWM) // set constant output + if (value < (float)LDS::VALUE_PWM) // set constant output digitalWrite(pin, (value == (float)LDS::VALUE_HIGH) ? HIGH : LOW); - else { // set PWM duty cycle - int pwm_value = ((1< -//#include -const uint8_t LDS_MOTOR_EN_PIN = 19; // ESP32 Dev Kit LiDAR enable pin -const uint8_t LDS_MOTOR_PWM_PIN = 15; // LiDAR motor speed control using PWM -#define LDS_MOTOR_PWM_FREQ 10000 -#define LDS_MOTOR_PWM_BITS 11 -#define LDS_MOTOR_PWM_CHANNEL 2 // ESP32 PWM channel for LiDAR motor speed control +const uint8_t LIDAR_EN_PIN = 19; // ESP32 Dev Kit LiDAR enable pin +const uint8_t LIDAR_PWM_PIN = 15; // LiDAR motor speed control using PWM +const uint8_t LIDAR_TX_PIN = 17; +const uint8_t LIDAR_RX_PIN = 16; -HardwareSerial LidarSerial(2); // TX 17, RX 16 +#define LIDAR_PWM_FREQ 10000 +#define LIDAR_PWM_BITS 11 +#define LIDAR_PWM_CHANNEL 2 // ESP32 PWM channel for LiDAR motor speed control + +HardwareSerial LidarSerial(1); LDS_YDLIDAR_X4 lidar; -//LDS_DELTA_2G lidar; void setup() { Serial.begin(115200); @@ -42,13 +43,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); @@ -77,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) { 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()); } } @@ -106,16 +104,16 @@ void lidar_error_callback(LDS::result_t code, String aux_info) { void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) { int pin = (lidar_pin == LDS::LDS_MOTOR_EN_PIN) ? - LDS_MOTOR_EN_PIN : LDS_MOTOR_PWM_PIN; + LIDAR_EN_PIN : LIDAR_PWM_PIN; if (value <= (float)LDS::DIR_INPUT) { // Configure pin direction if (value == (float)LDS::DIR_OUTPUT_PWM) { - #if ESP_IDF_VERSION_MAJOR >= 5 - ledcAttachChannel(pin, LDS_MOTOR_PWM_FREQ, LDS_MOTOR_PWM_BITS, LDS_MOTOR_PWM_CHANNEL); + #if ESP_IDF_VERSION_MAJOR < 5 + ledcSetup(LIDAR_PWM_CHANNEL, LIDAR_PWM_FREQ, LIDAR_PWM_BITS); + ledcAttachPin(pin, LIDAR_PWM_CHANNEL); #else - ledcSetup(LDS_MOTOR_PWM_CHANNEL, LDS_MOTOR_PWM_FREQ, LDS_MOTOR_PWM_BITS); - ledcAttachPin(pin, LDS_MOTOR_PWM_CHANNEL); + ledcAttachChannel(pin, LIDAR_PWM_FREQ, LIDAR_PWM_BITS, LIDAR_PWM_CHANNEL); #endif } else pinMode(pin, (value == (float)LDS::DIR_INPUT) ? INPUT : OUTPUT); @@ -125,8 +123,13 @@ void lidar_motor_pin_callback(float value, LDS::lds_pin_t lidar_pin) { if (value < (float)LDS::VALUE_PWM) // set constant output digitalWrite(pin, (value == (float)LDS::VALUE_HIGH) ? HIGH : LOW); else { // set PWM duty cycle - int pwm_value = ((1< maintainer=Ilia O. sentence=Laser distance scan sensors (LDS/LIDAR) wrapper/controller for kaia.ai robotics platform