Functions | Variables
ros_numpy.point_cloud2 Namespace Reference

Functions

def array_to_pointcloud2 (cloud_arr, stamp=None, frame_id=None)
 
def dtype_to_fields (dtype)
 
def fields_to_dtype (fields, point_step)
 
def get_xyz_points (cloud_array, remove_nans=True, dtype=np.float)
 
def merge_rgb_fields (cloud_arr)
 
def pointcloud2_to_array (cloud_msg, squeeze=True)
 
def pointcloud2_to_xyz_array (cloud_msg, remove_nans=True)
 
def split_rgb_field (cloud_arr)
 

Variables

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

Function Documentation

def ros_numpy.point_cloud2.array_to_pointcloud2 (   cloud_arr,
  stamp = None,
  frame_id = None 
)
Converts a numpy record array to a sensor_msgs.msg.PointCloud2.

Definition at line 133 of file point_cloud2.py.

def ros_numpy.point_cloud2.dtype_to_fields (   dtype)
Convert a numpy record datatype into a list of PointFields.

Definition at line 88 of file point_cloud2.py.

def ros_numpy.point_cloud2.fields_to_dtype (   fields,
  point_step 
)
Convert a list of PointFields to a numpy record datatype.

Definition at line 61 of file point_cloud2.py.

def ros_numpy.point_cloud2.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 224 of file point_cloud2.py.

def ros_numpy.point_cloud2.merge_rgb_fields (   cloud_arr)
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 155 of file point_cloud2.py.

def ros_numpy.point_cloud2.pointcloud2_to_array (   cloud_msg,
  squeeze = True 
)
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.frombuffer rather than struct.unpack is speed... especially
for large point clouds, this will be <much> faster.

Definition at line 109 of file point_cloud2.py.

def ros_numpy.point_cloud2.pointcloud2_to_xyz_array (   cloud_msg,
  remove_nans = True 
)

Definition at line 241 of file point_cloud2.py.

def ros_numpy.point_cloud2.split_rgb_field (   cloud_arr)
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 189 of file point_cloud2.py.

Variable Documentation

string ros_numpy.point_cloud2.__docformat__ = "restructuredtext en"
private

Definition at line 38 of file point_cloud2.py.

string ros_numpy.point_cloud2.DUMMY_FIELD_PREFIX = '__'

Definition at line 47 of file point_cloud2.py.

ros_numpy.point_cloud2.nptype_to_pftype = dict((nptype, pftype) for pftype, nptype in type_mappings)

Definition at line 54 of file point_cloud2.py.

dictionary ros_numpy.point_cloud2.pftype_sizes
Initial value:
1 = {PointField.INT8: 1, PointField.UINT8: 1, PointField.INT16: 2, PointField.UINT16: 2,
2  PointField.INT32: 4, PointField.UINT32: 4, PointField.FLOAT32: 4, PointField.FLOAT64: 8}

Definition at line 57 of file point_cloud2.py.

ros_numpy.point_cloud2.pftype_to_nptype = dict(type_mappings)

Definition at line 53 of file point_cloud2.py.

ros_numpy.point_cloud2.plural

Definition at line 60 of file point_cloud2.py.

ros_numpy.point_cloud2.PointField

Definition at line 60 of file point_cloud2.py.

list ros_numpy.point_cloud2.type_mappings
Initial value:
1 = [(PointField.INT8, np.dtype('int8')), (PointField.UINT8, np.dtype('uint8')), (PointField.INT16, np.dtype('int16')),
2  (PointField.UINT16, np.dtype('uint16')), (PointField.INT32, np.dtype('int32')), (PointField.UINT32, np.dtype('uint32')),
3  (PointField.FLOAT32, np.dtype('float32')), (PointField.FLOAT64, np.dtype('float64'))]

Definition at line 50 of file point_cloud2.py.



ros_numpy
Author(s): Eric Wieser
autogenerated on Sat Oct 3 2020 03:25:57