rslidar_SDK代码二开注意事项
0.下载地址
【github】https://github.com/RoboSense-LiDAR/rslidar_sdk
1.CMakeLists.txt
1.1 Cmake里面,首先选择编译方式,原始ORIGINAL还是CATKIN,还是COLCON
#=======================================
# Compile setup (ORIGINAL, CATKIN, COLCON)
#=======================================
set(COMPILE_METHOD CATKIN)
#Catkin#
if(${COMPILE_METHOD} STREQUAL "CATKIN")
add_definitions(-DRUN_IN_ROS_WORKSPACE)
find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
roslib
pcl_ros
pcl_conversions)
catkin_package(CATKIN_DEPENDS
sensor_msgs
roslib
pcl_ros
pcl_conversions)
endif(${COMPILE_METHOD} STREQUAL "CATKIN")
1.2 增加新增cpp文件位置
aux_source_directory(src/utility/ APP_DIR_SRCS)
# add_executable 增加对应文件夹
add_executable(rslidar_sdk_node
node/rslidar_sdk_node.cpp
src/manager/adapter_manager.cpp
${PROTO_FILE_PATH}/packet.pb.cc
${PROTO_FILE_PATH}/scan.pb.cc
${PROTO_FILE_PATH}/point_cloud.pb.cc
${APP_DIR_SRCS}
)
1.3 如果选择ORIGINAL模式,需要额外增加ROS包
if(${COMPILE_METHOD} STREQUAL "ORIGINAL")
add_definitions(-DRUN_IN_ORIGINAL)
find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
roslib
pcl_ros
pcl_conversions)
endif(${COMPILE_METHOD} STREQUAL "ORIGINAL")
1.4 由于rslidar_sdk项目中包含子模块驱动内核rs_driver, 因此在执行git clone 后还需要执行相关指令初始化并更新子模块。
git clone https://github.com/RoboSense-LiDAR/rslidar_sdk.git
cd rslidar_sdk
git submodule init
git submodule update
下载完毕之后,rs_driver文件夹下会有对应的代码,CMakeLists.txt中添加啦rs_dirver作为子模块添加到工程内。
使用find_package()指令找到rs_driver,然后链接相关库
add_subdirectory(${PROJECT_SOURCE_DIR}/rs_driver)
find_package(rs_driver REQUIRED)
include_directories(${rs_driver_INCLUDE_DIRS})
target_link_libraries(project ${rs_driver_LIBRARIES})
1.5 直接编译
按照如下指令即可编译运行程序。 直接编译也可以使用ROS相关功能(不包括ROS2),但需要在程序启动前手动启动roscore,启动后手动打开rviz才能看到可视化点云结果。
cd rslidar_sdk
mkdir build && cd build
cmake .. && make -j4
./rslidar_sdk_node
1.6 增加自定义点字段的点类型
#=======================================
# Custom Point Type (XYZI, XYZIRT, XYZITD)
#=======================================
set(POINT_TYPE XYZITD)
在 /src/msg/rs_msg/lidar_point_cloud_msg.h 文件中,新增点类型
struct RandyPointXYZITD
{
PCL_ADD_POINT4D;
uint8_t intensity;
double timestamp = 0;
uint8_t id = '0';
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
POINT_CLOUD_REGISTER_POINT_STRUCT(RandyPointXYZITD,
(float, x, x)
(float, y, y)
(float, z, z)
(uint8_t, intensity, intensity)
(double, timestamp, timestamp)
(uint8_t, id, id))
#ifdef POINT_TYPE_XYZI
typedef pcl::PointXYZI PointT;
#elif POINT_TYPE_XYZIRT
typedef PointXYZIRT PointT;
#elif POINT_TYPE_XYZITD
typedef RandyPointXYZITD PointT;
#endif
1.7 若使用PCL点云,增加PCL库
find_package(PCL QUIET REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
target_link_libraries(randylife
${PCL_LIBRARIES}
${YAML_CPP_LIBRARIES}
${rs_driver_LIBRARIES}
${PROTOBUF_LIBRARY}
${catkin_LIBRARIES}
${rosbag_LIBRARIES}
yaml-cpp)
2.隐藏功能
隐藏功能可参考代码中说明文档:doc/intro/hiding_parameters_intro_cn.md
2.1 pcap重复播报参数配置
yaml中默认没有`pcap_repeat = true`配置项,需要手工添加,代码中默认true
common:
msg_source: 1
send_packet_ros: false
send_point_cloud_ros: false
send_packet_proto: false
send_point_cloud_proto: false
pcap_path: /home/robosense/lidar.pcap
pcap_repeat: true
pcap_rate: 1
pcap_rate -- 默认值为1,点云频率约为10hz。 用户可调节此参数来控制pcap播放速度,设置的值越大,pcap播放速度越快。
2.2 坐标转换功能(点云标定)
提供了内置的坐标变换功能,可以直接输出经过坐标变换后的点云,显著节省了对点云进行坐标变换的操作耗时,可输出经过坐标变换后的点云。
默认参数也是不显示,需要手动添加
x, y, z, roll, pitch, yaw -- 坐标变换参数,若启用了内核的坐标变换功能,将会使用此参数输出经过变换后的点云。x, y, z, 单位为
米, roll, pitch, yaw, 单位为
弧度。
common:
msg_source: 1
send_packet_ros: false
send_point_cloud_ros: true
send_packet_proto: false
send_point_cloud_proto: false
pcap_path: /home/QCJ/lidar.pcap
lidar:
- driver:
lidar_type: RSM1
frame_id: /randylidar
msop_port: 0213
difop_port: 0122
start_angle: 0
end_angle: 360
min_distance: 0.2
max_distance: 200
use_lidar_clock: false
# 增加标定参数
x: 1.8
y: 0.8
z: 2.8
roll: 0.8
pitch: 0.8
yaw: 1.58
ros:
ros_recv_packet_topic: /randylidar_packets #Topic used to receive lidar packets from ROS
ros_send_packet_topic: /randylidar_packets #Topic used to send lidar packets through ROS
ros_send_point_cloud_topic: /randylidar_points #Topic used to send point cloud through ROS
具体使用方式可以参考 坐标变换功能(../howto/how_to_use_coordinate_transformation_cn.md
) 。
编译时需要增加编译参数:
cmake -DENABLE_TRANSFORM=ON ..
make -j4
3. 1.3.10版本结构
rslidar-类关系
初始化流程
创建适配器
创建传输器
读取pcap过程
最新版本增加了读取 速腾M2雷达pcap数据功能,敬请后续更新。
欢迎关注公众号【三戒纪元】