Skip to content

Commit 934de0c

Browse files
author
DavidHu
committed
[update]版本号v2.3.0,更改点为:
1. 优化代码框架,增加名空间,优化头文件包含; 2. 增加互斥锁,防止多线程中共享资源产生竞争; 3. 增加usb设备 rules配置文件 4. 串口接收buffer大小改为4K 5. 增加发布超时检测,应对设备退出或发布异常
1 parent ec5c2fc commit 934de0c

20 files changed

Lines changed: 679 additions & 532 deletions

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
*.json

.vscode/c_cpp_properties.json

Lines changed: 0 additions & 17 deletions
This file was deleted.

.vscode/settings.json

Lines changed: 0 additions & 5 deletions
This file was deleted.

CMakeLists.txt

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,13 @@ if(BUILD_TESTING)
3232
endif()
3333

3434
# Bin and Install
35-
file(GLOB MAIN_SRC ${CMAKE_CURRENT_SOURCE_DIR}/src/*.cpp)
36-
add_executable(${PROJECT_NAME}_node ${MAIN_SRC})
35+
include_directories(
36+
${CMAKE_CURRENT_SOURCE_DIR}/include
37+
${CMAKE_CURRENT_SOURCE_DIR}/include/ldlidar_driver/include
38+
)
39+
40+
file(GLOB DRIVER_SRC ${CMAKE_CURRENT_SOURCE_DIR}/include/ldlidar_driver/*.cpp)
41+
add_executable(${PROJECT_NAME}_node ${CMAKE_CURRENT_SOURCE_DIR}/src/demo.cpp ${DRIVER_SRC})
3742
ament_target_dependencies(${PROJECT_NAME}_node rclcpp sensor_msgs)
3843
target_link_libraries(${PROJECT_NAME}_node pthread)
3944

src/cmd_interface_linux.cpp renamed to include/ldlidar_driver/cmd_interface_linux.cpp

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**
22
* @file cmd_interface_linux.cpp
3-
* @author LDRobot (marketing1@ldrobot.com)
3+
* @author LDRobot (support@ldrobot.com)
44
* @brief linux serial port App
55
* @version 0.1
66
* @date 2021-10-28
@@ -19,17 +19,9 @@
1919

2020
#include "cmd_interface_linux.h"
2121

22-
#include <errno.h>
23-
#include <fcntl.h>
24-
#include <memory.h>
25-
#include <string.h>
26-
#include <sys/file.h>
27-
#include <termios.h>
28-
#include <unistd.h>
22+
namespace ldlidar {
2923

30-
#include <iostream>
31-
32-
#define MAX_ACK_BUF_LEN 2304000
24+
#define MAX_ACK_BUF_LEN 4096
3325

3426
CmdInterfaceLinux::CmdInterfaceLinux()
3527
: rx_thread_(nullptr), rx_count_(0), read_callback_(nullptr) {
@@ -55,8 +47,8 @@ bool CmdInterfaceLinux::Open(std::string &port_name) {
5547
return false;
5648
}
5749

58-
options.c_cflag |= (tcflag_t)(CLOCAL | CREAD | CS8 | CRTSCTS);
59-
options.c_cflag &= (tcflag_t) ~(CSTOPB | PARENB | PARODD);
50+
options.c_cflag |= (tcflag_t)(CLOCAL | CREAD | CS8);
51+
options.c_cflag &= (tcflag_t) ~(CSTOPB | PARENB);
6052
options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
6153
ISIG | IEXTEN); //|ECHOPRT
6254
options.c_oflag &= (tcflag_t) ~(OPOST);
@@ -166,5 +158,7 @@ void CmdInterfaceLinux::RxThreadProc(void *param) {
166158
delete[] rx_buf;
167159
}
168160

161+
}
162+
169163
/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF
170164
* FILE ********/

src/cmd_interface_linux.h renamed to include/ldlidar_driver/include/cmd_interface_linux.h

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**
22
* @file cmd_interface_linux.h
3-
* @author LDRobot (marketing1@ldrobot.com)
3+
* @author LDRobot (support@ldrobot.com)
44
* @brief linux serial port App
55
* @version 0.1
66
* @date 2021-10-28
@@ -21,8 +21,15 @@
2121
#define __LINUX_SERIAL_PORT_H__
2222

2323
#include <inttypes.h>
24+
#include <errno.h>
25+
#include <fcntl.h>
26+
#include <memory.h>
2427
#include <string.h>
28+
#include <sys/file.h>
29+
#include <termios.h>
30+
#include <unistd.h>
2531

32+
#include <iostream>
2633
#include <atomic>
2734
#include <condition_variable>
2835
#include <functional>
@@ -31,6 +38,8 @@
3138
#include <thread>
3239
#include <vector>
3340

41+
namespace ldlidar {
42+
3443
class CmdInterfaceLinux {
3544
public:
3645
CmdInterfaceLinux();
@@ -59,6 +68,8 @@ class CmdInterfaceLinux {
5968
static void RxThreadProc(void *param);
6069
};
6170

71+
} // namespace ldlidar
72+
6273
#endif //__LINUX_SERIAL_PORT_H__
6374

6475
/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF

src/lipkg.h renamed to include/ldlidar_driver/include/lipkg.h

Lines changed: 61 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**
22
* @file lipkg.h
3-
* @author LDRobot (marketing1@ldrobot.com)
3+
* @author LDRobot (support@ldrobot.com)
44
* @brief LiDAR data protocol processing App
55
* This code is only applicable to LDROBOT LiDAR LD06 products
66
* sold by Shenzhen LDROBOT Co., LTD
@@ -22,15 +22,13 @@
2222
#ifndef __LIPKG_H
2323
#define __LIPKG_H
2424

25-
#include <rclcpp/rclcpp.hpp>
26-
#include <sensor_msgs/msg/laser_scan.hpp>
27-
#include <stdint.h>
28-
29-
#include <array>
30-
#include <iostream>
31-
#include <vector>
25+
#include <chrono>
3226

3327
#include "pointdata.h"
28+
#include "tofbf.h"
29+
#include "cmd_interface_linux.h"
30+
31+
namespace ldlidar {
3432

3533
enum {
3634
PKG_HEADER = 0x54,
@@ -56,52 +54,69 @@ typedef struct __attribute__((packed)) {
5654

5755
class LiPkg {
5856
public:
59-
LiPkg(rclcpp::Node::SharedPtr& node, std::string frame_id, bool laser_scan_dir, bool enable_angle_crop_func,
60-
double angle_crop_min, double angle_crop_max);
61-
// get Lidar spin speed (Hz)
62-
double GetSpeed(void);
63-
// get time stamp of the packet
64-
uint16_t GetTimestamp(void) { return timestamp_; }
65-
// a packet is ready
66-
bool IsPkgReady(void) { return is_pkg_ready_; }
67-
// Get lidar data frame ready flag
68-
bool IsFrameReady(void) { return is_frame_ready_; }
69-
// Lidar data frame readiness flag reset
70-
void ResetFrameReady(void) { is_frame_ready_ = false; }
71-
// the number of errors in parser process of lidar data frame
72-
long GetErrorTimes(void) { return error_times_; }
73-
// Get original Lidar data package
74-
const std::array<PointData, POINT_PER_PACK>& GetPkgData(void);
75-
// parse single packet
76-
bool AnalysisOne(uint8_t byte);
77-
bool Parse(const uint8_t* data, long len);
78-
// combine stantard data into data frames and calibrate
79-
bool AssemblePacket();
80-
// Get ros2 laserscan type data
81-
sensor_msgs::msg::LaserScan GetLaserScan() { return output_; }
57+
const int kPointFrequence = 4500;
8258

59+
LiPkg();
60+
~LiPkg();
61+
/**
62+
* @brief get sdk pack version number
63+
*/
64+
std::string GetSdkPackVersionNum(void) const;
65+
/**
66+
* @brief get Lidar spin speed (Hz)
67+
*/
68+
double GetSpeed(void);
69+
/**
70+
* @brief get lidar spind speed (degree per second) origin
71+
*/
72+
uint16_t GetSpeedOrigin(void);
73+
/**
74+
* @brief get time stamp of the packet
75+
*/
76+
uint16_t GetTimestamp(void);
77+
/**
78+
* @brief Get lidar data frame ready flag
79+
*/
80+
bool IsFrameReady(void);
81+
/**
82+
* @brief Lidar data frame readiness flag reset
83+
*/
84+
void ResetFrameReady(void);
85+
/**
86+
* @brief the number of errors in parser process of lidar data frame
87+
*/
88+
long GetErrorTimes(void);
89+
/**
90+
* @brief comm data read callback handle
91+
*/
92+
void CommReadCallback(const char *byte, size_t len);
93+
/**
94+
* @brief get lidar scan point cloud data
95+
*/
96+
Points2D GetLaserScanData(void);
97+
8398
private:
84-
const int kPointFrequence = 4500;
85-
rclcpp::Node::SharedPtr& node_;
86-
std::string frame_id_;
99+
std::string sdk_pack_version_;
87100
uint16_t timestamp_;
88101
double speed_;
89102
long error_times_;
90103
bool is_frame_ready_;
91-
bool is_pkg_ready_;
92-
bool laser_scan_dir_;
93-
bool enable_angle_crop_func_;
94-
double angle_crop_min_;
95-
double angle_crop_max_;
96-
LiDARFrameTypeDef pkg;
97-
std::vector<uint8_t> data_tmp_;
98-
std::array<PointData, POINT_PER_PACK> one_pkg_;
99-
std::vector<PointData> frame_tmp_;
100-
sensor_msgs::msg::LaserScan output_;
101-
// Lidar frame data tranfrom to ros2 laserscan type data
102-
void ToLaserscan(std::vector<PointData> src);
104+
105+
LiDARFrameTypeDef pkg_;
106+
Points2D frame_tmp_;
107+
Points2D laser_scan_data_;
108+
std::mutex mutex_lock1_;
109+
std::mutex mutex_lock2_;
110+
111+
bool AnalysisOne(uint8_t byte);
112+
bool Parse(const uint8_t* data, long len);
113+
bool AssemblePacket();
114+
void SetLaserScanData(Points2D& src);
115+
void SetFrameReady(void);
103116
};
104117

118+
} // namespace ldlidar
119+
105120
#endif //__LIPKG_H
106121

107122
/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF

src/pointdata.h renamed to include/ldlidar_driver/include/pointdata.h

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**
22
* @file pointdata.h
3-
* @author LDRobot (marketing1@ldrobot.com)
3+
* @author LDRobot (support@ldrobot.com)
44
* @brief lidar point data structure
55
* This code is only applicable to LDROBOT products
66
* sold by Shenzhen LDROBOT Co., LTD
@@ -26,6 +26,11 @@
2626
#include <iostream>
2727
#include <vector>
2828

29+
namespace ldlidar {
30+
31+
#define ANGLE_TO_RADIAN(angle) ((angle)*3141.59 / 180000)
32+
#define RADIAN_TO_ANGLED(angle) ((angle)*180000 / 3141.59)
33+
2934
struct PointData {
3035
// Polar coordinate representation
3136
float angle; // Angle ranges from 0 to 359 degrees
@@ -52,8 +57,7 @@ struct PointData {
5257

5358
typedef std::vector<PointData> Points2D;
5459

55-
#define ANGLE_TO_RADIAN(angle) ((angle)*3141.59 / 180000)
56-
#define RADIAN_TO_ANGLED(angle) ((angle)*180000 / 3141.59)
60+
} // namespace ldlidar
5761

5862
#endif // _POINT_DATA_H_
5963

src/tofbf.h renamed to include/ldlidar_driver/include/tofbf.h

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**
22
* @file tofbf.h
3-
* @author LDRobot (marketing1@ldrobot.com)
3+
* @author LDRobot (support@ldrobot.com)
44
* @brief LiDAR near-range filtering algorithm
55
* This code is only applicable to LDROBOT LiDAR LD06 products
66
* sold by Shenzhen LDROBOT Co., LTD
@@ -22,11 +22,13 @@
2222
#ifndef __TOFBF_H_
2323
#define __TOFBF_H_
2424

25-
#include <stdint.h>
25+
#include <math.h>
2626

27-
#include <vector>
27+
#include <algorithm>
2828

29-
#include "lipkg.h"
29+
#include "pointdata.h"
30+
31+
namespace ldlidar {
3032

3133
class Tofbf {
3234
private:
@@ -45,6 +47,8 @@ class Tofbf {
4547
~Tofbf();
4648
};
4749

50+
} // namespace ldlidar
51+
4852
#endif //__TOFBF_H_
4953

5054
/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF

0 commit comments

Comments
 (0)