
Static Private Attributes | |
| list | _fields_ |
sick_scan_api: struct SickScanPointCloudMsg, equivalent to ros::std_msgs::PointCloud2
SickScanPointCloudMsg contains the polar or cartesian pointcloud data.
A SickScanPointCloudMsg in cartesian coordinates has fields (x, y, z, intensity).
A SickScanPointCloudMsg in polar coordinates has fields (range, azimuth, elevation, intensity).
Note: The pointcloud contains always <num_echos> echos. Invalid echos are filled with 0 values in the data array.
Attributes
----------
header : SickScanHeader
message timestamp
height : ctypes.c_uint32
2D structure of the point cloud. If the cloud is unordered, height is 1
width : ctypes.c_uint32
and width is the length of the point cloud.
fields : SickScanPointFieldArray
Describes the channels and their layout in the binary data blob.
is_bigendian : ctypes.c_uint8
Is this data bigendian?
point_step : ctypes.c_uint32
Length of a point in bytes
row_step : ctypes.c_uint32
Length of a row in bytes
data : SickScanUint8Array
Actual point data, size is (row_step*height)
is_dense : ctypes.c_uint8
True if there are no invalid points
num_echos : ctypes.c_int32
number of echos
segment_idx : ctypes.c_int32
segment index (or -1 if pointcloud contains data from multiple segments)
Definition at line 127 of file sick_scan_api.py.
|
staticprivate |
Definition at line 160 of file sick_scan_api.py.