diff --git a/.gitignore b/.gitignore index fd7b335..4fb3412 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,3 @@ *.json -build/** \ No newline at end of file +build/** +src/test_sys/build/** \ No newline at end of file diff --git a/ldlidar_driver/include/core/ldlidar_driver.h b/ldlidar_driver/include/core/ldlidar_driver.h index 5be7e02..07edba1 100644 --- a/ldlidar_driver/include/core/ldlidar_driver.h +++ b/ldlidar_driver/include/core/ldlidar_driver.h @@ -80,7 +80,7 @@ class LDLidarDriver { */ LidarStatus GetLaserScanData(Points2D& dst, int64_t timeout = 1000); - bool GetLidarSpinFreq(double& spin_hz); + bool GetLidarScanFreq(double& spin_hz); /** * @brief register get timestamp handle functional. diff --git a/ldlidar_driver/include/dataprocess/lipkg.h b/ldlidar_driver/include/dataprocess/lipkg.h index c321993..ddc9997 100644 --- a/ldlidar_driver/include/dataprocess/lipkg.h +++ b/ldlidar_driver/include/dataprocess/lipkg.h @@ -134,9 +134,9 @@ class LiPkg { Points2D GetLaserScanData(void); - void AnalysisLidarIsBlocking(uint16_t lidar_speed_val); + // void AnalysisLidarIsBlocking(uint16_t lidar_speed_val); - void AnalysisLidarIsOcclusion(Points2D& lidar_data); + // void AnalysisLidarIsOcclusion(Points2D& lidar_data); }; } // namespace ldlidar diff --git a/ldlidar_driver/src/core/ldlidar_driver.cpp b/ldlidar_driver/src/core/ldlidar_driver.cpp index 452191e..67857fa 100644 --- a/ldlidar_driver/src/core/ldlidar_driver.cpp +++ b/ldlidar_driver/src/core/ldlidar_driver.cpp @@ -24,7 +24,7 @@ namespace ldlidar { bool LDLidarDriver::is_ok_ = false; -LDLidarDriver::LDLidarDriver() : sdk_pack_version_("3.0.2"), +LDLidarDriver::LDLidarDriver() : sdk_pack_version_("3.0.3"), is_start_flag_(false), comm_pkg_(new LiPkg()), comm_serial_(new SerialInterfaceLinux()){ @@ -142,7 +142,7 @@ LidarStatus LDLidarDriver::GetLaserScanData(Points2D& dst, int64_t timeout) { } } -bool LDLidarDriver::GetLidarSpinFreq(double& spin_hz) { +bool LDLidarDriver::GetLidarScanFreq(double& spin_hz) { if (!is_start_flag_) { return false; } diff --git a/ldlidar_driver/src/dataprocess/lipkg.cpp b/ldlidar_driver/src/dataprocess/lipkg.cpp index 2e4543f..f30b650 100644 --- a/ldlidar_driver/src/dataprocess/lipkg.cpp +++ b/ldlidar_driver/src/dataprocess/lipkg.cpp @@ -146,11 +146,10 @@ bool LiPkg::Parse(const uint8_t *data, long len) { speed_ = datapkg_.speed; timestamp_ = datapkg_.timestamp; - // judge block - AnalysisLidarIsBlocking(datapkg_.speed); + // parse a package is success double diff = (datapkg_.end_angle / 100 - datapkg_.start_angle / 100 + 360) % 360; - if (diff <= ((double)datapkg_.speed * POINT_PER_PACK / 2300 * 1.5)) { + if (diff <= ((double)datapkg_.speed * POINT_PER_PACK / kPointFrequence * 1.5)) { if (0 == last_pkg_timestamp_) { last_pkg_timestamp_ = get_timestamp_(); @@ -221,7 +220,7 @@ bool LiPkg::AssemblePacket() { std::sort(tmp.begin(), tmp.end(), [](PointData a, PointData b) { return a.stamp < b.stamp; }); if (tmp.size() > 0) { SetLaserScanData(tmp); - AnalysisLidarIsOcclusion(tmp); + if (first_flag_) { first_flag_ = false; @@ -324,49 +323,51 @@ Points2D LiPkg::GetLaserScanData(void) { return lidar_frame_data_; } -void LiPkg::AnalysisLidarIsBlocking(uint16_t lidar_speed_val){ - static int16_t judge_block_cnt = 0; - static uint16_t last_speed = 0; - uint16_t curr_speed = lidar_speed_val; - if ((curr_speed == 0) && (last_speed == 0)) { - judge_block_cnt++; - } else { - judge_block_cnt--; - if (judge_block_cnt <= 0) { - judge_block_cnt = 0; - } - } - if (judge_block_cnt >= 5) { - SetLidarStatus(LidarStatus::ERROR); - SetLidarErrorCode(LIDAR_ERROR_BLOCKING); - } else { - SetLidarStatus(LidarStatus::NORMAL); - SetLidarErrorCode(LIDAR_NO_ERROR); - } - last_speed = curr_speed; -} - -void LiPkg::AnalysisLidarIsOcclusion(Points2D& lidar_data) { - - uint16_t no_occlusion_count = 0; - for (auto point: lidar_data) { - if (point.distance != 0) { - no_occlusion_count++; - } - } - - if (no_occlusion_count <= 5) { - SetLidarStatus(LidarStatus::ERROR); - if (GetLidarErrorCode() == LIDAR_ERROR_BLOCKING) { - SetLidarErrorCode(LIDAR_ERROR_BLOCKING_AND_OCCLUSION); - } else { - SetLidarErrorCode(LIDAR_ERROR_OCCLUSION); - } - } else { - SetLidarStatus(LidarStatus::NORMAL); - SetLidarErrorCode(LIDAR_NO_ERROR); - } -} +// BUG this function is unstable . +// void LiPkg::AnalysisLidarIsBlocking(uint16_t lidar_speed_val){ +// static int16_t judge_block_cnt = 0; +// static uint16_t last_speed = 0; +// uint16_t curr_speed = lidar_speed_val; +// if ((curr_speed == 0) && (last_speed == 0)) { +// judge_block_cnt++; +// } else { +// judge_block_cnt--; +// if (judge_block_cnt <= 0) { +// judge_block_cnt = 0; +// } +// } +// if (judge_block_cnt >= 5) { +// SetLidarStatus(LidarStatus::ERROR); +// SetLidarErrorCode(LIDAR_ERROR_BLOCKING); +// } else { +// SetLidarStatus(LidarStatus::NORMAL); +// SetLidarErrorCode(LIDAR_NO_ERROR); +// } +// last_speed = curr_speed; +// } + +// BUG this function is unstable . +// void LiPkg::AnalysisLidarIsOcclusion(Points2D& lidar_data) { + +// uint16_t no_occlusion_count = 0; +// for (auto point: lidar_data) { +// if (point.distance != 0) { +// no_occlusion_count++; +// } +// } + +// if (no_occlusion_count <= 5) { +// SetLidarStatus(LidarStatus::ERROR); +// if (GetLidarErrorCode() == LIDAR_ERROR_BLOCKING) { +// SetLidarErrorCode(LIDAR_ERROR_BLOCKING_AND_OCCLUSION); +// } else { +// SetLidarErrorCode(LIDAR_ERROR_OCCLUSION); +// } +// } else { +// SetLidarStatus(LidarStatus::NORMAL); +// SetLidarErrorCode(LIDAR_NO_ERROR); +// } +// } } // namespace ldlidar diff --git a/src/linux_demo/demo.cpp b/src/linux_demo/demo.cpp index 526a174..524f4fc 100644 --- a/src/linux_demo/demo.cpp +++ b/src/linux_demo/demo.cpp @@ -28,6 +28,16 @@ uint64_t GetTimestamp(void) { return ((uint64_t)tmp.count()); } +// void LidarPowerOn(void) { +// LDS_LOG_DEBUG("Lidar Power On",""); +// // ... +// } + +// void LidarPowerOff(void) { +// LDS_LOG_DEBUG("Lidar Power Off",""); +// // ... +// } + int main(int argc, char **argv) { if (argc != 2) { @@ -38,7 +48,6 @@ int main(int argc, char **argv) { LDS_LOG_INFO("or",""); LDS_LOG_INFO("./ldlidar_sl_node /dev/ttyS0",""); exit(EXIT_FAILURE); - exit(EXIT_FAILURE); } std::string port_name(argv[1]); @@ -52,7 +61,8 @@ int main(int argc, char **argv) { node->EnableFilterAlgorithnmProcess(true); if (node->Start(ldlidar::LDType::LD_14, port_name)) { - LDS_LOG_INFO("ldldiar node start is success",""); + LDS_LOG_INFO("ldlidar node start is success",""); + // LidarPowerOn(); } else { LDS_LOG_ERROR("ldlidar node start is fail",""); exit(EXIT_FAILURE); @@ -62,7 +72,7 @@ int main(int argc, char **argv) { LDS_LOG_INFO("ldlidar communication is normal.",""); } else { LDS_LOG_ERROR("ldlidar communication is abnormal.",""); - exit(EXIT_FAILURE); + node->Stop(); } ldlidar::Points2D laser_scan_points; @@ -70,15 +80,16 @@ int main(int argc, char **argv) { switch (node->GetLaserScanData(laser_scan_points, 1500)){ case ldlidar::LidarStatus::NORMAL: { - double lidar_spin_freq = 0; - node->GetLidarSpinFreq(lidar_spin_freq); + double lidar_scan_freq = 0; + node->GetLidarScanFreq(lidar_scan_freq); #ifdef __LP64__ LDS_LOG_INFO("speed(Hz):%f, size:%d,stamp_front:%lu, stamp_back:%lu", - lidar_spin_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); + lidar_scan_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); #else LDS_LOG_INFO("speed(Hz):%f, size:%d,stamp_front:%llu, stamp_back:%llu", - lidar_spin_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); + lidar_scan_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); #endif + // output 2d point cloud data for (auto point : laser_scan_points) { #ifdef __LP64__ LDS_LOG_INFO("stamp(ns):%lu,angle:%f,distance(mm):%d,intensity:%d", @@ -90,19 +101,6 @@ int main(int argc, char **argv) { } break; } - case ldlidar::LidarStatus::ERROR: { - uint8_t errcode = node->GetLidarErrorCode(); - LDS_LOG_ERROR("ldlidar feedback errcode:%d",errcode); - if (LIDAR_ERROR_BLOCKING == errcode) { - LDS_LOG_WARN("ldlidar blocking",""); - } else if (LIDAR_ERROR_OCCLUSION == errcode) { - LDS_LOG_WARN("ldlidar occlusion",""); - } else if (LIDAR_ERROR_BLOCKING_AND_OCCLUSION == errcode) { - LDS_LOG_WARN("ldlidar blocking and occlusion",""); - } - node->Stop(); - break; - } case ldlidar::LidarStatus::DATA_TIME_OUT: { LDS_LOG_ERROR("ldlidar point cloud data publish time out, please check your lidar device.",""); node->Stop(); @@ -111,9 +109,6 @@ int main(int argc, char **argv) { case ldlidar::LidarStatus::DATA_WAIT: { break; } - case ldlidar::LidarStatus::STOP: { - break; - } default: break; } @@ -122,6 +117,7 @@ int main(int argc, char **argv) { } node->Stop(); + // LidarPowerOff(); delete node; node = nullptr; diff --git a/src/test_sys/CMakeLists.txt b/src/test_sys/CMakeLists.txt new file mode 100644 index 0000000..955eab8 --- /dev/null +++ b/src/test_sys/CMakeLists.txt @@ -0,0 +1,74 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ldlidar_sl) + +if(${CMAKE_BUILD_TYPE} MATCHES "Release") + #set(CMAKE_BUILD_TYPE "Release") + set(CMAKE_CXX_FLAGS_RELEASE "$ENV{CXXFLAGS} -std=c++11 -Wall") + #set(CMAKE_CXX_FLAGS_RELEASE "$ENV{CXXFLAGS} -std=c++11 -O3 -Wall") + message(STATUS "Mode: Release") + message(STATUS "optional:-std=c++11 -Wall") +else() + #set(CMAKE_BUILD_TYPE "Debug") + set(CMAKE_CXX_FLAGS_DEBUG "$ENV{CXXFLAGS} -std=c++11 -Wall -Wextra -Wpedantic -g2 -ggdb") + #set(CMAKE_CXX_FLAGS_DEBUG "$ENV{CXXFLAGS} -std=c++11 -O2 -Wall -Wextra -Wpedantic -g2 -ggdb") + message(STATUS "Mode: Debug") + message(STATUS "optional:-std=c++11 -Wall -Wextra -Wpedantic -g2 -ggdb") +endif() + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/include/core/ + ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/include/dataprocess/ + ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/include/filter/ + ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/include/logger/ + ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/include/serialcom/ +) + +file(GLOB LDLIDAR_DRI_CORE ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/src/core/*.cpp) +file(GLOB LDLIDAR_DRI_DATARPC ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/src/dataprocess/*.cpp) +file(GLOB LDLIDAR_DRI_FILTER ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/src/filter/*.cpp) +file(GLOB LDLIDAR_DRI_LOGGER ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/src/logger/*.cpp) +file(GLOB LDLIDAR_DRI_SERIAL ${CMAKE_CURRENT_SOURCE_DIR}/../../ldlidar_driver/src/serialcom/*.cpp) + +add_executable(${PROJECT_NAME}_node ${CMAKE_CURRENT_SOURCE_DIR}/test.cpp) + +add_library(ldlidar_driver_static STATIC + ${LDLIDAR_DRI_CORE} + ${LDLIDAR_DRI_DATARPC} + ${LDLIDAR_DRI_FILTER} + ${LDLIDAR_DRI_LOGGER} + ${LDLIDAR_DRI_SERIAL} +) + +add_library(ldlidar_driver_shared SHARED + ${LDLIDAR_DRI_CORE} + ${LDLIDAR_DRI_DATARPC} + ${LDLIDAR_DRI_FILTER} + ${LDLIDAR_DRI_LOGGER} + ${LDLIDAR_DRI_SERIAL} +) + +# rename library name +set_target_properties (ldlidar_driver_static PROPERTIES OUTPUT_NAME "ldlidar_driver") +set_target_properties (ldlidar_driver_shared PROPERTIES OUTPUT_NAME "ldlidar_driver") + +# binary file link to library +target_link_libraries(${PROJECT_NAME}_node ldlidar_driver_static pthread wiringPi) + +########### +## Install ## +########### + +INSTALL(TARGETS ldlidar_driver_static ldlidar_driver_shared + ARCHIVE DESTINATION lib/ldlidar_driver + LIBRARY DESTINATION share/ldlidar_driver +) + +INSTALL(DIRECTORY ${PROJECT_SOURCE_DIR}/ldlidar_driver/include + DESTINATION include/ldlidar_driver +) diff --git a/src/test_sys/auto_build_test.sh b/src/test_sys/auto_build_test.sh new file mode 100644 index 0000000..ed88db7 --- /dev/null +++ b/src/test_sys/auto_build_test.sh @@ -0,0 +1,21 @@ +#!/bin/bash +#Author: David Hu +#Date: 2022-09 + +# Exit on error +set -e + +echo "Start cmake build" + +if [ ! -e "./build" ];then + mkdir build + echo "create ./build/" +fi + +cd ./build + +cmake -DCMAKE_BUILD_TYPE=Debug .. + +make -j2 + +echo "build finished." \ No newline at end of file diff --git a/src/test_sys/clean_build.sh b/src/test_sys/clean_build.sh new file mode 100644 index 0000000..d58f6d7 --- /dev/null +++ b/src/test_sys/clean_build.sh @@ -0,0 +1,14 @@ +#!/bin/bash +#Author: David Hu +#Date: 2022-09 +if [ -e "./build" ];then + rm -rf build/ + echo "del ./build/" +fi + +if [ -e "./install" ];then + rm -rf install/ + echo "del ./install/" +fi + +echo "del is ok....." \ No newline at end of file diff --git a/src/test_sys/test.cpp b/src/test_sys/test.cpp new file mode 100644 index 0000000..de9ffcb --- /dev/null +++ b/src/test_sys/test.cpp @@ -0,0 +1,182 @@ +/** + * @file test.cpp + * @author LDRobot (support@ldrobot.com) + * @brief sdk function test + * This code is only applicable to LDROBOT LiDAR LD00 LD03 LD08 LD14 + * products sold by Shenzhen LDROBOT Co., LTD + * @version 0.1 + * @date 2021-11-08 + * + * @copyright Copyright (c) 2021 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * 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. + */ + +#include "ldlidar_driver.h" +#include + +uint64_t GetTimestamp(void) { + std::chrono::time_point tp = + std::chrono::time_point_cast(std::chrono::system_clock::now()); + auto tmp = std::chrono::duration_cast(tp.time_since_epoch()); + return ((uint64_t)tmp.count()); +} + +bool ControlPinInit(void) { + // raspberrypi wiringPi GPIO Init + if(wiringPiSetup() == -1) { + return false; + } + pinMode(25,OUTPUT); // set wiringPi 25 Pin number is outuput Mode. + return true; +} + +void LidarPowerOn(void) { + LDS_LOG_DEBUG("Lidar Power On",""); + digitalWrite(25,HIGH); +} + +void LidarPowerOff(void) { + LDS_LOG_DEBUG("Lidar Power Off",""); + digitalWrite(25,LOW); +} + +void AbortTesting(void) { + LDS_LOG_WARN("Testing abort",""); + LidarPowerOff(); + exit(EXIT_FAILURE); +} + +int function_main(int argc, char **argv) { + + if (argc != 2) { + LDS_LOG_INFO("cmd error",""); + LDS_LOG_INFO("please input: ./ldlidar_sl_node ",""); + LDS_LOG_INFO("example:",""); + LDS_LOG_INFO("./ldlidar_sl_node /dev/ttyUSB0",""); + LDS_LOG_INFO("or",""); + LDS_LOG_INFO("./ldlidar_sl_node /dev/ttyS0",""); + exit(EXIT_FAILURE); + } + + std::string port_name(argv[1]); + + ldlidar::LDLidarDriver* node = new ldlidar::LDLidarDriver(); + + LDS_LOG_INFO("LDLiDAR SDK Pack Version is %s", node->GetLidarSdkVersionNumber().c_str()); + + node->RegisterGetTimestampFunctional(std::bind(&GetTimestamp)); + + node->EnableFilterAlgorithnmProcess(true); + + if (node->Start(ldlidar::LDType::LD_14, port_name)) { + LDS_LOG_INFO("ldlidar node start is success",""); + LidarPowerOn(); + } else { + LDS_LOG_ERROR("ldlidar node start is fail",""); + exit(EXIT_FAILURE); + } + + if (node->WaitLidarCommConnect(3500)) { + LDS_LOG_INFO("ldlidar communication is normal.",""); + } else { + LDS_LOG_ERROR("ldlidar communication is abnormal.",""); + AbortTesting(); + } + + ldlidar::Points2D laser_scan_points; + int cnt = 100; + while (ldlidar::LDLidarDriver::IsOk()) { + if ((cnt--) <= 0) { + node->Stop(); + } + + switch (node->GetLaserScanData(laser_scan_points, 1500)){ + case ldlidar::LidarStatus::NORMAL: { + double lidar_scan_freq = 0; + node->GetLidarScanFreq(lidar_scan_freq); + +#ifdef __LP64__ + LDS_LOG_INFO("speed(Hz):%f,size:%d,stamp_front:%lu, stamp_back:%lu", + lidar_scan_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); +#else + LDS_LOG_INFO("speed(Hz):%f,size:%d,stamp_front:%llu, stamp_back:%llu", + lidar_scan_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); +#endif + + if (laser_scan_points.front().stamp >= laser_scan_points.back().stamp) { + LDS_LOG_ERROR("timestamp error!",""); + node->Stop(); + AbortTesting(); + } + + int distance_zero_point_cnt = 0; + for (auto point : laser_scan_points) { + if (0 == point.distance) { + distance_zero_point_cnt++; + } + } + + if (distance_zero_point_cnt >= (int)laser_scan_points.size()) { + LDS_LOG_ERROR("a frame distance is zero value",""); + node->Stop(); + AbortTesting(); + } + + break; + } + case ldlidar::LidarStatus::DATA_TIME_OUT: { + LDS_LOG_ERROR("ldlidar point cloud data publish time out, please check your lidar device.",""); + node->Stop(); + AbortTesting(); + break; + } + case ldlidar::LidarStatus::DATA_WAIT: { + break; + } + default: + break; + } + + usleep(1000*166); // sleep 166ms , 6hz + } + + node->Stop(); + LidarPowerOff(); + sleep(3); + + delete node; + node = nullptr; + + return 0; +} + +int main(int argc, char** argv) { + + if (!ControlPinInit()) { + LDS_LOG_ERROR("Control pin Setup failed.",""); + exit(EXIT_FAILURE); + } + + for (int i = 0; i < 10000; i++) { + function_main(argc, argv); + } + + LDS_LOG_INFO("test is end.",""); + while (1) { + sleep(1); + } + + return 0; +} + + +/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF + * FILE ********/