Skip to content

Commit

Permalink
[update]版本号v2.3.0,更改点为:
Browse files Browse the repository at this point in the history
1. 优化代码框架,增加名空间,优化头文件包含;
2. 增加互斥锁,防止多线程中共享资源产生竞争;
3. 增加usb设备 rules配置文件
4. 串口接收buffer大小改为4K
5. 增加发布超时检测,应对设备退出或发布异常
  • Loading branch information
ldrobotsensor committed Jun 2, 2022
1 parent ec5c2fc commit 934de0c
Show file tree
Hide file tree
Showing 20 changed files with 679 additions and 532 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
*.json
17 changes: 0 additions & 17 deletions .vscode/c_cpp_properties.json

This file was deleted.

5 changes: 0 additions & 5 deletions .vscode/settings.json

This file was deleted.

9 changes: 7 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,13 @@ if(BUILD_TESTING)
endif()

# Bin and Install
file(GLOB MAIN_SRC ${CMAKE_CURRENT_SOURCE_DIR}/src/*.cpp)
add_executable(${PROJECT_NAME}_node ${MAIN_SRC})
include_directories(
${CMAKE_CURRENT_SOURCE_DIR}/include
${CMAKE_CURRENT_SOURCE_DIR}/include/ldlidar_driver/include
)

file(GLOB DRIVER_SRC ${CMAKE_CURRENT_SOURCE_DIR}/include/ldlidar_driver/*.cpp)
add_executable(${PROJECT_NAME}_node ${CMAKE_CURRENT_SOURCE_DIR}/src/demo.cpp ${DRIVER_SRC})
ament_target_dependencies(${PROJECT_NAME}_node rclcpp sensor_msgs)
target_link_libraries(${PROJECT_NAME}_node pthread)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file cmd_interface_linux.cpp
* @author LDRobot (marketing1@ldrobot.com)
* @author LDRobot (support@ldrobot.com)
* @brief linux serial port App
* @version 0.1
* @date 2021-10-28
Expand All @@ -19,17 +19,9 @@

#include "cmd_interface_linux.h"

#include <errno.h>
#include <fcntl.h>
#include <memory.h>
#include <string.h>
#include <sys/file.h>
#include <termios.h>
#include <unistd.h>
namespace ldlidar {

#include <iostream>

#define MAX_ACK_BUF_LEN 2304000
#define MAX_ACK_BUF_LEN 4096

CmdInterfaceLinux::CmdInterfaceLinux()
: rx_thread_(nullptr), rx_count_(0), read_callback_(nullptr) {
Expand All @@ -55,8 +47,8 @@ bool CmdInterfaceLinux::Open(std::string &port_name) {
return false;
}

options.c_cflag |= (tcflag_t)(CLOCAL | CREAD | CS8 | CRTSCTS);
options.c_cflag &= (tcflag_t) ~(CSTOPB | PARENB | PARODD);
options.c_cflag |= (tcflag_t)(CLOCAL | CREAD | CS8);
options.c_cflag &= (tcflag_t) ~(CSTOPB | PARENB);
options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
ISIG | IEXTEN); //|ECHOPRT
options.c_oflag &= (tcflag_t) ~(OPOST);
Expand Down Expand Up @@ -166,5 +158,7 @@ void CmdInterfaceLinux::RxThreadProc(void *param) {
delete[] rx_buf;
}

}

/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF
* FILE ********/
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file cmd_interface_linux.h
* @author LDRobot (marketing1@ldrobot.com)
* @author LDRobot (support@ldrobot.com)
* @brief linux serial port App
* @version 0.1
* @date 2021-10-28
Expand All @@ -21,8 +21,15 @@
#define __LINUX_SERIAL_PORT_H__

#include <inttypes.h>
#include <errno.h>
#include <fcntl.h>
#include <memory.h>
#include <string.h>
#include <sys/file.h>
#include <termios.h>
#include <unistd.h>

#include <iostream>
#include <atomic>
#include <condition_variable>
#include <functional>
Expand All @@ -31,6 +38,8 @@
#include <thread>
#include <vector>

namespace ldlidar {

class CmdInterfaceLinux {
public:
CmdInterfaceLinux();
Expand Down Expand Up @@ -59,6 +68,8 @@ class CmdInterfaceLinux {
static void RxThreadProc(void *param);
};

} // namespace ldlidar

#endif //__LINUX_SERIAL_PORT_H__

/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF
Expand Down
107 changes: 61 additions & 46 deletions src/lipkg.h → include/ldlidar_driver/include/lipkg.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file lipkg.h
* @author LDRobot (marketing1@ldrobot.com)
* @author LDRobot (support@ldrobot.com)
* @brief LiDAR data protocol processing App
* This code is only applicable to LDROBOT LiDAR LD06 products
* sold by Shenzhen LDROBOT Co., LTD
Expand All @@ -22,15 +22,13 @@
#ifndef __LIPKG_H
#define __LIPKG_H

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <stdint.h>

#include <array>
#include <iostream>
#include <vector>
#include <chrono>

#include "pointdata.h"
#include "tofbf.h"
#include "cmd_interface_linux.h"

namespace ldlidar {

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

class LiPkg {
public:
LiPkg(rclcpp::Node::SharedPtr& node, std::string frame_id, bool laser_scan_dir, bool enable_angle_crop_func,
double angle_crop_min, double angle_crop_max);
// get Lidar spin speed (Hz)
double GetSpeed(void);
// get time stamp of the packet
uint16_t GetTimestamp(void) { return timestamp_; }
// a packet is ready
bool IsPkgReady(void) { return is_pkg_ready_; }
// Get lidar data frame ready flag
bool IsFrameReady(void) { return is_frame_ready_; }
// Lidar data frame readiness flag reset
void ResetFrameReady(void) { is_frame_ready_ = false; }
// the number of errors in parser process of lidar data frame
long GetErrorTimes(void) { return error_times_; }
// Get original Lidar data package
const std::array<PointData, POINT_PER_PACK>& GetPkgData(void);
// parse single packet
bool AnalysisOne(uint8_t byte);
bool Parse(const uint8_t* data, long len);
// combine stantard data into data frames and calibrate
bool AssemblePacket();
// Get ros2 laserscan type data
sensor_msgs::msg::LaserScan GetLaserScan() { return output_; }
const int kPointFrequence = 4500;

LiPkg();
~LiPkg();
/**
* @brief get sdk pack version number
*/
std::string GetSdkPackVersionNum(void) const;
/**
* @brief get Lidar spin speed (Hz)
*/
double GetSpeed(void);
/**
* @brief get lidar spind speed (degree per second) origin
*/
uint16_t GetSpeedOrigin(void);
/**
* @brief get time stamp of the packet
*/
uint16_t GetTimestamp(void);
/**
* @brief Get lidar data frame ready flag
*/
bool IsFrameReady(void);
/**
* @brief Lidar data frame readiness flag reset
*/
void ResetFrameReady(void);
/**
* @brief the number of errors in parser process of lidar data frame
*/
long GetErrorTimes(void);
/**
* @brief comm data read callback handle
*/
void CommReadCallback(const char *byte, size_t len);
/**
* @brief get lidar scan point cloud data
*/
Points2D GetLaserScanData(void);

private:
const int kPointFrequence = 4500;
rclcpp::Node::SharedPtr& node_;
std::string frame_id_;
std::string sdk_pack_version_;
uint16_t timestamp_;
double speed_;
long error_times_;
bool is_frame_ready_;
bool is_pkg_ready_;
bool laser_scan_dir_;
bool enable_angle_crop_func_;
double angle_crop_min_;
double angle_crop_max_;
LiDARFrameTypeDef pkg;
std::vector<uint8_t> data_tmp_;
std::array<PointData, POINT_PER_PACK> one_pkg_;
std::vector<PointData> frame_tmp_;
sensor_msgs::msg::LaserScan output_;
// Lidar frame data tranfrom to ros2 laserscan type data
void ToLaserscan(std::vector<PointData> src);

LiDARFrameTypeDef pkg_;
Points2D frame_tmp_;
Points2D laser_scan_data_;
std::mutex mutex_lock1_;
std::mutex mutex_lock2_;

bool AnalysisOne(uint8_t byte);
bool Parse(const uint8_t* data, long len);
bool AssemblePacket();
void SetLaserScanData(Points2D& src);
void SetFrameReady(void);
};

} // namespace ldlidar

#endif //__LIPKG_H

/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF
Expand Down
10 changes: 7 additions & 3 deletions src/pointdata.h → include/ldlidar_driver/include/pointdata.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file pointdata.h
* @author LDRobot (marketing1@ldrobot.com)
* @author LDRobot (support@ldrobot.com)
* @brief lidar point data structure
* This code is only applicable to LDROBOT products
* sold by Shenzhen LDROBOT Co., LTD
Expand All @@ -26,6 +26,11 @@
#include <iostream>
#include <vector>

namespace ldlidar {

#define ANGLE_TO_RADIAN(angle) ((angle)*3141.59 / 180000)
#define RADIAN_TO_ANGLED(angle) ((angle)*180000 / 3141.59)

struct PointData {
// Polar coordinate representation
float angle; // Angle ranges from 0 to 359 degrees
Expand All @@ -52,8 +57,7 @@ struct PointData {

typedef std::vector<PointData> Points2D;

#define ANGLE_TO_RADIAN(angle) ((angle)*3141.59 / 180000)
#define RADIAN_TO_ANGLED(angle) ((angle)*180000 / 3141.59)
} // namespace ldlidar

#endif // _POINT_DATA_H_

Expand Down
12 changes: 8 additions & 4 deletions src/tofbf.h → include/ldlidar_driver/include/tofbf.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file tofbf.h
* @author LDRobot (marketing1@ldrobot.com)
* @author LDRobot (support@ldrobot.com)
* @brief LiDAR near-range filtering algorithm
* This code is only applicable to LDROBOT LiDAR LD06 products
* sold by Shenzhen LDROBOT Co., LTD
Expand All @@ -22,11 +22,13 @@
#ifndef __TOFBF_H_
#define __TOFBF_H_

#include <stdint.h>
#include <math.h>

#include <vector>
#include <algorithm>

#include "lipkg.h"
#include "pointdata.h"

namespace ldlidar {

class Tofbf {
private:
Expand All @@ -45,6 +47,8 @@ class Tofbf {
~Tofbf();
};

} // namespace ldlidar

#endif //__TOFBF_H_

/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF
Expand Down
Loading

0 comments on commit 934de0c

Please sign in to comment.