Functions | Variables
python_msg_conversions::pointclouds Namespace Reference

Functions

def arr_to_fields
def array_to_pointcloud2
def get_xyz_points
def merge_rgb_fields
def pointcloud2_to_array
def pointcloud2_to_dtype
def pointcloud2_to_xyz_array
def split_rgb_field

Variables

string __docformat__ = "restructuredtext en"
string DUMMY_FIELD_PREFIX = '__'
tuple nptype_to_pftype = dict((nptype, pftype) for pftype, nptype in type_mappings)
dictionary pftype_sizes
tuple pftype_to_nptype = dict(type_mappings)
list type_mappings

Function Documentation

Convert a numpy record datatype into a list of PointFields.

Definition at line 79 of file pointclouds.py.

def python_msg_conversions.pointclouds.array_to_pointcloud2 (   cloud_arr,
  stamp = None,
  frame_id = None,
  merge_rgb = False 
)
Converts a numpy record array to a sensor_msgs.msg.PointCloud2.

Definition at line 116 of file pointclouds.py.

def python_msg_conversions.pointclouds.get_xyz_points (   cloud_array,
  remove_nans = True,
  dtype = np.float 
)
Pulls out x, y, and z columns from the cloud recordarray, and returns
    a 3xN matrix.

Definition at line 210 of file pointclouds.py.

Takes an array with named np.uint8 fields 'r', 'g', and 'b', and returns an array in
which they have been merged into a single np.float32 'rgb' field. The first byte of this
field is the 'r' uint8, the second is the 'g', uint8, and the third is the 'b' uint8.

This is the way that pcl likes to handle RGB colors for some reason.

Definition at line 141 of file pointclouds.py.

def python_msg_conversions.pointclouds.pointcloud2_to_array (   cloud_msg,
  split_rgb = False 
)
Converts a rospy PointCloud2 message to a numpy recordarray 

Reshapes the returned array to have shape (height, width), even if the height is 1.

The reason for using np.fromstring rather than struct.unpack is speed... especially
for large point clouds, this will be <much> faster.

Definition at line 93 of file pointclouds.py.

Convert a list of PointFields to a numpy record datatype.

Definition at line 59 of file pointclouds.py.

def python_msg_conversions.pointclouds.pointcloud2_to_xyz_array (   cloud_msg,
  remove_nans = True 
)

Definition at line 227 of file pointclouds.py.

Takes an array with a named 'rgb' float32 field, and returns an array in which
this has been split into 3 uint 8 fields: 'r', 'g', and 'b'.

(pcl stores rgb in packed 32 bit floats)

Definition at line 175 of file pointclouds.py.


Variable Documentation

Definition at line 38 of file pointclouds.py.

Definition at line 46 of file pointclouds.py.

tuple python_msg_conversions::pointclouds::nptype_to_pftype = dict((nptype, pftype) for pftype, nptype in type_mappings)

Definition at line 53 of file pointclouds.py.

Initial value:
00001 {PointField.INT8: 1, PointField.UINT8: 1, PointField.INT16: 2, PointField.UINT16: 2,
00002                 PointField.INT32: 4, PointField.UINT32: 4, PointField.FLOAT32: 4, PointField.FLOAT64: 8}

Definition at line 56 of file pointclouds.py.

Definition at line 52 of file pointclouds.py.

Initial value:
00001 [(PointField.INT8, np.dtype('int8')), (PointField.UINT8, np.dtype('uint8')), (PointField.INT16, np.dtype('int16')),
00002                  (PointField.UINT16, np.dtype('uint16')), (PointField.INT32, np.dtype('int32')), (PointField.UINT32, np.dtype('uint32')),
00003                  (PointField.FLOAT32, np.dtype('float32')), (PointField.FLOAT64, np.dtype('float64'))]

Definition at line 49 of file pointclouds.py.



python_msg_conversions
Author(s): Jonathan Binney
autogenerated on Thu Jan 2 2014 11:37:16