ROS 加载KITTI数据集并在rviz中显示(一)

一、参考资料

ROS 加载kitti数据集图片发布图片话题,并用rivz显示出来

ROS 加载kitti数据集的激光雷达点云数据,并用rivz显示出来

二、ROS 加载KITTI数据集的图像数据

ROS加载kitti数据集的图像数据,在rviz中显示。

1. 下载kitti数据集

下载并解压KITTI数据集的 RawData数据。

2011_10_03_drive_0027_sync.zip
2011_10_03_calib.zip

文件目录结构

.
├── 2011_10_03
│   ├── 2011_10_03_drive_0027_sync
│   │   ├── image_00
│   │   ├── image_01
│   │   ├── image_02
│   │   ├── image_03
│   │   ├── oxts
│   │   └── velodyne_points
│   ├── calib_cam_to_cam.txt
│   ├── calib_imu_to_velo.txt
│   └── calib_velo_to_cam.txt

2. 创建工作空间

# 创建目录,用于存储ROS工作空间
mkdir -p ~/catkin_ws/src

# 初始化工作空间
cd ~/catkin_ws/src
catkin_init_workspace

# 编译工作空间
cd ~/catkin_ws
catkin_make

3. 设置环境变量

# 临时生效
source ~/catkin_ws/devel/setup.bash

# 永久生效
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

4. 创建功能包

# 创建功能包
cd ~/catkin_ws/src
catkin_create_pkg kitti_tutorial roscpp rospy std_msgs

# 编译功能包,生成 build、devel 文件夹
cd ~/catkin_ws
catkin_make

5. 编辑源代码

进入kitti_tutorial功能包目录,添加 scripts 目录,并编辑 python 文件。

cd ~/catkin_ws/src/kitti_tutorial
mkdir scripts

# 完成源代码之后,修改python文件的权限
chmod +x kitti.py 

kitti.py

#!/usr/bin/env python
# coding:utf-8

import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import os


DATA_PATH = "/media/yoyo/U/2011_10_03/2011_10_03_drive_0027_sync"

if __name__ == "__main__":
    rospy.init_node("kitti_node", anonymous=True)
    cam_pub = rospy.Publisher("kitti_cam", Image, queue_size=10)
    bridge = CvBridge()
    rate = rospy.Rate(10)
    frame = 0

    while not rospy.is_shutdown():
        img = cv2.imread(os.path.join(DATA_PATH, 'image_02/data/%010d.png'%frame))
        cam_pub.publish(bridge.cv2_to_imgmsg(img, 'rgb8'))
        rospy.loginfo("camera image published")
        rate.sleep()
        frame += 1
        frame %= 154

参数解释

  • 节点名称:kitti_node
  • 发布的话题名称:kitti_cam,数据类型为 Image
  • CvBridge():opencv与ros之间的图像格式转换;

6. 编辑配置文件

进入 ros 功能包目录,编辑功能包下的 CMakeLists.txt 文件。

CamkeList.txt

catkin_install_python(PROGRAMS scripts/kitti.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

7. 编译并执行

进入工作空间目录,重新编译工作空间。

cd ~/catkin_ws
catkin_make

执行helloworld程序。

# 打开新终端,启动roscore
roscore

# 如果没有设置环境变量,则source环境变量
source ~/catkin_ws/devel/setup.bash

# 打开新终端,启动节点,运行helloworld程序
cd ~/catkin_ws
rosrun kitti_rutorial kitti.py

8. 启动rviz显示

rosrun rviz rviz
yoyo@yoyo:~/catkin_ws$ rosrun rviz rviz
[ INFO] [1690354820.980297976]: rviz version 1.12.17
[ INFO] [1690354820.980329927]: compiled against Qt version 5.5.1
[ INFO] [1690354820.980337661]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1690354821.111348690]: Stereo is NOT SUPPORTED
[ INFO] [1690354821.111407271]: OpenGl version: 3 (GLSL 1.3).

在这里插入图片描述在这里插入图片描述

三、ROS 加载KITTI数据集的激光雷达点云数据

ROS加载KITTI数据集的激光雷达点云数据,在rviz中显示。
该章节流程与上一章节类似,本章节仅记录重要且有差异的地方,详细内容请参阅上一章节。

1. 编辑源代码

kitti2pcl.py

#!/usr/bin/env python
# coding:utf-8

import rospy
import os
import numpy as np

from sensor_msgs.msg import PointCloud2
import sensor_msgs.point_cloud2 as pcl2
from std_msgs.msg import Header


DATA_PATH = "/media/yoyo/U/2011_10_03/2011_10_03_drive_0027_sync"

if __name__ == "__main__":
    # 初始化节点
    rospy.init_node("kitti_node", anonymous=True)

    # 实例化发布者
    pcl_pub = rospy.Publisher("kitti_pcl", PointCloud2, queue_size=10)

    rate = rospy.Rate(10)
    frame = 0

    while not rospy.is_shutdown():
        pcl = np.fromfile(os.path.join(DATA_PATH, 'velodyne_points/data/%010d.bin'%frame), dtype=np.float32).reshape(-1, 4)

        header = Header()
        header.stamp = rospy.Time.now()
        header.frame_id = 'map'

        # 发布消息
        pcl_pub.publish(pcl2.create_cloud_xyz32(header, pcl[:,:3]))

        rospy.loginfo("published")
        rate.sleep()
        frame += 1
        frame %= 154

参数解释

  • 节点名称:kitti_node;
  • 发布的话题名称:kitti_pcl,数据类型为PointCloud2;
  • bin文件的数据,每一行有四个数字,分别代表xyz和反射强度信息。

2. 编辑配置文件

进入 ros 功能包目录,编辑功能包下的 CMakeLists.txt 文件。

CamkeList.txt

catkin_install_python(PROGRAMS scripts/kitti2pcl.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

3. 启动rviz显示

在这里插入图片描述在这里插入图片描述

四、FAQ

Q:[rosrun] Couldn't find executable named kitti.py

yoyo@yoyo:~/catkin_ws$ rosrun kitti_tutorial kitti.py
[rosrun] Couldn't find executable named kitti.py below /home/yoyo/catkin_ws/src/kitti_tutorial
[rosrun] Found the following, but they're either not files,
[rosrun] or not executable:
[rosrun]   /home/yoyo/catkin_ws/src/kitti_tutorial/scripts/kitti.py
错误原因:
没有给 kitti.py 文件添加权限

解决办法:
给 kitti.py 文件添加权限
chmod +x kitti.py

猜你喜欢

转载自blog.csdn.net/m0_37605642/article/details/131943899