Go to the documentation of this file.00001 import roslib; roslib.load_manifest('point_cloud_ros')
00002 from sensor_msgs.msg import PointCloud
00003 from geometry_msgs.msg import Point32
00004 from sensor_msgs.msg import ChannelFloat32
00005 import numpy as np
00006 import time
00007
00008
00009
00010
00011 def ros_pointcloud_to_np(ros_pointcloud):
00012 ''' ros PointCloud.pts -> 3xN numpy matrix
00013 '''
00014 return ros_pts_to_np(ros_pointcloud.points)
00015
00016
00017
00018
00019 def ros_pts_to_np(ros_pts):
00020 pts_list = []
00021 for p in ros_pts:
00022 pts_list.append([p.x,p.y,p.z])
00023
00024 return np.matrix(pts_list).T
00025
00026
00027
00028
00029 def np_points_to_ros(pts):
00030 p_list = []
00031 chlist = []
00032
00033
00034
00035 for p in pts.T:
00036 p_list.append(Point32(p[0,0],p[0,1],p[0,2]))
00037 chlist.append(0.)
00038
00039 ch = ChannelFloat32('t',chlist)
00040 pc = PointCloud()
00041 pc.points = p_list
00042 pc.channels = [ch]
00043 return pc
00044
00045