sensor_msgs_py.point_cloud2 module

sensor_msgs_py.point_cloud2.create_cloud(header: std_msgs.msg.Header, fields: Iterable[sensor_msgs.msg.PointField], points: Iterable, point_step: int | None = None) sensor_msgs.msg.PointCloud2

Create a sensor_msgs.msg.PointCloud2 message.

Parameters:
  • header – The point cloud header. (Type: std_msgs.msg.Header)

  • fields – The point cloud fields. (Type: iterable of sensor_msgs.msg.PointField)

  • points – The point cloud points. List of iterables, i.e. one iterable for each point, with the elements of each iterable being the values of the fields for that point (in the same order as the fields parameter)

  • point_step – Point step size in bytes. Calculated from the given fields by default. (Type: optional of integer)

Returns:

The point cloud as sensor_msgs.msg.PointCloud2

sensor_msgs_py.point_cloud2.create_cloud_xyz32(header: std_msgs.msg.Header, points: Iterable) sensor_msgs.msg.PointCloud2

Create a sensor_msgs.msg.PointCloud2 message with (x, y, z) fields.

Parameters:
  • header – The point cloud header. (Type: std_msgs.msg.Header)

  • points – The point cloud points. (Type: Iterable)

Returns:

The point cloud as sensor_msgs.msg.PointCloud2.

sensor_msgs_py.point_cloud2.dtype_from_fields(fields: Iterable[sensor_msgs.msg.PointField], point_step: int | None = None) numpy.dtype

Convert a Iterable of sensor_msgs.msg.PointField messages to a np.dtype.

Parameters:
  • fields – The point cloud fields. (Type: iterable of sensor_msgs.msg.PointField)

  • point_step – Point step size in bytes. Calculated from the given fields by default. (Type: optional of integer)

Returns:

NumPy datatype

sensor_msgs_py.point_cloud2.read_points(cloud: sensor_msgs.msg.PointCloud2, field_names: List[str] | None = None, skip_nans: bool = False, uvs: Iterable | None = None, reshape_organized_cloud: bool = False) numpy.ndarray

Read points from a sensor_msgs.PointCloud2 message.

Parameters:
  • cloud – The point cloud to read from sensor_msgs.PointCloud2.

  • field_names – The names of fields to read. If None, read all fields. (Type: Iterable, Default: None)

  • skip_nans – If True, then don’t return any point with a NaN value. (Type: Bool, Default: False)

  • uvs – If specified, then only return the points at the given coordinates. (Type: Iterable, Default: None)

  • reshape_organized_cloud – Returns the array as an 2D organized point cloud if set.

Returns:

Structured NumPy array containing all points.

sensor_msgs_py.point_cloud2.read_points_list(cloud: sensor_msgs.msg.PointCloud2, field_names: List[str] | None = None, skip_nans: bool = False, uvs: Iterable | None = None) List[NamedTuple]

Read points from a sensor_msgs.PointCloud2 message.

This function returns a list of namedtuples. It operates on top of the read_points method. For more efficient access use read_points directly.

Parameters:
  • cloud – The point cloud to read from. (Type: sensor_msgs.PointCloud2)

  • field_names – The names of fields to read. If None, read all fields. (Type: Iterable, Default: None)

  • skip_nans – If True, then don’t return any point with a NaN value. (Type: Bool, Default: False)

  • uvs – If specified, then only return the points at the given coordinates. (Type: Iterable, Default: None]

Returns:

List of namedtuples containing the values for each point

sensor_msgs_py.point_cloud2.read_points_numpy(cloud: sensor_msgs.msg.PointCloud2, field_names: List[str] | None = None, skip_nans: bool = False, uvs: Iterable | None = None, reshape_organized_cloud: bool = False) numpy.ndarray

Read equally typed fields from sensor_msgs.PointCloud2 message as a unstructured numpy array.

This method is better suited if one wants to perform math operations on e.g. all x,y,z fields. But it is limited to fields with the same dtype as unstructured numpy arrays only contain one dtype.

Parameters:
  • cloud – The point cloud to read from sensor_msgs.PointCloud2.

  • field_names – The names of fields to read. If None, read all fields. (Type: Iterable, Default: None)

  • skip_nans – If True, then don’t return any point with a NaN value. (Type: Bool, Default: False)

  • uvs – If specified, then only return the points at the given coordinates. (Type: Iterable, Default: None)

  • reshape_organized_cloud – Returns the array as an 2D organized point cloud if set.

Returns:

Numpy array containing all points.