point_cloud_utils.py
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 ## PointCloud  -> 3xN np matrix
00009 # @param ros_pointcloud - robot_msgs/PointCloud
00010 # @return 3xN np matrix
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 ## list of Point32 points  -> 3xN np matrix
00017 # @param ros_points - Point32[ ] (for e.g. from robot_msgs/PointCloud or Polygon3D)
00018 # @return 3xN np matrix
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 ## 3xN np matrix -> ros PointCloud
00027 # @param pts - 3xN np matrix
00028 # @return PointCloud as defined in robot_msgs/msg/PointCloud.msg
00029 def np_points_to_ros(pts):
00030     p_list = []
00031     chlist = []
00032 
00033 #    p_list = [Point32(p[0,0], p[0,1], p[0,2]) for p in pts.T]
00034 #    chlist = np.zeros(pts.shape[1]).tolist()
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 


point_cloud_ros
Author(s): Advait Jain (Healthcare Robotics Lab, Georgia Tech)
autogenerated on Wed Nov 27 2013 12:16:42