Livox格式的rosbag转为PointCloud2格式
参考文章前两篇是CSDN的,又一次让我见识到CSDN的Blog质量之低了。
写这篇文章的目的,是Livox LiDAR发布的格式是CustomMsg,没有办法用rviz直接可视化,必须重新发布为PointCloud2格式或者使用C++通过driver直接解析。
安装
先编译并安装Livox的SDK:
git clone https://github.com/Livox-SDK/Livox-SDK.git
mkdir build
cd build
cmake .. && make
sudo make install -j8
然后下载Livox的Driver:
git clone https://github.com/Livox-SDK/livox_ros_driver.git ws_livox/src
这里已经创建好 ws_livox/src
这个文件夹,并且把 livox_ros_driver
作为功能包 clone
下来了。
然后, 进入 src
并下载repub的功能包:
git clone https://github.com/jianfee/livox_repub.git
返回 ws_livox
工作空间目录并编译:
catkin_make
最终 ws_livox
文件夹结构应该是这样的, build
和 devel
两个文件夹的内容是编译自动产生的, 被我略去。
(cv) jetson@funnywii-orin:~/Documents/LiDAR/ws_livox$ tree -L 2
.
├── build
├── devel
└── src
├── CMakeLists.txt -> /opt/ros/noetic/share/catkin/cmake/toplevel.cmake
├── images
├── LICENSE.txt
├── livox_repub
├── livox_ros_driver
├── README_CN.md
└── README.md
然后在 ws_livox
目录下执行:
source devel/setup.bash
roslaunch livox_repub livox_repub.launch
运行
首先播放Livox的rosbag,其 rostopic
为 /livox/lidar
,repub出来的新话题为 /livox_pcl0
。
然后打开rviz,修改话题为 /livox_pcl0
,修改Fixed Frame为 /livox
。即可看到PointCloud2格式的点云。
最后用ros录制 /livox_pcl0
为话题的点云即可。
订阅代码
如果是想直接使用C++订阅Livox发布的点云,也是可行的,但是也要安装好上面提到的SDK和包。
首先修改CMakeLists:
find_package(catkin REQUIRED COMPONENTS
message_generation
message_runtime
roscpp
rospy
std_msgs
sensor_msgs
livox_ros_driver # 增加这一行
)
然后引用头文件:
#include "livox_ros_driver/CustomMsg.h"
C++回调函数:
bool awaken_detect_ = true;
void LidarCallback(const livox_ros_driver::CustomMsgConstPtr msg) {
if (awaken_detect_ == true) {
pcl::PointCloud<pcl::PointXYZI>::Ptr input_lidar_cloud(new pcl::PointCloud<pcl::PointXYZI>);
for (unsigned int i = 0; i < msg->point_num; ++i) {
pcl::PointXYZI pointxyzi;
pointxyzi.x = msg->points[i].x;
pointxyzi.y = msg->points[i].y;
pointxyzi.z = msg->points[i].z;
pointxyzi.intensity = ((int)msg->points[i].reflectivity) / 255.0;
(*input_lidar_cloud).push_back(pointxyzi);
}
std::cout << "Lidar point cloud size: " << input_lidar_cloud->size() << std::endl;
}
}
需要注意的是,在编译之前要先 source
一下 livox_ros_driver
和 livox_repub
工作空间的 setup.bash
然后 catkin_make
编译代码即可。
参考文章
[1] 将rosbag中livox CustomMsg格式转为Pointcloud2格式_rosbag中custommsg转pointcloud2-CSDN博客
[2] 如何将livox格式CustomMsg格式转换pointcloud2_livox repub-CSDN博客
#ROS(8)#PCL(6)#Point Cloud(10)评论