我是靠谱客的博主 整齐玫瑰,这篇文章主要介绍ROS 发布kitti数据集的gps信息1.准备数据2.读取数据:data_utils.py3.发布数据:publish_utils.py4.发布节点,现在分享给大家,希望可以做个参考。

  用ROS发布kitti的gps信息,效果如下:
在这里插入图片描述

ROS 发布kitti数据集的gps信息

  • 1.准备数据
  • 2.读取数据:data_utils.py
  • 3.发布数据:publish_utils.py
  • 4.发布节点

1.准备数据

在这里插入图片描述

2.读取数据:data_utils.py

复制代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
#!/usr/bin/env python import cv2 import numpy as np import pandas as pd from sensor_msgs.msg import Imu IMU_COLUMN_NAMES=['lat','lon','alt', 'roll','pitch','yaw', 'vn','ve','vf','vl','vu', 'ax','ay','az','af','al','au', 'wx','wy','wz','wf','wl','wu', 'posacc','velacc','navstat','numsats','posmode','velmode','orimode'] def read_camera(path): return cv2.imread(path) def read_point_cloud(path): return np.fromfile(path,dtype=np.float32).reshape(-1,4) def read_imu(path): df=pd.read_csv(path,header=None,sep=' ') df.columns=IMU_COLUMN_NAMES return df

3.发布数据:publish_utils.py

复制代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
#!/usr/bin/env python import rospy from std_msgs.msg import Header from sensor_msgs.msg import Image,PointCloud2,Imu,NavSatFix import sensor_msgs.point_cloud2 as pcl2 from cv_bridge import CvBridge from visualization_msgs.msg import Marker,MarkerArray from geometry_msgs.msg import Point import tf import numpy as np import tf_conversions FRAME_ID='map' def publish_camera(cam_pub,bridge,image): cam_pub.publish(bridge.cv2_to_imgmsg(image,'bgr8')) def publish_pcl(pcl_pub,point_cloud): header=Header() header.stamp=rospy.Time.now() header.frame_id=FRAME_ID pcl_pub.publish(pcl2.create_cloud_xyz32(header,point_cloud[:,:3])) def publish_ego_car(ego_car_pub): marker_array=MarkerArray() marker=Marker() marker.header.frame_id=FRAME_ID marker.header.stamp=rospy.Time.now() marker.id=0 marker.action=Marker.ADD marker.lifetime=rospy.Duration() marker.type=Marker.LINE_STRIP marker.color.r=0.0 marker.color.g=1.0 marker.color.b=0.0 marker.color.a=1.0 marker.scale.x=0.2 marker.points=[] marker.points.append(Point(10,10,0)) marker.points.append(Point(0,0,0)) marker.points.append(Point(10,-10,0)) marker_array.markers.append(marker) ####################################################### mesh_marker=Marker() mesh_marker.header.frame_id=FRAME_ID mesh_marker.header.stamp=rospy.Time.now() mesh_marker.id=-1 mesh_marker.lifetime=rospy.Duration() mesh_marker.type=Marker.MESH_RESOURCE mesh_marker.mesh_resource="package://kitti_tutorial/Car-Model/Car.dae" mesh_marker.pose.position.x=0 mesh_marker.pose.position.y=0 mesh_marker.pose.position.z=-1.73 q = tf_conversions.transformations.quaternion_from_euler(0,0,np.pi/2) 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 mesh_marker.scale.x=0.9 mesh_marker.scale.y=0.9 mesh_marker.scale.z=0.9 marker_array.markers.append(mesh_marker) ego_car_pub.publish(marker_array) def publish_imu(imu_pub,imu_data): imu=Imu() imu.header.frame_id=FRAME_ID imu.header.stamp=rospy.Time.now() q = tf_conversions.transformations.quaternion_from_euler(float(imu_data.roll),float(imu_data.pitch),float(imu_data.yaw)) 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,gps_data): gps=NavSatFix() gps.header.frame_id=FRAME_ID gps.header.stamp=rospy.Time.now() gps.latitude=gps_data.lat gps.longitude=gps_data.lon gps.altitude=gps_data.alt gps_pub.publish(gps)

4.发布节点

复制代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
#!/usr/bin/env python import os from data_utils import * from publish_utils import * DATA_PATH='/home/chen/Downloads/kittidata/2011_09_26/2011_09_26_drive_0005_sync/' if __name__=='__main__': 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) ego_pub=rospy.Publisher('kitti_ego_car',MarkerArray,queue_size=10) imu_pub=rospy.Publisher('kitti_imu',Imu,queue_size=10) gps_pub=rospy.Publisher('kitti_gps',NavSatFix,queue_size=10) bridge=CvBridge() rate=rospy.Rate(10) frame=0 while not rospy.is_shutdown(): img=read_camera(os.path.join(DATA_PATH,'image_02/data/%010d.png'%frame)) pcl=read_point_cloud(os.path.join(DATA_PATH,'velodyne_points/data/%010d.bin'%frame)) imu=read_imu(os.path.join(DATA_PATH,'oxts/data/%010d.txt'%frame)) publish_camera(cam_pub,bridge,img) publish_pcl(pcl_pub,pcl) publish_ego_car(ego_pub) publish_imu(imu_pub,imu) publish_gps(gps_pub,imu) rospy.loginfo('published') rate.sleep() frame+=1 frame%=154

最后

以上就是整齐玫瑰最近收集整理的关于ROS 发布kitti数据集的gps信息1.准备数据2.读取数据:data_utils.py3.发布数据:publish_utils.py4.发布节点的全部内容,更多相关ROS内容请搜索靠谱客的其他文章。

本图文内容来源于网友提供,作为学习参考使用,或来自网络收集整理,版权属于原作者所有。
点赞(582)

评论列表共有 0 条评论

立即
投稿
返回
顶部