diff --git a/README.md b/README.md index 705ade0..c9fc27d 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ and read this [blog post](https://kaia.ai/blog/arduino-lidar-library/) for more Please visit the [Support Forum](https://github.com/makerspet/support/discussions/)! This library supports: -- YDLIDAR X4, X3, X3-PRO, X2/X2L models +- YDLIDAR X4, X3, X3-PRO, X2/X2L, SCL models - SLAMTEC RPLIDAR A1 - Neato XV11/Botvac - Xiaomi Roborock Mi 1st gen LDS02RR @@ -19,6 +19,11 @@ Other models are in the works. ![LDS_collection_labeled_v3](https://github.com/kaiaai/LDS/assets/33589365/7b6a6a6f-a27c-45de-99c9-9e60d17b4d14) +### Video: YDLIDAR SCL runs on Arduino, ROS2 + + YDLIDAR SCL laser distance scan sensor runs on Arduino, ROS2 + + ### Video: Neato XV11 runs on Arduino, ROS2 Neato XV11 laser distance scan sensor runs on Arduino, ROS2 @@ -74,6 +79,9 @@ Some LiDAR/LDS models do not have built-in motor control and therefore require a ## Release notes +## v0.5.6 +- added YDLIDAR SCL + ## v0.5.5 - compilation bugfix diff --git a/keywords.txt b/keywords.txt index 3c78e6f..d2c3bf1 100644 --- a/keywords.txt +++ b/keywords.txt @@ -11,6 +11,7 @@ LDS_YDLIDAR_X4 KEYWORD1 LDS_YDLIDAR_X3 KEYWORD1 LDS_YDLIDAR_X3_PRO KEYWORD1 LDS_YDLIDAR_X2_X2L KEYWORD1 +LDS_YDLIDAR_SCL KEYWORD1 LDS_NEATO_X11 KEYWORD1 LDS_LDS02RR KEYWORD1 LDS_RPLIDAR_A1 KEYWORD1 diff --git a/library.properties b/library.properties index 2a7dc90..ad55839 100644 --- a/library.properties +++ b/library.properties @@ -1,9 +1,9 @@ name=LDS -version=0.5.5 +version=0.5.6 author=Ilia O. maintainer=Ilia O. sentence=Laser distance scan sensors (LDS/LIDAR) wrapper/controller for kaia.ai robotics platform -paragraph=Supports YDLIDAR X4, X3, X3 PRO, X2/X2L; Xiaomi Roborock 1st gen LDS02RR; Neato XV11; SLAMTEC RPLIDAR A1; 3irobotix Delta-2A, -2B, -2G, -2A 115000; LDROBOT LD14P; CAMSENSE X1 +paragraph=Supports YDLIDAR X4, X3, X3 PRO, X2/X2L, SCL; Xiaomi Roborock 1st gen LDS02RR; Neato XV11; SLAMTEC RPLIDAR A1; 3irobotix Delta-2A, -2B, -2G, -2A 115000; LDROBOT LD14P; CAMSENSE X1 category=Sensors url=https://github.com/kaiaai/LDS architectures=* diff --git a/src/LDS_YDLIDAR_SCL.cpp b/src/LDS_YDLIDAR_SCL.cpp index eb87fd5..8186c1f 100644 --- a/src/LDS_YDLIDAR_SCL.cpp +++ b/src/LDS_YDLIDAR_SCL.cpp @@ -273,9 +273,9 @@ LDS::result_t LDS_YDLIDAR_SCL::waitScanDot() { if (CheckSumResult == true) { int32_t AngleCorrectForDistance = 0; point = package_scl.packageSampleDistance[package_Sample_Index]; - node.distance_mm = (point.distance0 >> 2) + (point.distance1 << 8); + node.distance_mm = (point.distance_lsb >> 2) + (point.distance_msb << 6); node.intensity = point.intensity; - node.quality_flag = point.distance0 && 0x03; + node.quality_flag = point.distance_lsb && 0x03; if (node.distance_mm != 0) { AngleCorrectForDistance = (int32_t)(atan(17.8f/((float)node.distance_mm))*3666.929888837269f); // *64*360/2/pi diff --git a/src/LDS_YDLIDAR_SCL.h b/src/LDS_YDLIDAR_SCL.h index d8f6532..e9c25b9 100644 --- a/src/LDS_YDLIDAR_SCL.h +++ b/src/LDS_YDLIDAR_SCL.h @@ -50,8 +50,8 @@ class LDS_YDLIDAR_SCL : public LDS_YDLIDAR_X4 { struct cloud_point_scl_t { uint8_t intensity; - uint8_t distance0; - uint8_t distance1; + uint8_t distance_lsb; + uint8_t distance_msb; } __attribute__((packed)); struct node_package_scl_t {