1 """This file declares the functions and datatypes of the sick_scan_xd python-API.
3 See doc/sick_scan_api/sick_scan_api.md for further information.
18 sick_scan_api: struct SickScanHeader, equivalent to ros::std_msgs::Header
23 sequence ID: consecutively increasing ID
24 timestamp_sec : ctypes.c_uint32
25 seconds part of message timestamps: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
26 timestamp_nsec : ctypes.c_uint32
27 seconds part of message timestamps: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
28 frame_id : ctypes.c_char * 256
29 Frame this data is associated with
32 (
"seq", ctypes.c_uint32),
33 (
"timestamp_sec", ctypes.c_uint32),
34 (
"timestamp_nsec", ctypes.c_uint32),
35 (
"frame_id", ctypes.c_char * 256)
40 equivalent to sick_scan_api.h struct SickScanUint8Array
44 capacity : ctypes.c_uint64
45 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanPointFieldMsg)
46 size : ctypes.c_uint64
47 Number of currently used elements in the buffer
48 buffer : ctypes.POINTER(ctypes.c_uint8)
49 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
52 (
"capacity", ctypes.c_uint64),
53 (
"size", ctypes.c_uint64),
54 (
"buffer", ctypes.POINTER(ctypes.c_uint8))
59 This message holds the description of one point entry in the PointCloud2 message format, equivalent to type enum im ros::sensor_msgs::PointField
61 SICK_SCAN_POINTFIELD_DATATYPE_INT8 = 1,
"SICK_SCAN_POINTFIELD_DATATYPE_INT8"
62 SICK_SCAN_POINTFIELD_DATATYPE_UINT8 = 2,
"SICK_SCAN_POINTFIELD_DATATYPE_UINT8"
63 SICK_SCAN_POINTFIELD_DATATYPE_INT16 = 3,
"SICK_SCAN_POINTFIELD_DATATYPE_INT16"
64 SICK_SCAN_POINTFIELD_DATATYPE_UINT16 = 4,
"SICK_SCAN_POINTFIELD_DATATYPE_UINT16"
65 SICK_SCAN_POINTFIELD_DATATYPE_INT32 = 5,
"SICK_SCAN_POINTFIELD_DATATYPE_INT32"
66 SICK_SCAN_POINTFIELD_DATATYPE_UINT32 = 6,
"SICK_SCAN_POINTFIELD_DATATYPE_UINT32"
67 SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32 = 7,
"SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32"
68 SICK_SCAN_POINTFIELD_DATATYPE_FLOAT64 = 8,
"SICK_SCAN_POINTFIELD_DATATYPE_FLOAT64"
77 sick_scan_api: struct SickScanPointFieldMsg, equivalent to ros::sensor_msgs::PointField
78 SickScanPointFieldArray is an array of SickScanPointFieldMsg, which defines the structure of the binary data of a SickScanPointCloudMsg.
79 SickScanPointFieldMsg for pointclouds in cartesian coordinates with fields (x, y, z, intensity):
80 [ SickScanPointFieldMsg(name="x", offset=0, datatype=FLOAT32, count=1),
81 SickScanPointFieldMsg(name="y", offset=4, datatype=FLOAT32, count=1),
82 SickScanPointFieldMsg(name="z", offset=8, datatype=FLOAT32, count=1),
83 SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
84 SickScanPointFieldMsg for pointclouds in polar coordinates with fields (range, azimuth, elevation, intensity):
85 [ SickScanPointFieldMsg(name="range", offset=0, datatype=FLOAT32, count=1),
86 SickScanPointFieldMsg(name="azimuth", offset=4, datatype=FLOAT32, count=1),
87 SickScanPointFieldMsg(name="elevation", offset=8, datatype=FLOAT32, count=1),
88 SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
92 name : ctypes.c_char * 256
93 Name of field (max. length 256 characters)
94 offset : ctypes.c_uint32
95 Offset from start of point struct
96 datatype : ctypes.c_uint8
97 Datatype enumeration, see SickScanNativeDataType, equivalent to type enum im ros::sensor_msgs::PointField
98 count : ctypes.c_uint32
99 How many elements in the field
102 (
"name", ctypes.c_char * 256),
103 (
"offset", ctypes.c_uint32),
104 (
"datatype", ctypes.c_uint8),
105 (
"count", ctypes.c_uint32)
110 sick_scan_api: struct SickScanPointFieldArray, Array of SickScanPointFieldMsg, which can be serialized and imported in C, C++ or python
114 capacity : ctypes.c_uint64
115 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanPointFieldMsg)
116 size : ctypes.c_uint64
117 Number of currently used elements in the buffer
118 buffer : ctypes.POINTER(SickScanPointFieldMsg)
119 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
122 (
"capacity", ctypes.c_uint64),
123 (
"size", ctypes.c_uint64),
124 (
"buffer", ctypes.POINTER(SickScanPointFieldMsg))
129 sick_scan_api: struct SickScanPointCloudMsg, equivalent to ros::std_msgs::PointCloud2
130 SickScanPointCloudMsg contains the polar or cartesian pointcloud data.
131 A SickScanPointCloudMsg in cartesian coordinates has fields (x, y, z, intensity).
132 A SickScanPointCloudMsg in polar coordinates has fields (range, azimuth, elevation, intensity).
133 Note: The pointcloud contains always <num_echos> echos. Invalid echos are filled with 0 values in the data array.
137 header : SickScanHeader
139 height : ctypes.c_uint32
140 2D structure of the point cloud. If the cloud is unordered, height is 1
141 width : ctypes.c_uint32
142 and width is the length of the point cloud.
143 fields : SickScanPointFieldArray
144 Describes the channels and their layout in the binary data blob.
145 is_bigendian : ctypes.c_uint8
146 Is this data bigendian?
147 point_step : ctypes.c_uint32
148 Length of a point in bytes
149 row_step : ctypes.c_uint32
150 Length of a row in bytes
151 data : SickScanUint8Array
152 Actual point data, size is (row_step*height)
153 is_dense : ctypes.c_uint8
154 True if there are no invalid points
155 num_echos : ctypes.c_int32
157 segment_idx : ctypes.c_int32
158 segment index (or -1 if pointcloud contains data from multiple segments)
161 (
"header", SickScanHeader),
162 (
"height", ctypes.c_uint32),
163 (
"width", ctypes.c_uint32),
164 (
"fields", SickScanPointFieldArray),
165 (
"is_bigendian", ctypes.c_uint8),
166 (
"point_step", ctypes.c_uint32),
167 (
"row_step", ctypes.c_uint32),
168 (
"data", SickScanUint8Array),
169 (
"is_dense", ctypes.c_uint8),
170 (
"num_echos", ctypes.c_int32),
171 (
"segment_idx", ctypes.c_int32),
172 (
"topic", ctypes.c_char * 256)
177 sick_scan_api: struct SickScanVector3Msg, equivalent to geometry_msgs/Vector3
186 (
"x", ctypes.c_double),
187 (
"y", ctypes.c_double),
188 (
"z", ctypes.c_double)
193 sick_scan_api: struct SickScanQuaternionMsg, equivalent to geometry_msgs/Quaternion
203 (
"x", ctypes.c_double),
204 (
"y", ctypes.c_double),
205 (
"z", ctypes.c_double),
206 (
"w", ctypes.c_double)
211 sick_scan_api: struct SickScanPointArray, Array of SickScanVector3Msg, which can be serialized and imported in C, C++ or python
215 capacity : ctypes.c_uint64
216 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVector3Msg)
217 size : ctypes.c_uint64
218 Number of currently used elements in the buffer
219 buffer : ctypes.POINTER(SickScanVector3Msg)
220 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
223 (
"capacity", ctypes.c_uint64),
224 (
"size", ctypes.c_uint64),
225 (
"buffer", ctypes.POINTER(SickScanVector3Msg))
230 sick_scan_api: struct SickScanImuMsg, equivalent to ros sensor_msgs::Imu
234 header : SickScanHeader
236 orientation : SickScanQuaternionMsg
237 orientation_covariance : ctypes.c_double * 9
238 Row major about x, y, z axes
239 angular_velocity : SickScanVector3Msg
240 angular_velocity_covariance : ctypes.c_double * 9
241 Row major about x, y, z axes
242 linear_acceleration : SickScanVector3Msg
243 linear_acceleration_covariance : ctypes.c_double * 9
247 (
"header", SickScanHeader),
248 (
"orientation", SickScanQuaternionMsg),
249 (
"orientation_covariance", ctypes.c_double * 9),
250 (
"angular_velocity", SickScanVector3Msg),
251 (
"angular_velocity_covariance", ctypes.c_double * 9),
252 (
"linear_acceleration", SickScanVector3Msg),
253 (
"linear_acceleration_covariance", ctypes.c_double * 9)
258 sick_scan_api: struct SickScanLFErecFieldMsg, equivalent to LFErecFieldMsg.msg
262 version_number : ctypes.c_uint16
263 field_index : ctypes.c_uint8
264 sys_count : ctypes.c_uint32
265 dist_scale_factor : ctypes.c_float
266 dist_scale_offset : ctypes.c_float
267 angle_scale_factor : ctypes.c_uint32
268 angle_scale_offset : ctypes.c_int32
269 field_result_mrs : ctypes.c_uint8
270 field result is 0 (invalid/incorrect), 1 (free/clear) or 2 (infringed)
271 time_state : ctypes.c_uint16
272 No time data: 0, Time data: 1
273 year : ctypes.c_uint16
275 month : ctypes.c_uint8
279 hour : ctypes.c_uint8
281 minute : ctypes.c_uint8
283 second : ctypes.c_uint8
285 microsecond : ctypes.c_uint32
289 (
"version_number", ctypes.c_uint16),
290 (
"field_index", ctypes.c_uint8),
291 (
"sys_count", ctypes.c_uint32),
292 (
"dist_scale_factor", ctypes.c_float),
293 (
"dist_scale_offset", ctypes.c_float),
294 (
"angle_scale_factor", ctypes.c_uint32),
295 (
"angle_scale_offset", ctypes.c_int32),
296 (
"field_result_mrs", ctypes.c_uint8),
297 (
"time_state", ctypes.c_uint16),
298 (
"year", ctypes.c_uint16),
299 (
"month", ctypes.c_uint8),
300 (
"day", ctypes.c_uint8),
301 (
"hour", ctypes.c_uint8),
302 (
"minute", ctypes.c_uint8),
303 (
"second", ctypes.c_uint8),
304 (
"microsecond", ctypes.c_uint32)
309 sick_scan_api: struct SickScanLFErecMsg, equivalent to LFErecMsg.msg
313 header : SickScanHeader
315 fields_number : ctypes.c_uint16
316 number of valid fields
317 fields : SickScanLFErecFieldMsg * 3
321 (
"header", SickScanHeader),
322 (
"fields_number", ctypes.c_uint16),
323 (
"fields", SickScanLFErecFieldMsg * 3)
328 sick_scan_api: struct SickScanLIDoutputstateMsg, equivalent to LIDoutputstateMsg.msg
332 header : SickScanHeader
334 version_number : ctypes.c_uint16
335 Status code version number
336 system_counter : ctypes.c_uint32
337 Status code system counter (time in microsec since power up, max. 71 min then starting from 0 again)
338 output_state : ctypes.c_uint8 * 8
339 array of max. 8 output states, each state with value 0 (not active), 1 (active) or 2 (not used)
340 output_count : ctypes.c_uint32 * 8
341 array of max. 8 output counter
342 time_state : ctypes.c_uint16
343 No time data: 0, Time data: 1 (sensortime from the last change of min. one of the outputs)
344 year : ctypes.c_uint16
346 month : ctypes.c_uint8
350 hour : ctypes.c_uint8
352 minute : ctypes.c_uint8
354 second : ctypes.c_uint8
356 microsecond : ctypes.c_uint32
360 (
"header", SickScanHeader),
361 (
"version_number", ctypes.c_uint16),
362 (
"system_counter", ctypes.c_uint32),
363 (
"output_state", ctypes.c_uint8 * 8),
364 (
"output_count", ctypes.c_uint32 * 8),
365 (
"time_state", ctypes.c_uint16),
366 (
"year", ctypes.c_uint16),
367 (
"month", ctypes.c_uint8),
368 (
"day", ctypes.c_uint8),
369 (
"hour", ctypes.c_uint8),
370 (
"minute", ctypes.c_uint8),
371 (
"second", ctypes.c_uint8),
372 (
"microsecond", ctypes.c_uint32)
377 sick_scan_api: struct SickScanRadarPreHeader, equivalent to RadarPreHeader.msg
381 uiversionno : ctypes.c_uint16
383 sick_scan/RadarPreHeaderDeviceBlock:
384 uiident : ctypes.c_uint32
385 Logical number of the device"
386 udiserialno : ctypes.c_uint32
387 Serial number of the device
388 bdeviceerror : ctypes.c_uint8
390 bcontaminationwarning : ctypes.c_uint8
391 Contamination Warning
392 bcontaminationerror : ctypes.c_uint8
394 sick_scan/RadarPreHeaderStatusBlock:
395 uitelegramcount : ctypes.c_uint32
397 uicyclecount : ctypes.c_uint32
399 udisystemcountscan : ctypes.c_uint32
400 system time since power on of scan gen. [us]
401 udisystemcounttransmit : ctypes.c_uint32
402 system time since power on of scan transmission [us]
403 uiinputs : ctypes.c_uint16
404 state of digital inputs
405 uioutputs : ctypes.c_uint16
406 state of digital outputs
407 sick_scan/RadarPreHeaderMeasurementParam1Block:
408 uicycleduration : ctypes.c_uint32
409 Time in microseconds to detect this items
410 uinoiselevel : ctypes.c_uint32
412 sick_scan/RadarPreHeaderEncoderBlock[]:
413 numencoder : ctypes.c_uint16
414 number of valid encoders (0)
415 udiencoderpos : ctypes.c_uint32 * 3
416 array of max. 3 encoder position [inc]
417 iencoderspeed : ctypes.c_uint16 * 3
418 array of max. 3 encoder speed [inc/mm]
421 (
"uiversionno", ctypes.c_uint16),
423 (
"uiident", ctypes.c_uint32),
424 (
"udiserialno", ctypes.c_uint32),
425 (
"bdeviceerror", ctypes.c_uint8),
426 (
"bcontaminationwarning", ctypes.c_uint8),
427 (
"bcontaminationerror", ctypes.c_uint8),
429 (
"uitelegramcount", ctypes.c_uint32),
430 (
"uicyclecount", ctypes.c_uint32),
431 (
"udisystemcountscan", ctypes.c_uint32),
432 (
"udisystemcounttransmit", ctypes.c_uint32),
433 (
"uiinputs", ctypes.c_uint16),
434 (
"uioutputs", ctypes.c_uint16),
436 (
"uicycleduration", ctypes.c_uint32),
437 (
"uinoiselevel", ctypes.c_uint32),
439 (
"numencoder", ctypes.c_uint16),
440 (
"udiencoderpos", ctypes.c_uint32 * 3),
441 (
"iencoderspeed", ctypes.c_uint16 * 3)
446 sick_scan_api: struct SickScanRadarObject, equivalent to RadarObject.msg
451 tracking_time_sec : ctypes.c_uint32
452 seconds part of tracking_time (since when the object is tracked): seconds (stamp_secs) since epoch
453 tracking_time_nsec : ctypes.c_uint32
454 nanoseconds part of tracking_time (since when the object is tracked): nanoseconds since stamp_secs
455 last_seen_sec : ctypes.c_uint32
456 seconds part of last_seen timestamp: seconds (stamp_secs) since epoch
457 last_seen_nsec : ctypes.c_uint32
458 nanoseconds part of last_seen timestamp: nanoseconds since stamp_secs
459 # geometry_msgs/TwistWithCovariance velocity
460 velocity_linear : SickScanVector3Msg
461 velocity_angular : SickScanVector3Msg
462 velocity_covariance : ctypes.c_double * 36
463 Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
464 # geometry_msgs/Pose bounding_box_center
465 bounding_box_center_position : SickScanVector3Msg
466 bounding_box_center_orientation : SickScanQuaternionMsg
467 geometry_msgs/Vector3 bounding_box_size
468 bounding_box_size : SickScanVector3Msg
469 # geometry_msgs/PoseWithCovariance object_box_center
470 object_box_center_position : SickScanVector3Msg
471 object_box_center_orientation : SickScanQuaternionMsg
472 object_box_center_covariance : ctypes.c_double * 36
473 Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
474 # geometry_msgs/Vector3 object_box_size
475 object_box_size : SickScanVector3Msg
476 geometry_msgs/Point[] contour_points
477 contour_points : SickScanPointArray)
480 (
"id", ctypes.c_int32),
481 (
"tracking_time_sec", ctypes.c_uint32),
482 (
"tracking_time_nsec", ctypes.c_uint32),
483 (
"last_seen_sec", ctypes.c_uint32),
484 (
"last_seen_nsec", ctypes.c_uint32),
486 (
"velocity_linear", SickScanVector3Msg),
487 (
"velocity_angular", SickScanVector3Msg),
488 (
"velocity_covariance", ctypes.c_double * 36),
490 (
"bounding_box_center_position", SickScanVector3Msg),
491 (
"bounding_box_center_orientation", SickScanQuaternionMsg),
493 (
"bounding_box_size", SickScanVector3Msg),
495 (
"object_box_center_position", SickScanVector3Msg),
496 (
"object_box_center_orientation", SickScanQuaternionMsg),
497 (
"object_box_center_covariance", ctypes.c_double * 36),
499 (
"object_box_size", SickScanVector3Msg),
501 (
"contour_points", SickScanPointArray)
506 sick_scan_api: struct SickScanRadarObjectArray, Array of SickScanRadarObject
510 capacity : ctypes.c_uint64
511 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanRadarObject)
512 size : ctypes.c_uint64
513 Number of currently used elements in the buffer
514 buffer : ctypes.POINTER(SickScanRadarObject)
515 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
518 (
"capacity", ctypes.c_uint64),
519 (
"size", ctypes.c_uint64),
520 (
"buffer", ctypes.POINTER(SickScanRadarObject))
525 sick_scan_api: struct SickScanRadarScan, equivalent to RadarScan.msg
529 header : SickScanHeader
531 radarpreheader : SickScanRadarPreHeader
533 targets : SickScanPointCloudMsg
534 sensor_msgs/PointCloud2
535 objects : SickScanRadarObjectArray
536 Array of RadarObject.msg
539 (
"header", SickScanHeader),
540 (
"radarpreheader", SickScanRadarPreHeader),
541 (
"targets", SickScanPointCloudMsg),
542 (
"objects", SickScanRadarObjectArray)
547 sick_scan_api: struct SickScanLdmrsObject, equivalent to SickLdmrsObject.msg
553 sick_scan_api: struct SickScanLdmrsObjectBuffer, Array of SickScanLdmrsObject
557 capacity : ctypes.c_uint64
558 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanLdmrsObject)
559 size : ctypes.c_uint64
560 Number of currently used elements in the buffer
561 buffer : ctypes.POINTER(SickScanLdmrsObject)
562 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
565 (
"capacity", ctypes.c_uint64),
566 (
"size", ctypes.c_uint64),
567 (
"buffer", ctypes.POINTER(SickScanLdmrsObject))
572 sick_scan_api: struct SickScanLdmrsObjectArray, equivalent to SickLdmrsObjectArray.msg
576 header : SickScanHeader
578 objects : SickScanLdmrsObjectBuffer
579 Array of SickScanLdmrsObjects
582 (
"header", SickScanHeader),
583 (
"objects", SickScanLdmrsObjectBuffer)
588 equivalent to std_msgs::ColorRGBA
598 (
"r", ctypes.c_float),
599 (
"g", ctypes.c_float),
600 (
"b", ctypes.c_float),
601 (
"a", ctypes.c_float)
606 Array of SickScanColorRGBA, which can be serialized and imported in C, C++ or python
610 capacity : ctypes.c_uint64
611 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanColorRGBA)
612 size : ctypes.c_uint64
613 Number of currently used elements in the buffer
614 buffer : ctypes.POINTER(SickScanColorRGBA)
615 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
618 (
"capacity", ctypes.c_uint64),
619 (
"size", ctypes.c_uint64),
620 (
"buffer", ctypes.POINTER(SickScanColorRGBA))
625 equivalent to visualization_msgs::Marker
629 header : SickScanHeader
631 ns : ctypes.c_char * 1024
632 Namespace to place this object in... used in conjunction with id to create a unique name for the object
634 object ID useful in conjunction with the namespace for manipulating and deleting the object later
635 type : ctypes.c_int32
637 action : ctypes.c_int32
638 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects
639 pose_position : SickScanVector3Msg
640 Pose of the object (positional part)
641 pose_orientation : SickScanQuaternionMsg
642 Pose of the object (rotational part)
643 scale : SickScanVector3Msg
644 Scale of the object 1,1,1 means default (usually 1 meter square)
645 color : SickScanColorRGBA
647 lifetime_sec : ctypes.c_uint32
648 How long the object should last before being automatically deleted. 0 means forever (seconds part)
649 lifetime_nsec : ctypes.c_uint32
650 How long the object should last before being automatically deleted. 0 means forever (nanoseconds part)
651 frame_locked : ctypes.c_uint8
652 boolean, If this marker should be frame-locked, i.e. retransformed into its frame every timestep
653 points : SickScanPointArray
654 Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
655 colors : SickScanColorRGBAArray
656 Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...). Number of colors must either be 0 or equal to the number of points. NOTE: alpha is not yet used
657 text : ctypes.c_char * 1024
658 NOTE: only used for text markers
659 mesh_resource : ctypes.c_char * 1024
660 NOTE: only used for MESH_RESOURCE markers
661 mesh_use_embedded_materials : ctypes.c_uint8
665 (
"header", SickScanHeader),
666 (
"ns", ctypes.c_char * 1024),
667 (
"id", ctypes.c_int32),
668 (
"type", ctypes.c_int32),
669 (
"action", ctypes.c_int32),
670 (
"pose_position", SickScanVector3Msg),
671 (
"pose_orientation", SickScanQuaternionMsg),
672 (
"scale", SickScanVector3Msg),
673 (
"color", SickScanColorRGBA),
674 (
"lifetime_sec", ctypes.c_uint32),
675 (
"lifetime_nsec", ctypes.c_uint32),
676 (
"frame_locked", ctypes.c_uint8),
677 (
"points", SickScanPointArray),
678 (
"colors", SickScanColorRGBAArray),
679 (
"text", ctypes.c_char * 1024),
680 (
"mesh_resource", ctypes.c_char * 1024),
681 (
"mesh_use_embedded_materials", ctypes.c_uint8)
686 Array of SickScanVisualizationMarkers
690 capacity : ctypes.c_uint64
691 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVisualizationMarker)
692 size : ctypes.c_uint64
693 Number of currently used elements in the buffer
694 buffer : ctypes.POINTER(SickScanVisualizationMarker)
695 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
698 (
"capacity", ctypes.c_uint64),
699 (
"size", ctypes.c_uint64),
700 (
"buffer", ctypes.POINTER(SickScanVisualizationMarker))
705 equivalent to visualization_msgs::MarkerArray
709 markers : SickScanVisualizationMarkerBuffer
710 Array of SickScanVisualizationMarkers
713 (
"markers", SickScanVisualizationMarkerBuffer)
718 NAV-350 reflector equivalent to SickScanNavReflector defined in sick_scan_api.h
721 (
"pos_valid", ctypes.c_uint16),
723 (
"pos_x", ctypes.c_float),
724 (
"pos_y", ctypes.c_float),
725 (
"cartesian_valid", ctypes.c_uint16),
727 (
"cartesian_x", ctypes.c_int32),
728 (
"cartesian_y", ctypes.c_int32),
729 (
"polar_valid", ctypes.c_uint16),
731 (
"polar_dist", ctypes.c_uint32),
732 (
"polar_phi", ctypes.c_uint32),
733 (
"opt_valid", ctypes.c_uint16),
735 (
"opt_local_id", ctypes.c_uint16),
736 (
"opt_global_id", ctypes.c_uint16),
737 (
"opt_type", ctypes.c_uint8),
738 (
"opt_subtype", ctypes.c_uint16),
739 (
"opt_quality", ctypes.c_uint16),
740 (
"opt_timestamp", ctypes.c_uint32),
741 (
"opt_size", ctypes.c_uint16),
742 (
"opt_hitcount", ctypes.c_uint16),
743 (
"opt_meanecho", ctypes.c_uint16),
744 (
"opt_startindex", ctypes.c_uint16),
745 (
"opt_endindex", ctypes.c_uint16),
746 (
"opt_timestamp_sec", ctypes.c_uint32),
747 (
"opt_timestamp_nsec", ctypes.c_uint32)
752 Array of NAV-350 reflectors equivalent to SickScanNavReflectorBuffer defined in sick_scan_api.h
756 capacity : ctypes.c_uint64
757 Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanNavReflector)
758 size : ctypes.c_uint64
759 Number of currently used elements in the buffer
760 buffer : ctypes.POINTER(SickScanNavReflector)
761 Memory, data in plain order and system endianess (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
764 (
"capacity", ctypes.c_uint64),
765 (
"size", ctypes.c_uint64),
766 (
"buffer", ctypes.POINTER(SickScanNavReflector))
771 NAV-350 pose and landmark message equivalent to SickScanNavPoseLandmarkMsg defined in sick_scan_api.h
774 (
"pose_valid", ctypes.c_uint16),
776 (
"pose_x", ctypes.c_float),
777 (
"pose_y", ctypes.c_float),
778 (
"pose_yaw", ctypes.c_float),
779 (
"pose_timestamp_sec", ctypes.c_uint32),
780 (
"pose_timestamp_nsec", ctypes.c_uint32),
781 (
"pose_nav_x", ctypes.c_int32),
782 (
"pose_nav_y", ctypes.c_int32),
783 (
"pose_nav_phi", ctypes.c_uint32),
784 (
"pose_opt_valid", ctypes.c_uint16),
786 (
"pose_opt_output_mode", ctypes.c_uint8),
787 (
"pose_opt_timestamp", ctypes.c_uint32),
788 (
"pose_opt_mean_dev", ctypes.c_int32),
789 (
"pose_opt_nav_mode", ctypes.c_uint8),
790 (
"pose_opt_info_state", ctypes.c_uint32),
791 (
"pose_opt_quant_used_reflectors", ctypes.c_uint8),
793 (
"reflectors", SickScanNavReflectorBuffer)
798 NAV-350 velocity/odometry data in nav coordinates, see NAVOdomVelocity.msg
801 (
"vel_x", ctypes.c_float),
802 (
"vel_y", ctypes.c_float),
803 (
"omega", ctypes.c_float),
804 (
"timestamp", ctypes.c_uint32),
805 (
"coordbase", ctypes.c_uint8)
810 Velocity/odometry data in ros coordinates
813 (
"vel_x", ctypes.c_float),
814 (
"vel_y", ctypes.c_float),
815 (
"omega", ctypes.c_float),
816 (
"timestamp_sec", ctypes.c_uint32),
817 (
"timestamp_nsec", ctypes.c_uint32)
825 (
"log_level", ctypes.c_int32),
826 (
"log_message", ctypes.c_char_p)
834 (
"status_code", ctypes.c_int32),
835 (
"status_message", ctypes.c_char_p)
840 Error codes, return values of SickScanApi-functions
844 SICK_SCAN_API_SUCCESS = 0, "SICK_SCAN_API_SUCCESS" # function executed successfully
845 SICK_SCAN_API_ERROR = 1, "SICK_SCAN_API_ERROR" # general (unspecified) error
846 SICK_SCAN_API_NOT_LOADED = 2, "SICK_SCAN_API_NOT_LOADED" # sick_scan_xd library not loaded
847 SICK_SCAN_API_NOT_INITIALIZED = 3, "SICK_SCAN_API_NOT_INITIALIZED" # API not initialized
848 SICK_SCAN_API_NOT_IMPLEMENTED = 4, "SICK_SCAN_API_NOT_IMPLEMENTED" # function not implemented in sick_scan_xd library
849 SICK_SCAN_API_TIMEOUT = 5, "SICK_SCAN_API_TIMEOUT" # timeout during wait for response
851 SICK_SCAN_API_SUCCESS = 0,
"SICK_SCAN_API_SUCCESS"
852 SICK_SCAN_API_ERROR = 1,
"SICK_SCAN_API_ERROR"
853 SICK_SCAN_API_NOT_LOADED = 2,
"SICK_SCAN_API_NOT_LOADED"
854 SICK_SCAN_API_NOT_INITIALIZED = 3,
"SICK_SCAN_API_NOT_INITIALIZED"
855 SICK_SCAN_API_NOT_IMPLEMENTED = 4,
"SICK_SCAN_API_NOT_IMPLEMENTED"
856 SICK_SCAN_API_TIMEOUT = 5,
"SICK_SCAN_API_TIMEOUT"
863 Callback declarations
866 SickScanPointCloudMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg))
867 SickScanImuMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanImuMsg))
868 SickScanLFErecMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanLFErecMsg))
869 SickScanLIDoutputstateMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanLIDoutputstateMsg))
870 SickScanRadarScanCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanRadarScan))
871 SickScanLdmrsObjectArrayCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanLdmrsObjectArray))
872 SickScanVisualizationMarkerCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanVisualizationMarkerMsg))
873 SickScanNavPoseLandmarkCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanNavPoseLandmarkMsg))
874 SickScanLogMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanLogMsg))
875 SickScanDiagnosticMsgCallback = ctypes.CFUNCTYPE(
None, ctypes.c_void_p, ctypes.POINTER(SickScanDiagnosticMsg))
879 Functions to initialize and close the API and a lidar
884 Returns a python string from a zero terminated ctypes char array
886 return ''.join([chr(i)
for i
in char_array]).rstrip(
'\x00')
890 loads and returns a library, given its filename and a list of folder
893 filename = path + lib_filname
894 if os.path.exists(filename):
895 return ctypes.CDLL(filename)
896 return ctypes.CDLL(lib_filname)
900 Load sick_scan_library and functions
902 sick_scan_library =
loadLibrary(paths, lib_filname)
904 sick_scan_library.SickScanApiCreate.argtypes = [ctypes.c_int, ctypes.POINTER(ctypes.c_char_p)]
905 sick_scan_library.SickScanApiCreate.restype = ctypes.c_void_p
907 sick_scan_library.SickScanApiRelease.argtypes = [ctypes.c_void_p]
908 sick_scan_library.SickScanApiRelease.restype = ctypes.c_int
910 sick_scan_library.SickScanApiInitByLaunchfile.argtypes = [ctypes.c_void_p, ctypes.c_char_p]
911 sick_scan_library.SickScanApiInitByLaunchfile.restype = ctypes.c_int
913 sick_scan_library.SickScanApiInitByCli.argtypes = [ctypes.c_void_p, ctypes.c_int, ctypes.POINTER(ctypes.c_char_p)]
914 sick_scan_library.SickScanApiInitByCli.restype = ctypes.c_int
916 sick_scan_library.SickScanApiClose.argtypes = [ctypes.c_void_p]
917 sick_scan_library.SickScanApiClose.restype = ctypes.c_int
919 sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
920 sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg.restype = ctypes.c_int
922 sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
923 sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg.restype = ctypes.c_int
925 sick_scan_library.SickScanApiRegisterPolarPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
926 sick_scan_library.SickScanApiRegisterPolarPointCloudMsg.restype = ctypes.c_int
928 sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
929 sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg.restype = ctypes.c_int
931 sick_scan_library.SickScanApiRegisterImuMsg.argtypes = [ctypes.c_void_p, SickScanImuMsgCallback]
932 sick_scan_library.SickScanApiRegisterImuMsg.restype = ctypes.c_int
934 sick_scan_library.SickScanApiDeregisterImuMsg.argtypes = [ctypes.c_void_p, SickScanImuMsgCallback]
935 sick_scan_library.SickScanApiDeregisterImuMsg.restype = ctypes.c_int
937 sick_scan_library.SickScanApiRegisterLFErecMsg.argtypes = [ctypes.c_void_p, SickScanLFErecMsgCallback]
938 sick_scan_library.SickScanApiRegisterLFErecMsg.restype = ctypes.c_int
940 sick_scan_library.SickScanApiDeregisterLFErecMsg.argtypes = [ctypes.c_void_p, SickScanLFErecMsgCallback]
941 sick_scan_library.SickScanApiDeregisterLFErecMsg.restype = ctypes.c_int
943 sick_scan_library.SickScanApiRegisterLIDoutputstateMsg.argtypes = [ctypes.c_void_p, SickScanLIDoutputstateMsgCallback]
944 sick_scan_library.SickScanApiRegisterLIDoutputstateMsg.restype = ctypes.c_int
946 sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg.argtypes = [ctypes.c_void_p, SickScanLIDoutputstateMsgCallback]
947 sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg.restype = ctypes.c_int
949 sick_scan_library.SickScanApiRegisterRadarScanMsg.argtypes = [ctypes.c_void_p, SickScanRadarScanCallback]
950 sick_scan_library.SickScanApiRegisterRadarScanMsg.restype = ctypes.c_int
952 sick_scan_library.SickScanApiDeregisterRadarScanMsg.argtypes = [ctypes.c_void_p, SickScanRadarScanCallback]
953 sick_scan_library.SickScanApiDeregisterRadarScanMsg.restype = ctypes.c_int
955 sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, SickScanLdmrsObjectArrayCallback]
956 sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg.restype = ctypes.c_int
958 sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, SickScanLdmrsObjectArrayCallback]
959 sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg.restype = ctypes.c_int
961 sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, SickScanVisualizationMarkerCallback]
962 sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg.restype = ctypes.c_int
964 sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, SickScanVisualizationMarkerCallback]
965 sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg.restype = ctypes.c_int
967 sick_scan_library.SickScanApiRegisterDiagnosticMsg.argtypes = [ctypes.c_void_p, SickScanDiagnosticMsgCallback]
968 sick_scan_library.SickScanApiRegisterDiagnosticMsg.restype = ctypes.c_int
970 sick_scan_library.SickScanApiDeregisterDiagnosticMsg.argtypes = [ctypes.c_void_p, SickScanDiagnosticMsgCallback]
971 sick_scan_library.SickScanApiDeregisterDiagnosticMsg.restype = ctypes.c_int
973 sick_scan_library.SickScanApiRegisterLogMsg.argtypes = [ctypes.c_void_p, SickScanLogMsgCallback]
974 sick_scan_library.SickScanApiRegisterLogMsg.restype = ctypes.c_int
976 sick_scan_library.SickScanApiDeregisterLogMsg.argtypes = [ctypes.c_void_p, SickScanLogMsgCallback]
977 sick_scan_library.SickScanApiDeregisterLogMsg.restype = ctypes.c_int
979 sick_scan_library.SickScanApiGetStatus.argtypes = [ctypes.c_void_p, ctypes.POINTER(ctypes.c_int32), ctypes.c_char_p, ctypes.c_int32]
980 sick_scan_library.SickScanApiGetStatus.restype = ctypes.c_int
982 sick_scan_library.SickScanApiSendSOPAS.argtypes = [ctypes.c_void_p, ctypes.c_char_p, ctypes.c_char_p, ctypes.c_int32]
983 sick_scan_library.SickScanApiSendSOPAS.restype = ctypes.c_int
985 sick_scan_library.SickScanApiSetVerboseLevel.argtypes = [ctypes.c_void_p, ctypes.c_int32]
986 sick_scan_library.SickScanApiSetVerboseLevel.restype = ctypes.c_int
988 sick_scan_library.SickScanApiGetVerboseLevel.argtypes = [ctypes.c_void_p]
989 sick_scan_library.SickScanApiGetVerboseLevel.restype = ctypes.c_int
991 sick_scan_library.SickScanApiWaitNextCartesianPointCloudMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg), ctypes.c_double]
992 sick_scan_library.SickScanApiWaitNextCartesianPointCloudMsg.restype = ctypes.c_int
994 sick_scan_library.SickScanApiWaitNextPolarPointCloudMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg), ctypes.c_double]
995 sick_scan_library.SickScanApiWaitNextPolarPointCloudMsg.restype = ctypes.c_int
997 sick_scan_library.SickScanApiFreePointCloudMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg)]
998 sick_scan_library.SickScanApiFreePointCloudMsg.restype = ctypes.c_int
1000 sick_scan_library.SickScanApiWaitNextImuMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanImuMsg), ctypes.c_double]
1001 sick_scan_library.SickScanApiWaitNextImuMsg.restype = ctypes.c_int
1003 sick_scan_library.SickScanApiFreeImuMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanImuMsg)]
1004 sick_scan_library.SickScanApiFreeImuMsg.restype = ctypes.c_int
1006 sick_scan_library.SickScanApiWaitNextLFErecMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLFErecMsg), ctypes.c_double]
1007 sick_scan_library.SickScanApiWaitNextLFErecMsg.restype = ctypes.c_int
1009 sick_scan_library.SickScanApiFreeLFErecMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLFErecMsg)]
1010 sick_scan_library.SickScanApiFreeLFErecMsg.restype = ctypes.c_int
1012 sick_scan_library.SickScanApiWaitNextLIDoutputstateMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLIDoutputstateMsg), ctypes.c_double]
1013 sick_scan_library.SickScanApiWaitNextLIDoutputstateMsg.restype = ctypes.c_int
1015 sick_scan_library.SickScanApiFreeLIDoutputstateMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLIDoutputstateMsg)]
1016 sick_scan_library.SickScanApiFreeLIDoutputstateMsg.restype = ctypes.c_int
1018 sick_scan_library.SickScanApiWaitNextRadarScanMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanRadarScan), ctypes.c_double]
1019 sick_scan_library.SickScanApiWaitNextRadarScanMsg.restype = ctypes.c_int
1021 sick_scan_library.SickScanApiFreeRadarScanMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanRadarScan)]
1022 sick_scan_library.SickScanApiFreeRadarScanMsg.restype = ctypes.c_int
1024 sick_scan_library.SickScanApiWaitNextLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLdmrsObjectArray), ctypes.c_double]
1025 sick_scan_library.SickScanApiWaitNextLdmrsObjectArrayMsg.restype = ctypes.c_int
1027 sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLdmrsObjectArray)]
1028 sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg.restype = ctypes.c_int
1030 sick_scan_library.SickScanApiWaitNextVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanVisualizationMarkerMsg), ctypes.c_double]
1031 sick_scan_library.SickScanApiWaitNextVisualizationMarkerMsg.restype = ctypes.c_int
1033 sick_scan_library.SickScanApiFreeVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanVisualizationMarkerMsg)]
1034 sick_scan_library.SickScanApiFreeVisualizationMarkerMsg.restype = ctypes.c_int
1036 sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, SickScanNavPoseLandmarkCallback]
1037 sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg.restype = ctypes.c_int
1039 sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, SickScanNavPoseLandmarkCallback]
1040 sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg.restype = ctypes.c_int
1042 sick_scan_library.SickScanApiWaitNextNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanNavPoseLandmarkMsg), ctypes.c_double]
1043 sick_scan_library.SickScanApiWaitNextNavPoseLandmarkMsg.restype = ctypes.c_int
1045 sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanNavPoseLandmarkMsg)]
1046 sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg.restype = ctypes.c_int
1048 sick_scan_library.SickScanApiNavOdomVelocityMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanNavOdomVelocityMsg)]
1049 sick_scan_library.SickScanApiNavOdomVelocityMsg.restype = ctypes.c_int
1051 sick_scan_library.SickScanApiOdomVelocityMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanOdomVelocityMsg)]
1052 sick_scan_library.SickScanApiOdomVelocityMsg.restype = ctypes.c_int
1053 return sick_scan_library
1057 Unload sick_scan_xd api library
1059 del sick_scan_library
1063 Create an instance of sick_scan_xd api.
1064 Call SickScanApiInitByLaunchfile or SickScanApiInitByCli to process a lidar.
1066 null_ptr = ctypes.POINTER(ctypes.c_char_p)()
1067 api_handle = sick_scan_library.SickScanApiCreate(0, null_ptr)
1072 Release and free all resources of the api handle; the handle is invalid after SickScanApiRelease
1074 return sick_scan_library.SickScanApiRelease(api_handle)
1078 Initialize a lidar by launchfile and start message receiving and processing
1080 return sick_scan_library.SickScanApiInitByLaunchfile(api_handle, ctypes.create_string_buffer(str.encode(launchfile_args)))
1084 Release and free all resources of the api handle; the handle is invalid after SickScanApiRelease
1086 return sick_scan_library.SickScanApiClose(api_handle)
1089 Registration and deregistration of message callbacks
1094 Register a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
1096 return sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg(api_handle, pointcloud_callback)
1100 Deregister a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
1102 return sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg(api_handle, pointcloud_callback)
1106 Register a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
1108 return sick_scan_library.SickScanApiRegisterPolarPointCloudMsg(api_handle, pointcloud_callback)
1112 Deregister a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
1114 return sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg(api_handle, pointcloud_callback)
1118 Register a callback for Imu messages
1120 return sick_scan_library.SickScanApiRegisterImuMsg(api_handle, imu_callback)
1124 Deregister a callback for Imu messages
1126 return sick_scan_library.SickScanApiDeregisterImuMsg(api_handle, imu_callback)
1130 Register a callback for LFErec messages
1132 return sick_scan_library.SickScanApiRegisterLFErecMsg(api_handle, lferec_callback)
1136 Deregister a callback for LFErec messages
1138 return sick_scan_library.SickScanApiDeregisterLFErecMsg(api_handle, lferec_callback)
1142 Register a callback for LIDoutputstate messages
1144 return sick_scan_library.SickScanApiRegisterLIDoutputstateMsg(api_handle, lidoutputstate_callback)
1148 Deregister a callback for LIDoutputstate messages
1150 return sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg(api_handle, lidoutputstate_callback)
1154 Register a callback for RadarScan messages
1156 return sick_scan_library.SickScanApiRegisterRadarScanMsg(api_handle, radarscan_callback)
1160 Deregister a callback for RadarScan messages
1162 return sick_scan_library.SickScanApiDeregisterRadarScanMsg(api_handle, radarscan_callback)
1166 Register a callback for LdmrsObjectArray messages
1168 return sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg(api_handle, ldmrsobjectarray_callback)
1172 Deregister a callback for LdmrsObjectArray messages
1174 return sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg(api_handle, ldmrsobjectarray_callback)
1178 Register a callback for VisualizationMarker messages
1180 return sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg(api_handle, ldmrsobjectarray_callback)
1184 Deregister a callback for VisualizationMarker messages
1186 return sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg(api_handle, ldmrsobjectarray_callback)
1190 Register a callback for SickScanNavPoseLandmarkMsg messages
1192 return sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg(api_handle, callback)
1196 Deregister a callback for SickScanNavPoseLandmarkMsg messages
1198 return sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg(api_handle, callback)
1201 Diagnostic functions
1206 Register a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
1208 return sick_scan_library.SickScanApiRegisterDiagnosticMsg(api_handle, callback)
1212 Deregister a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
1214 return sick_scan_library.SickScanApiDeregisterDiagnosticMsg(api_handle, callback)
1218 Register a callback for log messages (all informational and error messages)
1220 return sick_scan_library.SickScanApiRegisterLogMsg(api_handle, callback)
1224 Deregister a callback for log messages (all informational and error messages)
1226 return sick_scan_library.SickScanApiDeregisterLogMsg(api_handle, callback)
1230 Query current status and status message
1232 return sick_scan_library.SickScanApiGetStatus(api_handle, status_code, message_buffer, message_buffer_size)
1237 Sends a SOPAS command like "sRN SCdevicestate" or "sRN ContaminationResult" and returns the lidar response
1239 response_buffer_size = max(1024, response_buffer_size)
1240 ctypes_response_buffer = ctypes.create_string_buffer(response_buffer_size + 1)
1241 ret_val = sick_scan_library.SickScanApiSendSOPAS(api_handle, ctypes.create_string_buffer(str.encode(sopas_command)), ctypes_response_buffer, response_buffer_size)
1246 return ctypes_response_buffer.value.decode()
1250 Set verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET (equivalent to ros::console::levels),
1251 i.e. print messages on console above the given verbose level.
1252 Default verbose level is 1 (INFO), i.e. print informational, warnings and error messages.
1254 return sick_scan_library.SickScanApiSetVerboseLevel(api_handle, verbose_level)
1258 Returns the current verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET. Default verbose level is 1 (INFO)
1260 return sick_scan_library.SickScanApiGetVerboseLevel(api_handle)
1268 Wait for and return the next cartesian PointCloud message
1270 return sick_scan_library.SickScanApiWaitNextCartesianPointCloudMsg(api_handle, msg, timeout_sec)
1274 Wait for and return the next polar PointCloud message
1276 return sick_scan_library.SickScanApiWaitNextPolarPointCloudMsg(api_handle, msg, timeout_sec)
1280 Deallocate a PointCloud message, use after SickScanApiWaitNextCartesianPointCloudMsg resp. SickScanApiWaitNextPolarPointCloudMsg
1282 return sick_scan_library.SickScanApiFreePointCloudMsg(api_handle, msg)
1286 Wait for and return the next Imu message
1288 return sick_scan_library.SickScanApiWaitNextImuMsg(api_handle, msg, timeout_sec)
1292 Deallocate a Imu message, use after SickScanApiWaitNextImuMsg
1294 return sick_scan_library.SickScanApiFreeImuMsg(api_handle, msg)
1298 Wait for and return the next LFErec message
1300 return sick_scan_library.SickScanApiWaitNextLFErecMsg(api_handle, msg, timeout_sec)
1304 Deallocate a LFErec message, use after SickScanApiWaitNextLFErecMsg
1306 return sick_scan_library.SickScanApiFreeLFErecMsg(api_handle, msg)
1310 Wait for and return the next LIDoutputstate message
1312 return sick_scan_library.SickScanApiWaitNextLIDoutputstateMsg(api_handle, msg, timeout_sec)
1316 Deallocate a LIDoutputstate message, use after SickScanApiWaitNextLIDoutputstateMsg
1318 return sick_scan_library.SickScanApiFreeLIDoutputstateMsg(api_handle, msg)
1322 Wait for and return the next RadarScan message
1324 return sick_scan_library.SickScanApiWaitNextRadarScanMsg(api_handle, msg, timeout_sec)
1328 Deallocate a RadarScan message, use after SickScanApiWaitNextRadarScanMsg
1330 return sick_scan_library.SickScanApiFreeRadarScanMsg(api_handle, msg)
1334 Wait for and return the next LdmrsObjectArray message
1336 return sick_scan_library.SickScanApiWaitNextLdmrsObjectArrayMsg(api_handle, msg, timeout_sec)
1340 Deallocate a LdmrsObjectArray message, use after SickScanApiWaitNextLdmrsObjectArrayMsg
1342 return sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg(api_handle, msg)
1346 Wait for and return the next VisualizationMarker message
1348 return sick_scan_library.SickScanApiWaitNextVisualizationMarkerMsg(api_handle, msg, timeout_sec)
1352 Deallocate a VisualizationMarker message, use after SickScanApiWaitNextVisualizationMarkerMsg
1354 return sick_scan_library.SickScanApiFreeVisualizationMarkerMsg(api_handle, msg)
1358 Wait for and return the next SickScanNavPoseLandmarkMsg message
1360 return sick_scan_library.SickScanApiWaitNextNavPoseLandmarkMsg(api_handle, msg, timeout_sec)
1364 Deallocate a SickScanNavPoseLandmarkMsg message, use after SickScanApiWaitNextNavPoseLandmarkMsg
1366 return sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg(api_handle, msg)
1370 Send NAV350 velocity/odometry data in nav coordinates
1372 return sick_scan_library.SickScanApiNavOdomVelocityMsg(api_handle, msg)
1376 Send velocity/odometry data in ros coordinates
1378 return sick_scan_library.SickScanApiOdomVelocityMsg(api_handle, msg)