04 | 格式优化(kitti数据集运用)

1. kitti_teach.py

#!/usr/bin/env python3
import os 

from data_utils import *
from publish_utils import *

DATA_PATH = '/home/jony/data/kitti/RawData/2011_09_26/2011_09_26_drive_0005_sync/'

if __name__ == '__main__':
    frame = 0
    rospy.init_node('kitti_node', anonymous=True)
    cam_pub = rospy.Publisher('kitti_cam', Image, queue_size=10)
    pcl_pub = rospy.Publisher('kitti_pcl', PointCloud2, queue_size=10)
    bridge = CvBridge()

    rate = rospy.Rate(10)
    while not rospy.is_shutdown():
        image = read_camera(os.path.join(DATA_PATH, 'image_02/data/%010d.png' % frame))
        point_cloud = read_point_cloud(os.path.join(DATA_PATH, 'velodyne_points/data/%010d.bin'%frame))
     
        publish_camera(cam_pub, bridge, image)
        publish_point_cloud(pcl_pub, point_cloud)
        rospy.loginfo("Published!")
        rate.sleep()
        frame += 1
        frame %= 154

2. publish_utils.py

#!/usr/bin/env python3
import rospy
import sensor_msgs.point_cloud2 as plc2 

from std_msgs.msg import Header
from sensor_msgs.msg import Image, PointCloud2 
from cv_bridge import CvBridge 

FRAME_ID = 'map'

def publish_camera(cam_pub, bridge, image):
	cam_pub.publish(bridge.cv2_to_imgmsg(image, "bgr8"))

def publish_point_cloud(pcl_pub, point_cloud):
	header = Header()
	header.stamp = rospy.Time.now()
	header.frame_id = FRAME_ID
	pcl_pub.publish(plc2.create_cloud_xyz32(header, point_cloud[:, :3]))

3. data_utils.py

#!/usr/bin/env python3
import cv2
import numpy as np 

def read_camera(path):
	return cv2.imread(path)

def read_point_cloud(path):
	return np.fromfile(path, dtype=np.float32).reshape(-1, 4)
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值