tracking资料存放在/kitti_folder/tracking中
jupyter工程存放在/test3_autodrive_ws/src/jupyter_prj下的2D_tracking_label.ipynb
数据文件存放在/home/qinsir/kitti_folder/tracking/data_tracking_label_2/training/label_02
下,可以看到是txt文件
矫正程序在test3_autodrive_ws/src/demo1_kitti_pub_photo/scripts/calibration.py中
上一节已经实现在jupyter-notebook平台上的稳定运行,本节将其移植至ROS中即可
from calibration import *
def compute_3d_box_cam2(h, w, l, x, y, z, yaw)
box3d_pub = rospy.Publisher("kitti_3d", MarkerArray, queue_size=10)
calib = Calibration('/home/qinsir/kitti_folder/2011_09_26', from_video=True)
boxes_3d = np.array(df_tracking[df_tracking.frame==frame][['height', 'width', 'length', 'pos_x', 'pos_y', 'pos_z', 'rot_y']])
corners_3d_velos = []
for box_3d in boxes_3d:
corners_3d_cam2 = compute_3d_box_cam2(*box_3d) #用*表展开为7个参数
#经过矫正到velodyne的函数,入口参数为从cam到velodyne
#需要8X3,转置一下
corners_3d_velo = calib.project_ref_to_velo(corners_3d_cam2.T)
corners_3d_velos += [corners_3d_velo] #逐个存入列表
publish_3dbox(box3d_pub, corners_3d_velos, types) #发布三维
LIFETIME = 0.1 #我没用上
LINES = [[0,1], [1,2], [2,3], [3, 0]] #底面
LINES += [[4,5], [5,6], [6,7], [7,4]] #顶面
LINES += [[4,0], [5,1], [6,2], [7,3]] #中间的四条线
LINES += [[4,1], [5,0]] #前边用"X"标志
b, g, r = DETECTION_COLOR_DICT[types[i]]
marker.color.r = r / 255.0
marker.color.g = g / 255.0
marker.color.b = b / 255.0 #这条线的颜色
for i, corners_3d_velo in enumerate(corners_3d_velos):
for l in LINES:
p1 = corners_3d_velo[l[0]]
marker.points.append(Point(p1[0], p1[1], p1[2]))
p2 = corners_3d_velo[l[1]]
marker.points.append(Point(p2[0], p2[1], p2[2]))
box3d_pub.publish(marker_array)
#!/usr/bin/env python3
#coding:utf-8
import rospy
from std_msgs.msg import Header
from sensor_msgs.msg import Image, PointCloud2, Imu, NavSatFix
from visualization_msgs.msg import Marker, MarkerArray
import sensor_msgs.point_cloud2 as pcl2
from geometry_msgs.msg import Point
from cv_bridge import CvBridge
import numpy as np
import tf
import cv2
FRAME_ID = "map"
DETECTION_COLOR_DICT = {'Car':(255, 255, 0), 'Pedestrian':(0, 226, 255), 'Cyclist':(141, 40, 255)}
#为三种车型,分别添加颜色值对应的框
LIFETIME = 0.1
#生存周期
LINES = [[0,1], [1,2], [2,3], [3, 0]] #底面
LINES += [[4,5], [5,6], [6,7], [7,4]] #顶面
LINES += [[4,0], [5,1], [6,2], [7,3]] #中间的四条线
LINES += [[4,1], [5,0]] #前边用"X"标志
'''
def publish_camera(cam_pub, bridge, image):
cam_pub.publish(bridge.cv2_to_imgmsg(image, 'bgr8'))
'''
def publish_camera(cam_pub, bridge, image, boxes, types):
#画出每一个坐标
for typ, box in zip(types, boxes): #for一个矩阵,它是一行一行读取
# 左上角,右下角,像素都是整数
top_left = int(box[0]), int(box[1])
right_down = int(box[2]), int(box[3])
# 画矩形
cv2.rectangle(image, top_left, right_down, DETECTION_COLOR_DICT[typ], 2)
cam_pub.publish(bridge.cv2_to_imgmsg(image, 'bgr8'))
def publish_point_cloud(pcl_pub, point_cloud):
header = Header()
header.frame_id = FRAME_ID
header.stamp = rospy.Time.now()
pcl_pub.publish(pcl2.create_cloud_xyz32(header, point_cloud[:, :3]))
def publish_ego_car(ego_car_pub):
'publish left and right 45 degree FOV and ego car model mesh'
#header部分
marker = Marker()
marker.header.frame_id = FRAME_ID
marker.header.stamp = rospy.Time.now()
# marker的id
marker.id = 0
marker.action = Marker.ADD # 加入一个marker
marker.lifetime = rospy.Duration() # 生存时间,()中无参数永远出现
marker.type = Marker.LINE_STRIP #marker 的type,有很多种,这里选择线条
marker.color.r = 0.0
marker.color.g = 1.0
marker.color.b = 0.0 #这条线的颜色
marker.color.a = 1.0 #透明度 1不透明
marker.scale.x = 0.2 #大小,粗细
#设定marker中的资料
marker.points = []
# 两条线,三个点即可
#原点是0,0,0, 看左上角和右上角的数据要看kitti的设定,看坐标
marker.points.append(Point(10, -10, 0))
marker.points.append(Point(0, 0, 0))
marker.points.append(Point(10, 10, 0))
ego_car_pub.publish(marker) #设定完毕,发布
def publish_car_model(model):
#header部分
mesh_marker = Marker()
mesh_marker.header.frame_id = FRAME_ID
mesh_marker.header.stamp = rospy.Time.now()
# marker的id
mesh_marker.id = -1
mesh_marker.lifetime = rospy.Duration() # 生存时间,()中无参数永远出现
mesh_marker.type = Marker.MESH_RESOURCE #marker 的type,有很多种,这里选择mesh
mesh_marker.mesh_resource = "package://demo1_kitti_pub_photo/mesh/car_model/car.DAE"
#平移量设置
mesh_marker.pose.position.x = 0.0
mesh_marker.pose.position.y = 0.0
#以为0,0,0 是velodyne的坐标(车顶),这里坐标是车底,所以是负数
mesh_marker.pose.position.z = -1.73
#旋转量设定
q = tf.transformations.quaternion_from_euler(np.pi/2, 0, np.pi/2)
# 这里的参数和下载模型的预设角度有关,旋转关系,根据显示效果而调整,转成四元数q
#x轴旋转
mesh_marker.pose.orientation.x = q[0]
mesh_marker.pose.orientation.y = q[1]
mesh_marker.pose.orientation.z = q[2]
mesh_marker.pose.orientation.w = q[3]
#颜色设定(白色)
mesh_marker.color.r = 1.0
mesh_marker.color.g = 1.0
mesh_marker.color.b = 1.0
mesh_marker.color.a = 1.0
#设置体积: x,y,z方向的膨胀程度
mesh_marker.scale.x = 0.4
mesh_marker.scale.y = 0.4
mesh_marker.scale.z = 0.4
model.publish(mesh_marker) #设定完毕,发布
def publish_two_marker(kitti_two_marker):
#建立markerarray
markerarray = MarkerArray()
# 绿线设定
marker = Marker()
marker.header.frame_id = FRAME_ID
marker.header.stamp = rospy.Time.now()
# marker的id
marker.id = 0
marker.action = Marker.ADD # 加入一个marker
marker.lifetime = rospy.Duration() # 生存时间,()中无参数永远出现
marker.type = Marker.LINE_STRIP #marker 的type,有很多种,这里选择线条
marker.color.r = 0.0
marker.color.g = 1.0
marker.color.b = 0.0 #这条线的颜色
marker.color.a = 1.0 #透明度 1不透明
marker.scale.x = 0.2 #大小,粗细
#设定marker中的资料
marker.points = []
# 两条线,三个点即可
#原点是0,0,0, 看左上角和右上角的数据要看kitti的设定,看坐标
marker.points.append(Point(10, -10, 0))
marker.points.append(Point(0, 0, 0))
marker.points.append(Point(10, 10, 0))
#加入第一个
markerarray.markers.append(marker)
mesh_marker = Marker()
mesh_marker.header.frame_id = FRAME_ID
mesh_marker.header.stamp = rospy.Time.now()
# marker的id
mesh_marker.id = -1
mesh_marker.lifetime = rospy.Duration() # 生存时间,()中无参数永远出现
mesh_marker.type = Marker.MESH_RESOURCE #marker 的type,有很多种,这里选择mesh
mesh_marker.mesh_resource = "package://demo1_kitti_pub_photo/mesh/car_model/car.DAE"
#平移量设置
mesh_marker.pose.position.x = 0.0
mesh_marker.pose.position.y = 0.0
#以为0,0,0 是velodyne的坐标(车顶),这里坐标是车底,所以是负数
mesh_marker.pose.position.z = -1.73
#旋转量设定
q = tf.transformations.quaternion_from_euler(np.pi/2, 0, np.pi/2)
# 这里的参数和下载模型的预设角度有关,旋转关系,根据显示效果而调整,转成四元数q
#x轴旋转
mesh_marker.pose.orientation.x = q[0]
mesh_marker.pose.orientation.y = q[1]
mesh_marker.pose.orientation.z = q[2]
mesh_marker.pose.orientation.w = q[3]
#颜色设定(白色)
mesh_marker.color.r = 1.0
mesh_marker.color.g = 1.0
mesh_marker.color.b = 1.0
mesh_marker.color.a = 1.0
#设置体积: x,y,z方向的膨胀程度
mesh_marker.scale.x = 0.4
mesh_marker.scale.y = 0.4
mesh_marker.scale.z = 0.4
# 加入第二个:车子模型
markerarray.markers.append(mesh_marker)
#发布
kitti_two_marker.publish(markerarray)
def publish_imu(imu_pub, imu_data):
# 消息建立
imu = Imu()
#头填充
imu.header.frame_id = FRAME_ID
imu.header.stamp = rospy.Time.now()
#旋转角度
q = tf.transformations.quaternion_from_euler(float(imu_data.roll), float(imu_data.pitch), float(imu_data.yaw))
# 将roll, pitch, yaw转成可被电脑识别的四元数q,并设定出去
imu.orientation.x = q[0]
imu.orientation.y = q[1]
imu.orientation.z = q[2]
imu.orientation.w = q[3]
#线性加速度
imu.linear_acceleration.x = imu_data.af
imu.linear_acceleration.y = imu_data.al
imu.linear_acceleration.z = imu_data.au
#角速度
imu.angular_velocity.x = imu_data.wf
imu.angular_velocity.y = imu_data.wl
imu.angular_velocity.z = imu_data.wu
#发布
imu_pub.publish(imu)
def publish_gps(gps_pub, imu_data):
gps = NavSatFix()
#头填充
gps.header.frame_id = FRAME_ID
gps.header.stamp = rospy.Time.now()
#维度, 经度 和海拔
gps.latitude = imu_data.lat
gps.longitude = imu_data.lon
gps.altitude = imu_data.al
gps_pub.publish(gps)
def publish_3dbox(box3d_pub, corners_3d_velos, types):
marker_array = MarkerArray()
#对每一组数据/交通工具/矩形框进行迭代
for i, corners_3d_velo in enumerate(corners_3d_velos):
#header部分
marker = Marker()
marker.header.frame_id = FRAME_ID
marker.header.stamp = rospy.Time.now()
# marker的id
marker.id = i
marker.action = Marker.ADD # 加入一个marker
marker.lifetime = rospy.Duration(0) # 生存时间,()中无参数永远出现
marker.type = Marker.LINE_STRIP #marker 的type,有很多种,这里选择线条
b, g, r = DETECTION_COLOR_DICT[types[i]]
marker.color.r = r / 255.0
marker.color.g = g / 255.0
marker.color.b = b / 255.0 #这条线的颜色
marker.color.a = 1.0 #透明度 1不透明
marker.scale.x = 0.1 #大小,粗细
#设定marker中的资料
marker.points = []
#对每两个点之间进行迭代,存在则连
for l in LINES :
p1 = corners_3d_velo[l[0]]
marker.points.append(Point(p1[0], p1[1], p1[2]))
p2 = corners_3d_velo[l[1]]
marker.points.append(Point(p2[0], p2[1], p2[2]))
marker_array.markers.append(marker)
box3d_pub.publish(marker_array)
#!/usr/bin/env python3
#coding:utf-8
from data_utils import *
from publish_utils import *
from calibration import *
DATA_PATH = '/home/qinsir/kitti_folder/2011_09_26/2011_09_26_drive_0005_sync/'
# 根据长宽高XYZ和旋转角坐标定位
def compute_3d_box_cam2(h, w, l, x, y, z, yaw):
'''
return : 3xn in cam2 coordinate
'''
R = np.array([[np.cos(yaw), 0, np.sin(yaw)], [0, 1, 0], [-np.sin(yaw), 0, np.cos(yaw)]])
x_corners = [l/2, l/2, -l/2, -l/2, l/2, l/2, -l/2, -l/2]
y_corners = [0, 0, 0, 0, -h, -h, -h, -h]
z_corners = [w/2, -w/2, -w/2, w/2, w/2, -w/2, -w/2, w/2]
corners_3d_cam2 = np.dot(R, np.vstack([x_corners, y_corners, z_corners]))
corners_3d_cam2 += np.vstack([x, y, z])
return corners_3d_cam2
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_point_cloud", PointCloud2, queue_size=10)
#ego_pub = rospy.Publisher('kitti_ego_car', Marker, queue_size=10)
#model_pub = rospy.Publisher("kitti_car_model", Marker, queue_size=10)
two_marker_pub = rospy.Publisher("kitti_two_mark", MarkerArray, queue_size=10)
imu_pub = rospy.Publisher("kitti_imu", Imu, queue_size=10) #IMU发布者
gps_pub = rospy.Publisher("kitti_gps", NavSatFix, queue_size=10)
box3d_pub = rospy.Publisher("kitti_3d", MarkerArray, queue_size=10)
bridge = CvBridge() #opencv支持的图片和ROS可以读取的图片之间转换的桥梁
rate = rospy.Rate(10)
#以第0组(厢型车等归类适用的tracking数据)为数据读取
df_tracking = read_tracking('/home/qinsir/kitti_folder/tracking/data_tracking_label_2/training/label_02/0000.txt')
calib = Calibration('/home/qinsir/kitti_folder/2011_09_26', from_video=True)
while not rospy.is_shutdown():
boxes_2d = np.array(df_tracking[df_tracking.frame==frame][["bbox_left", "bbox_top", "bbox_right", "bbox_bottom"]]) #格式转换,第0帧所有的打标框
types = np.array(df_tracking[df_tracking.frame==frame]["type"])
boxes_3d = np.array(df_tracking[df_tracking.frame==frame][['height', 'width', 'length', 'pos_x', 'pos_y', 'pos_z', 'rot_y']])
#保存8个雷达坐标系下点的坐标的list
corners_3d_velos = []
#对于图片中的每一个记录物体都进行计算
for box_3d in boxes_3d:
#相机里的坐标
corners_3d_cam2 = compute_3d_box_cam2(*box_3d) #用*表展开为7个参数
#经过矫正到velodyne的函数,入口参数为从cam到velodyne
#需要8X3,转置一下
corners_3d_velo = calib.project_ref_to_velo(corners_3d_cam2.T)
corners_3d_velos += [corners_3d_velo] #逐个存入列表
#使用OS,路径串接,%010d,这个字串有10个数字(比如0000000001).png
img = 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))
imu_data = read_imu(os.path.join(DATA_PATH, "oxts/data/%010d.txt"%frame))
publish_camera(cam_pub, bridge, img, boxes_2d, types)
#publish_camera(cam_pub, bridge, img)
publish_point_cloud(pcl_pub, point_cloud)
publish_3dbox(box3d_pub, corners_3d_velos, types) #发布三维
#publish_ego_car(ego_pub)
#publish_car_model(model_pub)
publish_two_marker(two_marker_pub)
publish_imu(imu_pub, imu_data)
publish_gps(gps_pub, imu_data)
rospy.loginfo('new file publish')
rate.sleep()
frame += 1
frame %= 154