Functions | |
def | _get_struct_fmt |
def | create_cloud |
def | create_cloud_xyz32 |
def | read_points |
Variables | |
dictionary | _DATATYPES = {} |
def sensor_msgs.point_cloud2._get_struct_fmt | ( | is_bigendian, | |
fields, | |||
field_names = None |
|||
) | [private] |
Definition at line 167 of file point_cloud2.py.
def sensor_msgs.point_cloud2.create_cloud | ( | header, | |
fields, | |||
points | |||
) |
Create a L{sensor_msgs.msg.PointCloud2} message. @param header: The point cloud header. @type header: L{std_msgs.msg.Header} @param fields: The point cloud fields. @type fields: iterable of L{sensor_msgs.msg.PointField} @param points: The point cloud points. @type 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) @return: The point cloud. @rtype: L{sensor_msgs.msg.PointCloud2}
Definition at line 115 of file point_cloud2.py.
def sensor_msgs.point_cloud2.create_cloud_xyz32 | ( | header, | |
points | |||
) |
Create a L{sensor_msgs.msg.PointCloud2} message with 3 float32 fields (x, y, z). @param header: The point cloud header. @type header: L{std_msgs.msg.Header} @param points: The point cloud points. @type points: iterable @return: The point cloud. @rtype: L{sensor_msgs.msg.PointCloud2}
Definition at line 151 of file point_cloud2.py.
def sensor_msgs.point_cloud2.read_points | ( | cloud, | |
field_names = None , |
|||
skip_nans = False , |
|||
uvs = [] |
|||
) |
Read points from a L{sensor_msgs.PointCloud2} message. @param cloud: The point cloud to read from. @type cloud: L{sensor_msgs.PointCloud2} @param field_names: The names of fields to read. If None, read all fields. [default: None] @type field_names: iterable @param skip_nans: If True, then don't return any point with a NaN value. @type skip_nans: bool [default: False] @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] @type uvs: iterable @return: Generator which yields a list of values for each point. @rtype: generator
Definition at line 60 of file point_cloud2.py.
dictionary sensor_msgs::point_cloud2::_DATATYPES = {} |
Definition at line 50 of file point_cloud2.py.