
Static Private Attributes | |
| list | _fields_ |
sick_scan_api: struct SickScanPointFieldMsg, equivalent to ros::sensor_msgs::PointField
SickScanPointFieldArray is an array of SickScanPointFieldMsg, which defines the structure of the binary data of a SickScanPointCloudMsg.
SickScanPointFieldMsg for pointclouds in cartesian coordinates with fields (x, y, z, intensity):
[ SickScanPointFieldMsg(name="x", offset=0, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="y", offset=4, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="z", offset=8, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
SickScanPointFieldMsg for pointclouds in polar coordinates with fields (range, azimuth, elevation, intensity):
[ SickScanPointFieldMsg(name="range", offset=0, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="azimuth", offset=4, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="elevation", offset=8, datatype=FLOAT32, count=1),
SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
Attributes
----------
name : ctypes.c_char * 256
Name of field (max. length 256 characters)
offset : ctypes.c_uint32
Offset from start of point struct
datatype : ctypes.c_uint8
Datatype enumeration, see SickScanNativeDataType, equivalent to type enum im ros::sensor_msgs::PointField
count : ctypes.c_uint32
How many elements in the field
Definition at line 75 of file sick_scan_api.py.
|
staticprivate |
Definition at line 101 of file sick_scan_api.py.