sick_scan_api.py
Go to the documentation of this file.
1 """This file declares the functions and datatypes of the sick_scan_xd python-API.
2 
3 See doc/sick_scan_api/sick_scan_api.md for further information.
4 
5 """
6 
7 import ctypes
8 import numpy as np
9 import os
10 from enum import Enum
11 
12 """
13 Message definitions
14 """
15 
16 class SickScanHeader(ctypes.Structure):
17  """
18  sick_scan_api: struct SickScanHeader, equivalent to ros::std_msgs::Header
19 
20  Attributes
21  ----------
22  seq : ctypes.c_uint32
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
30  """
31  _fields_ = [
32  ("seq", ctypes.c_uint32), # sequence ID: consecutively increasing ID
33  ("timestamp_sec", ctypes.c_uint32), # seconds part of message timestamps: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
34  ("timestamp_nsec", ctypes.c_uint32), # seconds part of message timestamps: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
35  ("frame_id", ctypes.c_char * 256) # Frame this data is associated with
36  ]
37 
38 class SickScanUint8Array(ctypes.Structure):
39  """
40  equivalent to sick_scan_api.h struct SickScanUint8Array
41 
42  Attributes
43  ----------
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.
50  """
51  _fields_ = [
52  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanPointFieldMsg)
53  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
54  ("buffer", ctypes.POINTER(ctypes.c_uint8)) # 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.
55  ]
56 
58  """
59  This message holds the description of one point entry in the PointCloud2 message format, equivalent to type enum im ros::sensor_msgs::PointField
60  """
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"
69  def __int__(self):
70  return self.value[0]
71  def __str__(self):
72  return self.value[1]
73 
74 
75 class SickScanPointFieldMsg(ctypes.Structure):
76  """
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) ]
89 
90  Attributes
91  ----------
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
100  """
101  _fields_ = [
102  ("name", ctypes.c_char * 256), # Name of field (max. length 256 characters)
103  ("offset", ctypes.c_uint32), # Offset from start of point struct
104  ("datatype", ctypes.c_uint8), # Datatype enumeration, see SickScanNativeDataType, equivalent to type enum im ros::sensor_msgs::PointField
105  ("count", ctypes.c_uint32) # How many elements in the field
106  ]
107 
108 class SickScanPointFieldArray(ctypes.Structure):
109  """
110  sick_scan_api: struct SickScanPointFieldArray, Array of SickScanPointFieldMsg, which can be serialized and imported in C, C++ or python
111 
112  Attributes
113  ----------
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.
120  """
121  _fields_ = [
122  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanPointFieldMsg)
123  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
124  ("buffer", ctypes.POINTER(SickScanPointFieldMsg)) # 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.
125  ]
126 
127 class SickScanPointCloudMsg(ctypes.Structure):
128  """
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.
134 
135  Attributes
136  ----------
137  header : SickScanHeader
138  message timestamp
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
156  number of echos
157  segment_idx : ctypes.c_int32
158  segment index (or -1 if pointcloud contains data from multiple segments)
159  """
160  _fields_ = [
161  ("header", SickScanHeader), # message timestamp
162  ("height", ctypes.c_uint32), # 2D structure of the point cloud. If the cloud is unordered, height is 1
163  ("width", ctypes.c_uint32), # and width is the length of the point cloud.
164  ("fields", SickScanPointFieldArray), # Describes the channels and their layout in the binary data blob.
165  ("is_bigendian", ctypes.c_uint8), # Is this data bigendian?
166  ("point_step", ctypes.c_uint32), # Length of a point in bytes
167  ("row_step", ctypes.c_uint32), # Length of a row in bytes
168  ("data", SickScanUint8Array), # Actual point data, size is (row_step*height)
169  ("is_dense", ctypes.c_uint8), # True if there are no invalid points
170  ("num_echos", ctypes.c_int32), # number of echos
171  ("segment_idx", ctypes.c_int32), # segment index (or -1 if pointcloud contains data from multiple segments)
172  ("topic", ctypes.c_char * 256) # ros topic this pointcloud is published
173  ]
174 
175 class SickScanVector3Msg(ctypes.Structure):
176  """
177  sick_scan_api: struct SickScanVector3Msg, equivalent to geometry_msgs/Vector3
178 
179  Attributes
180  ----------
181  x : ctypes.c_double
182  y : ctypes.c_double
183  z : ctypes.c_double
184  """
185  _fields_ = [
186  ("x", ctypes.c_double),
187  ("y", ctypes.c_double),
188  ("z", ctypes.c_double)
189  ]
190 
191 class SickScanQuaternionMsg(ctypes.Structure):
192  """
193  sick_scan_api: struct SickScanQuaternionMsg, equivalent to geometry_msgs/Quaternion
194 
195  Attributes
196  ----------
197  x : ctypes.c_double
198  y : ctypes.c_double
199  z : ctypes.c_double
200  w : ctypes.c_double
201  """
202  _fields_ = [
203  ("x", ctypes.c_double),
204  ("y", ctypes.c_double),
205  ("z", ctypes.c_double),
206  ("w", ctypes.c_double)
207  ]
208 
209 class SickScanPointArray(ctypes.Structure):
210  """
211  sick_scan_api: struct SickScanPointArray, Array of SickScanVector3Msg, which can be serialized and imported in C, C++ or python
212 
213  Attributes
214  ----------
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.
221  """
222  _fields_ = [
223  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVector3Msg)
224  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
225  ("buffer", ctypes.POINTER(SickScanVector3Msg)) # 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.
226  ]
227 
228 class SickScanImuMsg(ctypes.Structure):
229  """
230  sick_scan_api: struct SickScanImuMsg, equivalent to ros sensor_msgs::Imu
231 
232  Attributes
233  ----------
234  header : SickScanHeader
235  message timestamp
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
244  Row major x, y z
245  """
246  _fields_ = [
247  ("header", SickScanHeader), # message timestamp
248  ("orientation", SickScanQuaternionMsg),
249  ("orientation_covariance", ctypes.c_double * 9), # Row major about x, y, z axes
250  ("angular_velocity", SickScanVector3Msg),
251  ("angular_velocity_covariance", ctypes.c_double * 9), # Row major about x, y, z axes
252  ("linear_acceleration", SickScanVector3Msg),
253  ("linear_acceleration_covariance", ctypes.c_double * 9) # Row major x, y z
254  ]
255 
256 class SickScanLFErecFieldMsg(ctypes.Structure):
257  """
258  sick_scan_api: struct SickScanLFErecFieldMsg, equivalent to LFErecFieldMsg.msg
259 
260  Attributes
261  ----------
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
274  f.e. 2021
275  month : ctypes.c_uint8
276  1 ... 12
277  day : ctypes.c_uint8
278  1 ... 31
279  hour : ctypes.c_uint8
280  0 ... 23
281  minute : ctypes.c_uint8
282  0 ... 59
283  second : ctypes.c_uint8
284  0 ... 59
285  microsecond : ctypes.c_uint32
286  0 ... 999999
287  """
288  _fields_ = [
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), # field result is 0 (invalid/incorrect), 1 (free/clear) or 2 (infringed)
297  ("time_state", ctypes.c_uint16), # No time data: 0, Time data: 1
298  ("year", ctypes.c_uint16), # f.e. 2021
299  ("month", ctypes.c_uint8), # 1 ... 12
300  ("day", ctypes.c_uint8), # 1 ... 31
301  ("hour", ctypes.c_uint8), # 0 ... 23
302  ("minute", ctypes.c_uint8), # 0 ... 59
303  ("second", ctypes.c_uint8), # 0 ... 59
304  ("microsecond", ctypes.c_uint32) # 0 ... 999999
305  ]
306 
307 class SickScanLFErecMsg(ctypes.Structure):
308  """
309  sick_scan_api: struct SickScanLFErecMsg, equivalent to LFErecMsg.msg
310 
311  Attributes
312  ----------
313  header : SickScanHeader
314  message timestamp
315  fields_number : ctypes.c_uint16
316  number of valid fields
317  fields : SickScanLFErecFieldMsg * 3
318  max. 3 valid fields
319  """
320  _fields_ = [
321  ("header", SickScanHeader), # message timestamp
322  ("fields_number", ctypes.c_uint16), # number of valid fields
323  ("fields", SickScanLFErecFieldMsg * 3) # max. 3 valid fields
324  ]
325 
326 class SickScanLIDoutputstateMsg(ctypes.Structure):
327  """
328  sick_scan_api: struct SickScanLIDoutputstateMsg, equivalent to LIDoutputstateMsg.msg
329 
330  Attributes
331  ----------
332  header : SickScanHeader
333  message timestamp
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
345  f.e. 2021
346  month : ctypes.c_uint8
347  1 ... 12
348  day : ctypes.c_uint8
349  1 ... 31
350  hour : ctypes.c_uint8
351  0 ... 23
352  minute : ctypes.c_uint8
353  0 ... 59
354  second : ctypes.c_uint8
355  0 ... 59
356  microsecond : ctypes.c_uint32
357  0 ... 999999
358  """
359  _fields_ = [
360  ("header", SickScanHeader), # message timestamp
361  ("version_number", ctypes.c_uint16), # Status code version number
362  ("system_counter", ctypes.c_uint32), # Status code system counter (time in microsec since power up, max. 71 min then starting from 0 again)
363  ("output_state", ctypes.c_uint8 * 8), # array of max. 8 output states, each state with value 0 (not active), 1 (active) or 2 (not used)
364  ("output_count", ctypes.c_uint32 * 8), # array of max. 8 output counter
365  ("time_state", ctypes.c_uint16), # No time data: 0, Time data: 1 (sensortime from the last change of min. one of the outputs)
366  ("year", ctypes.c_uint16), # f.e. 2021
367  ("month", ctypes.c_uint8), # 1 ... 12
368  ("day", ctypes.c_uint8), # 1 ... 31
369  ("hour", ctypes.c_uint8), # 0 ... 23
370  ("minute", ctypes.c_uint8), # 0 ... 59
371  ("second", ctypes.c_uint8), # 0 ... 59
372  ("microsecond", ctypes.c_uint32) # 0 ... 999999
373  ]
374 
375 class SickScanRadarPreHeader(ctypes.Structure):
376  """
377  sick_scan_api: struct SickScanRadarPreHeader, equivalent to RadarPreHeader.msg
378 
379  Attributes
380  ----------
381  uiversionno : ctypes.c_uint16
382  version number
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
389  State of the device
390  bcontaminationwarning : ctypes.c_uint8
391  Contamination Warning
392  bcontaminationerror : ctypes.c_uint8
393  Contamination Error
394  sick_scan/RadarPreHeaderStatusBlock:
395  uitelegramcount : ctypes.c_uint32
396  telegram number
397  uicyclecount : ctypes.c_uint32
398  "scan number"
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
411  [1/100dB]
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]
419  """
420  _fields_ = [
421  ("uiversionno", ctypes.c_uint16), # version number
422  # sick_scan/RadarPreHeaderDeviceBlock:
423  ("uiident", ctypes.c_uint32), # Logical number of the device"
424  ("udiserialno", ctypes.c_uint32), # Serial number of the device
425  ("bdeviceerror", ctypes.c_uint8), # State of the device
426  ("bcontaminationwarning", ctypes.c_uint8), # Contamination Warning
427  ("bcontaminationerror", ctypes.c_uint8), # Contamination Error
428  # sick_scan/RadarPreHeaderStatusBlock:
429  ("uitelegramcount", ctypes.c_uint32), # telegram number
430  ("uicyclecount", ctypes.c_uint32), # "scan number"
431  ("udisystemcountscan", ctypes.c_uint32), # system time since power on of scan gen. [us]
432  ("udisystemcounttransmit", ctypes.c_uint32), # system time since power on of scan transmission [us]
433  ("uiinputs", ctypes.c_uint16), # state of digital inputs
434  ("uioutputs", ctypes.c_uint16), # state of digital outputs
435  # sick_scan/RadarPreHeaderMeasurementParam1Block:
436  ("uicycleduration", ctypes.c_uint32), # Time in microseconds to detect this items
437  ("uinoiselevel", ctypes.c_uint32), # [1/100dB]
438  # sick_scan/RadarPreHeaderEncoderBlock[]:
439  ("numencoder", ctypes.c_uint16), # number of valid encoders (0)
440  ("udiencoderpos", ctypes.c_uint32 * 3), # array of max. 3 encoder position [inc]
441  ("iencoderspeed", ctypes.c_uint16 * 3) # array of max. 3 encoder speed [inc/mm]
442  ]
443 
444 class SickScanRadarObject(ctypes.Structure):
445  """
446  sick_scan_api: struct SickScanRadarObject, equivalent to RadarObject.msg
447 
448  Attributes
449  ----------
450  id : ctypes.c_int32
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)
478  """
479  _fields_ = [
480  ("id", ctypes.c_int32),
481  ("tracking_time_sec", ctypes.c_uint32), # seconds part of tracking_time (since when the object is tracked): seconds (stamp_secs) since epoch
482  ("tracking_time_nsec", ctypes.c_uint32), # nanoseconds part of tracking_time (since when the object is tracked): nanoseconds since stamp_secs
483  ("last_seen_sec", ctypes.c_uint32), # seconds part of last_seen timestamp: seconds (stamp_secs) since epoch
484  ("last_seen_nsec", ctypes.c_uint32), # nanoseconds part of last_seen timestamp: nanoseconds since stamp_secs
485  # geometry_msgs/TwistWithCovariance velocity
486  ("velocity_linear", SickScanVector3Msg),
487  ("velocity_angular", SickScanVector3Msg),
488  ("velocity_covariance", ctypes.c_double * 36), # Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
489  # geometry_msgs/Pose bounding_box_center
490  ("bounding_box_center_position", SickScanVector3Msg),
491  ("bounding_box_center_orientation", SickScanQuaternionMsg),
492  # geometry_msgs/Vector3 bounding_box_size
493  ("bounding_box_size", SickScanVector3Msg),
494  # geometry_msgs/PoseWithCovariance object_box_center
495  ("object_box_center_position", SickScanVector3Msg),
496  ("object_box_center_orientation", SickScanQuaternionMsg),
497  ("object_box_center_covariance", ctypes.c_double * 36), # Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
498  # geometry_msgs/Vector3 object_box_size
499  ("object_box_size", SickScanVector3Msg),
500  # geometry_msgs/Point[] contour_points
501  ("contour_points", SickScanPointArray)
502  ]
503 
504 class SickScanRadarObjectArray(ctypes.Structure):
505  """
506  sick_scan_api: struct SickScanRadarObjectArray, Array of SickScanRadarObject
507 
508  Attributes
509  ----------
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.
516  """
517  _fields_ = [
518  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanRadarObject)
519  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
520  ("buffer", ctypes.POINTER(SickScanRadarObject)) # 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.
521  ]
522 
523 class SickScanRadarScan(ctypes.Structure):
524  """
525  sick_scan_api: struct SickScanRadarScan, equivalent to RadarScan.msg
526 
527  Attributes
528  ----------
529  header : SickScanHeader
530  message timestamp
531  radarpreheader : SickScanRadarPreHeader
532  RadarPreHeader.msg
533  targets : SickScanPointCloudMsg
534  sensor_msgs/PointCloud2
535  objects : SickScanRadarObjectArray
536  Array of RadarObject.msg
537  """
538  _fields_ = [
539  ("header", SickScanHeader), # message timestamp
540  ("radarpreheader", SickScanRadarPreHeader), # RadarPreHeader.msg
541  ("targets", SickScanPointCloudMsg), # sensor_msgs/PointCloud2
542  ("objects", SickScanRadarObjectArray) # Array of RadarObject.msg
543  ]
544 
546  """
547  sick_scan_api: struct SickScanLdmrsObject, equivalent to SickLdmrsObject.msg
548  """
549  pass
550 
551 class SickScanLdmrsObjectBuffer(ctypes.Structure):
552  """
553  sick_scan_api: struct SickScanLdmrsObjectBuffer, Array of SickScanLdmrsObject
554 
555  Attributes
556  ----------
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.
563  """
564  _fields_ = [
565  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanLdmrsObject)
566  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
567  ("buffer", ctypes.POINTER(SickScanLdmrsObject)) # 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.
568  ]
569 
570 class SickScanLdmrsObjectArray(ctypes.Structure):
571  """
572  sick_scan_api: struct SickScanLdmrsObjectArray, equivalent to SickLdmrsObjectArray.msg
573 
574  Attributes
575  ----------
576  header : SickScanHeader
577  message timestamp
578  objects : SickScanLdmrsObjectBuffer
579  Array of SickScanLdmrsObjects
580  """
581  _fields_ = [
582  ("header", SickScanHeader), # message timestamp
583  ("objects", SickScanLdmrsObjectBuffer) # Array of SickScanLdmrsObjects
584  ]
585 
586 class SickScanColorRGBA(ctypes.Structure):
587  """
588  equivalent to std_msgs::ColorRGBA
589 
590  Attributes
591  ----------
592  r : ctypes.c_float
593  g : ctypes.c_float
594  b : ctypes.c_float
595  a : ctypes.c_float
596  """
597  _fields_ = [
598  ("r", ctypes.c_float),
599  ("g", ctypes.c_float),
600  ("b", ctypes.c_float),
601  ("a", ctypes.c_float)
602  ]
603 
604 class SickScanColorRGBAArray(ctypes.Structure):
605  """
606  Array of SickScanColorRGBA, which can be serialized and imported in C, C++ or python
607 
608  Attributes
609  ----------
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.
616  """
617  _fields_ = [
618  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanColorRGBA)
619  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
620  ("buffer", ctypes.POINTER(SickScanColorRGBA)) # 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.
621  ]
622 
623 class SickScanVisualizationMarker(ctypes.Structure):
624  """
625  equivalent to visualization_msgs::Marker
626 
627  Attributes
628  ----------
629  header : SickScanHeader
630  message timestamp
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
633  id : ctypes.c_int32
634  object ID useful in conjunction with the namespace for manipulating and deleting the object later
635  type : ctypes.c_int32
636  Type of object
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
646  Color [0.0-1.0]
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
662  boolean
663  """
664  _fields_ = [
665  ("header", SickScanHeader), # message timestamp
666  ("ns", ctypes.c_char * 1024), # Namespace to place this object in... used in conjunction with id to create a unique name for the object
667  ("id", ctypes.c_int32), # object ID useful in conjunction with the namespace for manipulating and deleting the object later
668  ("type", ctypes.c_int32), # Type of object
669  ("action", ctypes.c_int32), # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects
670  ("pose_position", SickScanVector3Msg), # Pose of the object (positional part)
671  ("pose_orientation", SickScanQuaternionMsg), # Pose of the object (rotational part)
672  ("scale", SickScanVector3Msg), # Scale of the object 1,1,1 means default (usually 1 meter square)
673  ("color", SickScanColorRGBA), # Color [0.0-1.0]
674  ("lifetime_sec", ctypes.c_uint32), # How long the object should last before being automatically deleted. 0 means forever (seconds part)
675  ("lifetime_nsec", ctypes.c_uint32), # How long the object should last before being automatically deleted. 0 means forever (nanoseconds part)
676  ("frame_locked", ctypes.c_uint8), # boolean, If this marker should be frame-locked, i.e. retransformed into its frame every timestep
677  ("points", SickScanPointArray), # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
678  ("colors", SickScanColorRGBAArray), # 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
679  ("text", ctypes.c_char * 1024), # NOTE: only used for text markers
680  ("mesh_resource", ctypes.c_char * 1024), # NOTE: only used for MESH_RESOURCE markers
681  ("mesh_use_embedded_materials", ctypes.c_uint8) # boolean
682  ]
683 
684 class SickScanVisualizationMarkerBuffer(ctypes.Structure):
685  """
686  Array of SickScanVisualizationMarkers
687 
688  Attributes
689  ----------
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.
696  """
697  _fields_ = [
698  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVisualizationMarker)
699  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
700  ("buffer", ctypes.POINTER(SickScanVisualizationMarker)) # 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.
701  ]
702 
703 class SickScanVisualizationMarkerMsg(ctypes.Structure):
704  """
705  equivalent to visualization_msgs::MarkerArray
706 
707  Attributes
708  ----------
709  markers : SickScanVisualizationMarkerBuffer
710  Array of SickScanVisualizationMarkers
711  """
712  _fields_ = [
713  ("markers", SickScanVisualizationMarkerBuffer) # Array of SickScanVisualizationMarkers
714  ]
715 
716 class SickScanNavReflector(ctypes.Structure):
717  """
718  NAV-350 reflector equivalent to SickScanNavReflector defined in sick_scan_api.h
719  """
720  _fields_ = [
721  ("pos_valid", ctypes.c_uint16),
722  # reflector position in [m] in ros coordinates, if pos_valid > 0:
723  ("pos_x", ctypes.c_float),
724  ("pos_y", ctypes.c_float),
725  ("cartesian_valid", ctypes.c_uint16),
726  # reflector position in [mm] in lidar coordinates, if cartesian_valid > 0:
727  ("cartesian_x", ctypes.c_int32),
728  ("cartesian_y", ctypes.c_int32),
729  ("polar_valid", ctypes.c_uint16),
730  # reflector position in [mm] and [mdeg] in polar lidar coordinates, if polar_valid > 0:
731  ("polar_dist", ctypes.c_uint32),
732  ("polar_phi", ctypes.c_uint32),
733  ("opt_valid", ctypes.c_uint16),
734  # Optional reflector data, if opt_valid > 0
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), # lidar timestamp in milliseconds
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), # timestamp converted to system time (seconds part, 0 if timestamp not valid)
747  ("opt_timestamp_nsec", ctypes.c_uint32) # timestamp converted to system time (nanoseconds part, 0 if timestamp not valid)
748  ]
749 
750 class SickScanNavReflectorBuffer(ctypes.Structure):
751  """
752  Array of NAV-350 reflectors equivalent to SickScanNavReflectorBuffer defined in sick_scan_api.h
753 
754  Attributes
755  ----------
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.
762  """
763  _fields_ = [
764  ("capacity", ctypes.c_uint64), # Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVisualizationMarker)
765  ("size", ctypes.c_uint64), # Number of currently used elements in the buffer
766  ("buffer", ctypes.POINTER(SickScanNavReflector)) # 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.
767  ]
768 
769 class SickScanNavPoseLandmarkMsg(ctypes.Structure):
770  """
771  NAV-350 pose and landmark message equivalent to SickScanNavPoseLandmarkMsg defined in sick_scan_api.h
772  """
773  _fields_ = [
774  ("pose_valid", ctypes.c_uint16),
775  # NAV pose, if pose_valid > 0:
776  ("pose_x", ctypes.c_float), # x-position in ros coordinates in m
777  ("pose_y", ctypes.c_float), # y-position in ros coordinates in m
778  ("pose_yaw", ctypes.c_float), # yaw angle in ros coordinates in radians
779  ("pose_timestamp_sec", ctypes.c_uint32), # timestamp of pose converted to system time (seconds part, 0 if timestamp not valid)
780  ("pose_timestamp_nsec", ctypes.c_uint32), # timestamp of pose converted to system time (nanoseconds part, 0 if timestamp not valid)
781  ("pose_nav_x", ctypes.c_int32), # x-position in lidar coordinates in mm
782  ("pose_nav_y", ctypes.c_int32), # y-position in lidar coordinates in mm
783  ("pose_nav_phi", ctypes.c_uint32), # orientation in lidar coordinates in 0 ... 360000 mdeg
784  ("pose_opt_valid", ctypes.c_uint16),
785  # Optional NAV pose data, if pose_opt_valid > 0:
786  ("pose_opt_output_mode", ctypes.c_uint8),
787  ("pose_opt_timestamp", ctypes.c_uint32), # lidar timestamp in milliseconds
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),
792  # NAV reflectors:
793  ("reflectors", SickScanNavReflectorBuffer) # Array of SickScanNavReflectors
794  ]
795 
796 class SickScanNavOdomVelocityMsg(ctypes.Structure):
797  """
798  NAV-350 velocity/odometry data in nav coordinates, see NAVOdomVelocity.msg
799  """
800  _fields_ = [
801  ("vel_x", ctypes.c_float), # x-component of velocity in the coordinate system defined by coordbase (i.e. in lidar coordinate for coordbase=0) in m/s, -32.0 ... +32.0 m/s
802  ("vel_y", ctypes.c_float), # y-component of velocity in the coordinate system defined by coordbase (i.e. in lidar coordinate for coordbase=0) in m/s, -32.0 ... +32.0 m/s
803  ("omega", ctypes.c_float), # angular velocity of the NAV350 in radians/s, -2*PI ... +2*PI rad/s
804  ("timestamp", ctypes.c_uint32), # timestamp of the Velocity vector related to the NAV350 clock
805  ("coordbase", ctypes.c_uint8) # coordinate system of the velocity vector (local or global), 0 = local coordinate system of the NAV350, 1 = absolute coordinate system
806  ]
807 
808 class SickScanOdomVelocityMsg(ctypes.Structure):
809  """
810  Velocity/odometry data in ros coordinates
811  """
812  _fields_ = [
813  ("vel_x", ctypes.c_float), # x-component of velocity in ros coordinates in m/s
814  ("vel_y", ctypes.c_float), # y-component of velocity in ros coordinates in m/s
815  ("omega", ctypes.c_float), # angular velocity in radians/s
816  ("timestamp_sec", ctypes.c_uint32), # seconds part of system timestamp of the odometry data
817  ("timestamp_nsec", ctypes.c_uint32) # nanoseconds part of system timestamp of the odometry data
818  ]
819 
820 class SickScanLogMsg(ctypes.Structure):
821  """
822  general log message
823  """
824  _fields_ = [
825  ("log_level", ctypes.c_int32), # log_level defined in ros::console::levels: Info=1, Warn=2, Error=3, Fatal=4
826  ("log_message", ctypes.c_char_p) # log message
827  ]
828 
829 class SickScanDiagnosticMsg(ctypes.Structure):
830  """
831  general log message
832  """
833  _fields_ = [
834  ("status_code", ctypes.c_int32), # status_code defined in SICK_DIAGNOSTIC_STATUS: OK=0 (normal operation), WARN=1 (warning), ERROR=2 (error, should not occure), INIT=3 (initialization after startup or reconnection), EXIT=4 (sick_scan_xd exiting)
835  ("status_message", ctypes.c_char_p) # diagnostic message
836  ]
837 
838 class SickScanApiErrorCodes(Enum): #
839  """
840  Error codes, return values of SickScanApi-functions
841 
842  Attributes
843  ----------
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
850  """
851  SICK_SCAN_API_SUCCESS = 0, "SICK_SCAN_API_SUCCESS" # function executed successfully
852  SICK_SCAN_API_ERROR = 1, "SICK_SCAN_API_ERROR" # general (unspecified) error
853  SICK_SCAN_API_NOT_LOADED = 2, "SICK_SCAN_API_NOT_LOADED" # sick_scan_xd library not loaded
854  SICK_SCAN_API_NOT_INITIALIZED = 3, "SICK_SCAN_API_NOT_INITIALIZED" # API not initialized
855  SICK_SCAN_API_NOT_IMPLEMENTED = 4, "SICK_SCAN_API_NOT_IMPLEMENTED" # function not implemented in sick_scan_xd library
856  SICK_SCAN_API_TIMEOUT = 5, "SICK_SCAN_API_TIMEOUT" # timeout during wait for response
857  def __int__(self):
858  return self.value[0]
859  def __str__(self):
860  return self.value[1]
861 
862 """
863 Callback declarations
864 """
865 
866 SickScanPointCloudMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg)) # sick_scan_api.h: typedef void(* SickScanPointCloudMsgCallback)(SickScanApiHandle apiHandle, const SickScanPointCloudMsg* msg);
867 SickScanImuMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanImuMsg)) # sick_scan_api.h: typedef void(* SickScanImuMsgCallback)(SickScanApiHandle apiHandle, const SickScanImuMsg* msg);
868 SickScanLFErecMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanLFErecMsg)) # sick_scan_api.h: typedef void(* SickScanLFErecMsgCallback)(SickScanApiHandle apiHandle, const SickScanLFErecMsg* msg);
869 SickScanLIDoutputstateMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanLIDoutputstateMsg)) # sick_scan_api.h: typedef void(* SickScanLIDoutputstateMsgCallback)(SickScanApiHandle apiHandle, const SickScanLIDoutputstateMsg* msg);
870 SickScanRadarScanCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanRadarScan)) # sick_scan_api.h: typedef void(* SickScanRadarScanCallback)(SickScanApiHandle apiHandle, const SickScanRadarScan* msg);
871 SickScanLdmrsObjectArrayCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanLdmrsObjectArray)) # sick_scan_api.h: typedef void(* SickScanLdmrsObjectArrayCallback)(SickScanApiHandle apiHandle, const SickScanLdmrsObjectArray* msg);
872 SickScanVisualizationMarkerCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanVisualizationMarkerMsg)) # sick_scan_api.h: typedef void(* SickScanVisualizationMarkerCallback)(SickScanApiHandle apiHandle, const SickScanVisualizationMarkerMsg* msg);
873 SickScanNavPoseLandmarkCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanNavPoseLandmarkMsg)) # sick_scan_api.h: typedef void(* SickScanNavPoseLandmarkCallback)(SickScanApiHandle apiHandle, const SickScanNavPoseLandmarkMsg* msg);
874 SickScanLogMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanLogMsg)) # sick_scan_api.h: typedef void(* SickScanLogMsgCallback)(SickScanApiHandle apiHandle, const SickScanLogMsg* msg);
875 SickScanDiagnosticMsgCallback = ctypes.CFUNCTYPE(None, ctypes.c_void_p, ctypes.POINTER(SickScanDiagnosticMsg)) # sick_scan_api.h: typedef void(* SickScanDiagnosticMsgCallback)(SickScanApiHandle apiHandle, const SickScanDiagnosticMsg* msg);
876 
877 
878 """
879 Functions to initialize and close the API and a lidar
880 """
881 
882 def ctypesCharArrayToString(char_array):
883  """
884  Returns a python string from a zero terminated ctypes char array
885  """
886  return ''.join([chr(i) for i in char_array]).rstrip('\x00')
887 
888 def loadLibrary(paths, lib_filname):
889  """
890  loads and returns a library, given its filename and a list of folder
891  """
892  for path in paths:
893  filename = path + lib_filname
894  if os.path.exists(filename):
895  return ctypes.CDLL(filename)
896  return ctypes.CDLL(lib_filname)
897 
898 def SickScanApiLoadLibrary(paths, lib_filname):
899  """
900  Load sick_scan_library and functions
901  """
902  sick_scan_library = loadLibrary(paths, lib_filname)
903  # sick_scan_api.h: SickScanApiHandle SickScanApiCreate(int argc, char** argv);
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
906  # sick_scan_api.h: int32_t SickScanApiRelease(SickScanApiHandle apiHandle);
907  sick_scan_library.SickScanApiRelease.argtypes = [ctypes.c_void_p]
908  sick_scan_library.SickScanApiRelease.restype = ctypes.c_int
909  # sick_scan_api.h: int32_t SickScanApiInitByLaunchfile(SickScanApiHandle apiHandle, const char* launchfile_args);
910  sick_scan_library.SickScanApiInitByLaunchfile.argtypes = [ctypes.c_void_p, ctypes.c_char_p]
911  sick_scan_library.SickScanApiInitByLaunchfile.restype = ctypes.c_int
912  # sick_scan_api.h: int32_t SickScanApiInitByCli(SickScanApiHandle apiHandle, int argc, char** argv);
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
915  # sick_scan_api.h: int32_t SickScanApiClose(SickScanApiHandle apiHandle);
916  sick_scan_library.SickScanApiClose.argtypes = [ctypes.c_void_p]
917  sick_scan_library.SickScanApiClose.restype = ctypes.c_int
918  # sick_scan_api.h: int32_t SickScanApiRegisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback);
919  sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
920  sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg.restype = ctypes.c_int
921  # sick_scan_api.h: int32_t SickScanApiDeregisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback);
922  sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
923  sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg.restype = ctypes.c_int
924  # sick_scan_api.h: int32_t SickScanApiRegisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback);
925  sick_scan_library.SickScanApiRegisterPolarPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
926  sick_scan_library.SickScanApiRegisterPolarPointCloudMsg.restype = ctypes.c_int
927  # sick_scan_api.h: int32_t SickScanApiDeregisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback);
928  sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg.argtypes = [ctypes.c_void_p, SickScanPointCloudMsgCallback]
929  sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg.restype = ctypes.c_int
930  # sick_scan_api.h: int32_t SickScanApiRegisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback);
931  sick_scan_library.SickScanApiRegisterImuMsg.argtypes = [ctypes.c_void_p, SickScanImuMsgCallback]
932  sick_scan_library.SickScanApiRegisterImuMsg.restype = ctypes.c_int
933  # sick_scan_api.h: int32_t SickScanApiDeregisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback);
934  sick_scan_library.SickScanApiDeregisterImuMsg.argtypes = [ctypes.c_void_p, SickScanImuMsgCallback]
935  sick_scan_library.SickScanApiDeregisterImuMsg.restype = ctypes.c_int
936  # sick_scan_api.h: int32_t SickScanApiRegisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback);
937  sick_scan_library.SickScanApiRegisterLFErecMsg.argtypes = [ctypes.c_void_p, SickScanLFErecMsgCallback]
938  sick_scan_library.SickScanApiRegisterLFErecMsg.restype = ctypes.c_int
939  # sick_scan_api.h: int32_t SickScanApiDeregisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback);
940  sick_scan_library.SickScanApiDeregisterLFErecMsg.argtypes = [ctypes.c_void_p, SickScanLFErecMsgCallback]
941  sick_scan_library.SickScanApiDeregisterLFErecMsg.restype = ctypes.c_int
942  # sick_scan_api.h: int32_t SickScanApiRegisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback);
943  sick_scan_library.SickScanApiRegisterLIDoutputstateMsg.argtypes = [ctypes.c_void_p, SickScanLIDoutputstateMsgCallback]
944  sick_scan_library.SickScanApiRegisterLIDoutputstateMsg.restype = ctypes.c_int
945  # sick_scan_api.h: int32_t SickScanApiDeregisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback);
946  sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg.argtypes = [ctypes.c_void_p, SickScanLIDoutputstateMsgCallback]
947  sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg.restype = ctypes.c_int
948  # sick_scan_api.h: int32_t SickScanApiRegisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback);
949  sick_scan_library.SickScanApiRegisterRadarScanMsg.argtypes = [ctypes.c_void_p, SickScanRadarScanCallback]
950  sick_scan_library.SickScanApiRegisterRadarScanMsg.restype = ctypes.c_int
951  # sick_scan_api.h: int32_t SickScanApiDeregisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback);
952  sick_scan_library.SickScanApiDeregisterRadarScanMsg.argtypes = [ctypes.c_void_p, SickScanRadarScanCallback]
953  sick_scan_library.SickScanApiDeregisterRadarScanMsg.restype = ctypes.c_int
954  # sick_scan_api.h: int32_t SickScanApiRegisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback);
955  sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, SickScanLdmrsObjectArrayCallback]
956  sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg.restype = ctypes.c_int
957  # sick_scan_api.h: int32_t SickScanApiDeregisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback);
958  sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, SickScanLdmrsObjectArrayCallback]
959  sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg.restype = ctypes.c_int
960  # sick_scan_api.h: int32_t SickScanApiRegisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback);
961  sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, SickScanVisualizationMarkerCallback]
962  sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg.restype = ctypes.c_int
963  # sick_scan_api.h: int32_t SickScanApiDeregisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback);
964  sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, SickScanVisualizationMarkerCallback]
965  sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg.restype = ctypes.c_int
966  # sick_scan_api.h: int32_t SickScanApiRegisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback);
967  sick_scan_library.SickScanApiRegisterDiagnosticMsg.argtypes = [ctypes.c_void_p, SickScanDiagnosticMsgCallback]
968  sick_scan_library.SickScanApiRegisterDiagnosticMsg.restype = ctypes.c_int
969  # sick_scan_api.h: int32_t SickScanApiDeregisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback);
970  sick_scan_library.SickScanApiDeregisterDiagnosticMsg.argtypes = [ctypes.c_void_p, SickScanDiagnosticMsgCallback]
971  sick_scan_library.SickScanApiDeregisterDiagnosticMsg.restype = ctypes.c_int
972  # sick_scan_api.h: int32_t SickScanApiRegisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback);
973  sick_scan_library.SickScanApiRegisterLogMsg.argtypes = [ctypes.c_void_p, SickScanLogMsgCallback]
974  sick_scan_library.SickScanApiRegisterLogMsg.restype = ctypes.c_int
975  # sick_scan_api.h: int32_t SickScanApiDeregisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback);
976  sick_scan_library.SickScanApiDeregisterLogMsg.argtypes = [ctypes.c_void_p, SickScanLogMsgCallback]
977  sick_scan_library.SickScanApiDeregisterLogMsg.restype = ctypes.c_int
978  # sick_scan_api.h: int32_t SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t* status_code, char* message_buffer, int32_t message_buffer_size);
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
981  # sick_scan_api.h: int32_t SickScanApiSendSOPAS(SickScanApiHandle apiHandle, const char* sopas_command, char* sopas_response_buffer, int32_t response_buffer_size);
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
984  # sick_scan_api.h: int32_t SickScanApiSetVerboseLevel(SickScanApiHandle apiHandle, int32_t verbose_level);
985  sick_scan_library.SickScanApiSetVerboseLevel.argtypes = [ctypes.c_void_p, ctypes.c_int32]
986  sick_scan_library.SickScanApiSetVerboseLevel.restype = ctypes.c_int
987  # sick_scan_api.h: int32_t SickScanApiGetVerboseLevel(SickScanApiHandle apiHandle);
988  sick_scan_library.SickScanApiGetVerboseLevel.argtypes = [ctypes.c_void_p]
989  sick_scan_library.SickScanApiGetVerboseLevel.restype = ctypes.c_int
990  # sick_scan_api.h: int32_t SickScanApiWaitNextCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg* msg, double timeout_sec);
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
993  # sick_scan_api.h: int32_t SickScanApiWaitNextPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg* msg, double timeout_sec);
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
996  # sick_scan_api.h: int32_t SickScanApiFreePointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg* msg);
997  sick_scan_library.SickScanApiFreePointCloudMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanPointCloudMsg)]
998  sick_scan_library.SickScanApiFreePointCloudMsg.restype = ctypes.c_int
999  # sick_scan_api.h: int32_t SickScanApiWaitNextImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg* msg, double timeout_sec);
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
1002  # sick_scan_api.h: int32_t SickScanApiFreeImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg* msg)
1003  sick_scan_library.SickScanApiFreeImuMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanImuMsg)]
1004  sick_scan_library.SickScanApiFreeImuMsg.restype = ctypes.c_int
1005  # sick_scan_api.h: int32_t SickScanApiWaitNextLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg* msg, double timeout_sec);
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
1008  # sick_scan_api.h: int32_t SickScanApiFreeLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg* msg);
1009  sick_scan_library.SickScanApiFreeLFErecMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLFErecMsg)]
1010  sick_scan_library.SickScanApiFreeLFErecMsg.restype = ctypes.c_int
1011  # sick_scan_api.h: int32_t SickScanApiWaitNextLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg* msg, double timeout_sec);
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
1014  # sick_scan_api.h: int32_t SickScanApiFreeLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg* msg);
1015  sick_scan_library.SickScanApiFreeLIDoutputstateMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLIDoutputstateMsg)]
1016  sick_scan_library.SickScanApiFreeLIDoutputstateMsg.restype = ctypes.c_int
1017  # sick_scan_api.h: int32_t SickScanApiWaitNextRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan* msg, double timeout_sec);
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
1020  # sick_scan_api.h: int32_t SickScanApiFreeRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan* msg);
1021  sick_scan_library.SickScanApiFreeRadarScanMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanRadarScan)]
1022  sick_scan_library.SickScanApiFreeRadarScanMsg.restype = ctypes.c_int
1023  # sick_scan_api.h: int32_t SickScanApiWaitNextLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray* msg, double timeout_sec);
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
1026  # sick_scan_api.h: int32_t SickScanApiFreeLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray* msg);
1027  sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanLdmrsObjectArray)]
1028  sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg.restype = ctypes.c_int
1029  # sick_scan_api.h: int32_t SickScanApiWaitNextVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg* msg, double timeout_sec);
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
1032  # sick_scan_api.h: int32_t SickScanApiFreeVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg* msg);
1033  sick_scan_library.SickScanApiFreeVisualizationMarkerMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanVisualizationMarkerMsg)]
1034  sick_scan_library.SickScanApiFreeVisualizationMarkerMsg.restype = ctypes.c_int
1035  # sick_scan_api.h: int32_t SickScanApiRegisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback);
1036  sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, SickScanNavPoseLandmarkCallback]
1037  sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg.restype = ctypes.c_int
1038  # sick_scan_api.h: int32_t SickScanApiDeregisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback);
1039  sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, SickScanNavPoseLandmarkCallback]
1040  sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg.restype = ctypes.c_int
1041  # sick_scan_api.h: int32_t SickScanApiWaitNextNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg* msg, double timeout_sec);
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
1044  # sick_scan_api.h: int32_t SickScanApiFreeNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg* msg);
1045  sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanNavPoseLandmarkMsg)]
1046  sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg.restype = ctypes.c_int
1047  # sick_scan_api.h: int32_t SickScanApiNavOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg* msg);
1048  sick_scan_library.SickScanApiNavOdomVelocityMsg.argtypes = [ctypes.c_void_p, ctypes.POINTER(SickScanNavOdomVelocityMsg)]
1049  sick_scan_library.SickScanApiNavOdomVelocityMsg.restype = ctypes.c_int
1050  # sick_scan_api.h: int32_t SickScanApiOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg* msg);
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
1054 
1055 def SickScanApiUnloadLibrary(sick_scan_library):
1056  """
1057  Unload sick_scan_xd api library
1058  """
1059  del sick_scan_library
1060 
1061 def SickScanApiCreate(sick_scan_library):
1062  """
1063  Create an instance of sick_scan_xd api.
1064  Call SickScanApiInitByLaunchfile or SickScanApiInitByCli to process a lidar.
1065  """
1066  null_ptr = ctypes.POINTER(ctypes.c_char_p)()
1067  api_handle = sick_scan_library.SickScanApiCreate(0, null_ptr)
1068  return api_handle
1069 
1070 def SickScanApiRelease(sick_scan_library, api_handle):
1071  """
1072  Release and free all resources of the api handle; the handle is invalid after SickScanApiRelease
1073  """
1074  return sick_scan_library.SickScanApiRelease(api_handle)
1075 
1076 def SickScanApiInitByLaunchfile(sick_scan_library, api_handle, launchfile_args):
1077  """
1078  Initialize a lidar by launchfile and start message receiving and processing
1079  """
1080  return sick_scan_library.SickScanApiInitByLaunchfile(api_handle, ctypes.create_string_buffer(str.encode(launchfile_args)))
1081 
1082 def SickScanApiClose(sick_scan_library, api_handle):
1083  """
1084  Release and free all resources of the api handle; the handle is invalid after SickScanApiRelease
1085  """
1086  return sick_scan_library.SickScanApiClose(api_handle)
1087 
1088 """
1089 Registration and deregistration of message callbacks
1090 """
1091 
1092 def SickScanApiRegisterCartesianPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback):
1093  """
1094  Register a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
1095  """
1096  return sick_scan_library.SickScanApiRegisterCartesianPointCloudMsg(api_handle, pointcloud_callback)
1097 
1098 def SickScanApiDeregisterCartesianPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback):
1099  """
1100  Deregister a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
1101  """
1102  return sick_scan_library.SickScanApiDeregisterCartesianPointCloudMsg(api_handle, pointcloud_callback)
1103 
1104 def SickScanApiRegisterPolarPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback):
1105  """
1106  Register a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
1107  """
1108  return sick_scan_library.SickScanApiRegisterPolarPointCloudMsg(api_handle, pointcloud_callback)
1109 
1110 def SickScanApiDeregisterPolarPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback):
1111  """
1112  Deregister a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
1113  """
1114  return sick_scan_library.SickScanApiDeregisterPolarPointCloudMsg(api_handle, pointcloud_callback)
1115 
1116 def SickScanApiRegisterImuMsg(sick_scan_library, api_handle, imu_callback):
1117  """
1118  Register a callback for Imu messages
1119  """
1120  return sick_scan_library.SickScanApiRegisterImuMsg(api_handle, imu_callback)
1121 
1122 def SickScanApiDeregisterImuMsg(sick_scan_library, api_handle, imu_callback):
1123  """
1124  Deregister a callback for Imu messages
1125  """
1126  return sick_scan_library.SickScanApiDeregisterImuMsg(api_handle, imu_callback)
1127 
1128 def SickScanApiRegisterLFErecMsg(sick_scan_library, api_handle, lferec_callback):
1129  """
1130  Register a callback for LFErec messages
1131  """
1132  return sick_scan_library.SickScanApiRegisterLFErecMsg(api_handle, lferec_callback)
1133 
1134 def SickScanApiDeregisterLFErecMsg(sick_scan_library, api_handle, lferec_callback):
1135  """
1136  Deregister a callback for LFErec messages
1137  """
1138  return sick_scan_library.SickScanApiDeregisterLFErecMsg(api_handle, lferec_callback)
1139 
1140 def SickScanApiRegisterLIDoutputstateMsg(sick_scan_library, api_handle, lidoutputstate_callback):
1141  """
1142  Register a callback for LIDoutputstate messages
1143  """
1144  return sick_scan_library.SickScanApiRegisterLIDoutputstateMsg(api_handle, lidoutputstate_callback)
1145 
1146 def SickScanApiDeregisterLIDoutputstateMsg(sick_scan_library, api_handle, lidoutputstate_callback):
1147  """
1148  Deregister a callback for LIDoutputstate messages
1149  """
1150  return sick_scan_library.SickScanApiDeregisterLIDoutputstateMsg(api_handle, lidoutputstate_callback)
1151 
1152 def SickScanApiRegisterRadarScanMsg(sick_scan_library, api_handle, radarscan_callback):
1153  """
1154  Register a callback for RadarScan messages
1155  """
1156  return sick_scan_library.SickScanApiRegisterRadarScanMsg(api_handle, radarscan_callback)
1157 
1158 def SickScanApiDeregisterRadarScanMsg(sick_scan_library, api_handle, radarscan_callback):
1159  """
1160  Deregister a callback for RadarScan messages
1161  """
1162  return sick_scan_library.SickScanApiDeregisterRadarScanMsg(api_handle, radarscan_callback)
1163 
1164 def SickScanApiRegisterLdmrsObjectArrayMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback):
1165  """
1166  Register a callback for LdmrsObjectArray messages
1167  """
1168  return sick_scan_library.SickScanApiRegisterLdmrsObjectArrayMsg(api_handle, ldmrsobjectarray_callback)
1169 
1170 def SickScanApiDeregisterLdmrsObjectArrayMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback):
1171  """
1172  Deregister a callback for LdmrsObjectArray messages
1173  """
1174  return sick_scan_library.SickScanApiDeregisterLdmrsObjectArrayMsg(api_handle, ldmrsobjectarray_callback)
1175 
1176 def SickScanApiRegisterVisualizationMarkerMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback):
1177  """
1178  Register a callback for VisualizationMarker messages
1179  """
1180  return sick_scan_library.SickScanApiRegisterVisualizationMarkerMsg(api_handle, ldmrsobjectarray_callback)
1181 
1182 def SickScanApiDeregisterVisualizationMarkerMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback):
1183  """
1184  Deregister a callback for VisualizationMarker messages
1185  """
1186  return sick_scan_library.SickScanApiDeregisterVisualizationMarkerMsg(api_handle, ldmrsobjectarray_callback)
1187 
1188 def SickScanApiRegisterNavPoseLandmarkMsg(sick_scan_library, api_handle, callback):
1189  """
1190  Register a callback for SickScanNavPoseLandmarkMsg messages
1191  """
1192  return sick_scan_library.SickScanApiRegisterNavPoseLandmarkMsg(api_handle, callback)
1193 
1194 def SickScanApiDeregisterNavPoseLandmarkMsg(sick_scan_library, api_handle, callback):
1195  """
1196  Deregister a callback for SickScanNavPoseLandmarkMsg messages
1197  """
1198  return sick_scan_library.SickScanApiDeregisterNavPoseLandmarkMsg(api_handle, callback)
1199 
1200 """
1201 Diagnostic functions
1202 """
1203 
1204 def SickScanApiRegisterDiagnosticMsg(sick_scan_library, api_handle, callback):
1205  """
1206  Register a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
1207  """
1208  return sick_scan_library.SickScanApiRegisterDiagnosticMsg(api_handle, callback)
1209 
1210 def SickScanApiDeregisterDiagnosticMsg(sick_scan_library, api_handle, callback):
1211  """
1212  Deregister a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
1213  """
1214  return sick_scan_library.SickScanApiDeregisterDiagnosticMsg(api_handle, callback)
1215 
1216 def SickScanApiRegisterLogMsg(sick_scan_library, api_handle, callback):
1217  """
1218  Register a callback for log messages (all informational and error messages)
1219  """
1220  return sick_scan_library.SickScanApiRegisterLogMsg(api_handle, callback)
1221 
1222 def SickScanApiDeregisterLogMsg(sick_scan_library, api_handle, callback):
1223  """
1224  Deregister a callback for log messages (all informational and error messages)
1225  """
1226  return sick_scan_library.SickScanApiDeregisterLogMsg(api_handle, callback)
1227 
1228 def SickScanApiGetStatus(sick_scan_library, api_handle, status_code, message_buffer, message_buffer_size):
1229  """
1230  Query current status and status message
1231  """
1232  return sick_scan_library.SickScanApiGetStatus(api_handle, status_code, message_buffer, message_buffer_size)
1233 
1234 # sopas_string_buffer = {}
1235 def SickScanApiSendSOPAS(sick_scan_library, api_handle, sopas_command, response_buffer_size = 1024):
1236  """
1237  Sends a SOPAS command like "sRN SCdevicestate" or "sRN ContaminationResult" and returns the lidar response
1238  """
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)
1242  # global sopas_string_buffer
1243  # if sopas_command not in sopas_string_buffer:
1244  # sopas_string_buffer[sopas_command] = ctypes.create_string_buffer(str.encode(sopas_command))
1245  # ret_val = sick_scan_library.SickScanApiSendSOPAS(api_handle, sopas_string_buffer[sopas_command], ctypes_response_buffer, response_buffer_size)
1246  return ctypes_response_buffer.value.decode()
1247 
1248 def SickScanApiSetVerboseLevel(sick_scan_library, api_handle, verbose_level):
1249  """
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.
1253  """
1254  return sick_scan_library.SickScanApiSetVerboseLevel(api_handle, verbose_level)
1255 
1256 def SickScanApiGetVerboseLevel(sick_scan_library, api_handle):
1257  """
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)
1259  """
1260  return sick_scan_library.SickScanApiGetVerboseLevel(api_handle)
1261 
1262 """
1263 Polling functions
1264 """
1265 
1266 def SickScanApiWaitNextCartesianPointCloudMsg(sick_scan_library, api_handle, msg, timeout_sec):
1267  """
1268  Wait for and return the next cartesian PointCloud message
1269  """
1270  return sick_scan_library.SickScanApiWaitNextCartesianPointCloudMsg(api_handle, msg, timeout_sec)
1271 
1272 def SickScanApiWaitNextPolarPointCloudMsg(sick_scan_library, api_handle, msg, timeout_sec):
1273  """
1274  Wait for and return the next polar PointCloud message
1275  """
1276  return sick_scan_library.SickScanApiWaitNextPolarPointCloudMsg(api_handle, msg, timeout_sec)
1277 
1278 def SickScanApiFreePointCloudMsg(sick_scan_library, api_handle, msg):
1279  """
1280  Deallocate a PointCloud message, use after SickScanApiWaitNextCartesianPointCloudMsg resp. SickScanApiWaitNextPolarPointCloudMsg
1281  """
1282  return sick_scan_library.SickScanApiFreePointCloudMsg(api_handle, msg)
1283 
1284 def SickScanApiWaitNextImuMsg(sick_scan_library, api_handle, msg, timeout_sec):
1285  """
1286  Wait for and return the next Imu message
1287  """
1288  return sick_scan_library.SickScanApiWaitNextImuMsg(api_handle, msg, timeout_sec)
1289 
1290 def SickScanApiFreeImuMsg(sick_scan_library, api_handle, msg):
1291  """
1292  Deallocate a Imu message, use after SickScanApiWaitNextImuMsg
1293  """
1294  return sick_scan_library.SickScanApiFreeImuMsg(api_handle, msg)
1295 
1296 def SickScanApiWaitNextLFErecMsg(sick_scan_library, api_handle, msg, timeout_sec):
1297  """
1298  Wait for and return the next LFErec message
1299  """
1300  return sick_scan_library.SickScanApiWaitNextLFErecMsg(api_handle, msg, timeout_sec)
1301 
1302 def SickScanApiFreeLFErecMsg(sick_scan_library, api_handle, msg):
1303  """
1304  Deallocate a LFErec message, use after SickScanApiWaitNextLFErecMsg
1305  """
1306  return sick_scan_library.SickScanApiFreeLFErecMsg(api_handle, msg)
1307 
1308 def SickScanApiWaitNextLIDoutputstateMsg(sick_scan_library, api_handle, msg, timeout_sec):
1309  """
1310  Wait for and return the next LIDoutputstate message
1311  """
1312  return sick_scan_library.SickScanApiWaitNextLIDoutputstateMsg(api_handle, msg, timeout_sec)
1313 
1314 def SickScanApiFreeLIDoutputstateMsg(sick_scan_library, api_handle, msg):
1315  """
1316  Deallocate a LIDoutputstate message, use after SickScanApiWaitNextLIDoutputstateMsg
1317  """
1318  return sick_scan_library.SickScanApiFreeLIDoutputstateMsg(api_handle, msg)
1319 
1320 def SickScanApiWaitNextRadarScanMsg(sick_scan_library, api_handle, msg, timeout_sec):
1321  """
1322  Wait for and return the next RadarScan message
1323  """
1324  return sick_scan_library.SickScanApiWaitNextRadarScanMsg(api_handle, msg, timeout_sec)
1325 
1326 def SickScanApiFreeRadarScanMsg(sick_scan_library, api_handle, msg):
1327  """
1328  Deallocate a RadarScan message, use after SickScanApiWaitNextRadarScanMsg
1329  """
1330  return sick_scan_library.SickScanApiFreeRadarScanMsg(api_handle, msg)
1331 
1332 def SickScanApiWaitNextLdmrsObjectArrayMsg(sick_scan_library, api_handle, msg, timeout_sec):
1333  """
1334  Wait for and return the next LdmrsObjectArray message
1335  """
1336  return sick_scan_library.SickScanApiWaitNextLdmrsObjectArrayMsg(api_handle, msg, timeout_sec)
1337 
1338 def SickScanApiFreeLdmrsObjectArrayMsg(sick_scan_library, api_handle, msg):
1339  """
1340  Deallocate a LdmrsObjectArray message, use after SickScanApiWaitNextLdmrsObjectArrayMsg
1341  """
1342  return sick_scan_library.SickScanApiFreeLdmrsObjectArrayMsg(api_handle, msg)
1343 
1344 def SickScanApiWaitNextVisualizationMarkerMsg(sick_scan_library, api_handle, msg, timeout_sec):
1345  """
1346  Wait for and return the next VisualizationMarker message
1347  """
1348  return sick_scan_library.SickScanApiWaitNextVisualizationMarkerMsg(api_handle, msg, timeout_sec)
1349 
1350 def SickScanApiFreeVisualizationMarkerMsg(sick_scan_library, api_handle, msg):
1351  """
1352  Deallocate a VisualizationMarker message, use after SickScanApiWaitNextVisualizationMarkerMsg
1353  """
1354  return sick_scan_library.SickScanApiFreeVisualizationMarkerMsg(api_handle, msg)
1355 
1356 def SickScanApiWaitNextNavPoseLandmarkMsg(sick_scan_library, api_handle, msg, timeout_sec):
1357  """
1358  Wait for and return the next SickScanNavPoseLandmarkMsg message
1359  """
1360  return sick_scan_library.SickScanApiWaitNextNavPoseLandmarkMsg(api_handle, msg, timeout_sec)
1361 
1362 def SickScanApiFreeNavPoseLandmarkMsg(sick_scan_library, api_handle, msg):
1363  """
1364  Deallocate a SickScanNavPoseLandmarkMsg message, use after SickScanApiWaitNextNavPoseLandmarkMsg
1365  """
1366  return sick_scan_library.SickScanApiFreeNavPoseLandmarkMsg(api_handle, msg)
1367 
1368 def SickScanApiNavOdomVelocityMsg(sick_scan_library, api_handle, msg):
1369  """
1370  Send NAV350 velocity/odometry data in nav coordinates
1371  """
1372  return sick_scan_library.SickScanApiNavOdomVelocityMsg(api_handle, msg)
1373 
1374 def SickScanApiOdomVelocityMsg(sick_scan_library, api_handle, msg):
1375  """
1376  Send velocity/odometry data in ros coordinates
1377  """
1378  return sick_scan_library.SickScanApiOdomVelocityMsg(api_handle, msg)
api.sick_scan_api.SickScanApiRegisterLFErecMsg
def SickScanApiRegisterLFErecMsg(sick_scan_library, api_handle, lferec_callback)
Definition: sick_scan_api.py:1128
api.sick_scan_api.SickScanApiFreeRadarScanMsg
def SickScanApiFreeRadarScanMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1326
api.sick_scan_api.SickScanLFErecMsg
Definition: sick_scan_api.py:307
api.sick_scan_api.SickScanApiWaitNextLFErecMsg
def SickScanApiWaitNextLFErecMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1296
api.sick_scan_api.SickScanApiErrorCodes
Definition: sick_scan_api.py:838
api.sick_scan_api.SickScanApiDeregisterLFErecMsg
def SickScanApiDeregisterLFErecMsg(sick_scan_library, api_handle, lferec_callback)
Definition: sick_scan_api.py:1134
api.sick_scan_api.SickScanNativeDataType.__int__
def __int__(self)
Definition: sick_scan_api.py:69
api.sick_scan_api.SickScanApiSetVerboseLevel
def SickScanApiSetVerboseLevel(sick_scan_library, api_handle, verbose_level)
Definition: sick_scan_api.py:1248
api.sick_scan_api.SickScanApiRegisterLogMsg
def SickScanApiRegisterLogMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1216
api.sick_scan_api.SickScanNavOdomVelocityMsg
Definition: sick_scan_api.py:796
api.sick_scan_api.SickScanApiDeregisterNavPoseLandmarkMsg
def SickScanApiDeregisterNavPoseLandmarkMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1194
api.sick_scan_api.SickScanNavPoseLandmarkMsg
Definition: sick_scan_api.py:769
api.sick_scan_api.SickScanLFErecFieldMsg
Definition: sick_scan_api.py:256
api.sick_scan_api.SickScanApiDeregisterCartesianPointCloudMsg
def SickScanApiDeregisterCartesianPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback)
Definition: sick_scan_api.py:1098
api.sick_scan_api.SickScanApiOdomVelocityMsg
def SickScanApiOdomVelocityMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1374
SickScanLdmrsObjectBufferType
Definition: sick_scan_api.h:302
api.sick_scan_api.SickScanQuaternionMsg
Definition: sick_scan_api.py:191
api.sick_scan_api.SickScanApiDeregisterPolarPointCloudMsg
def SickScanApiDeregisterPolarPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback)
Definition: sick_scan_api.py:1110
api.sick_scan_api.SickScanNativeDataType.__str__
def __str__(self)
Definition: sick_scan_api.py:71
api.sick_scan_api.SickScanLdmrsObjectArray
Definition: sick_scan_api.py:570
api.sick_scan_api.ctypesCharArrayToString
def ctypesCharArrayToString(char_array)
Definition: sick_scan_api.py:882
api.sick_scan_api.SickScanApiWaitNextVisualizationMarkerMsg
def SickScanApiWaitNextVisualizationMarkerMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1344
api.sick_scan_api.SickScanVisualizationMarkerBuffer
Definition: sick_scan_api.py:684
api.sick_scan_api.SickScanApiRegisterLdmrsObjectArrayMsg
def SickScanApiRegisterLdmrsObjectArrayMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback)
Definition: sick_scan_api.py:1164
api.sick_scan_api.SickScanApiInitByLaunchfile
def SickScanApiInitByLaunchfile(sick_scan_library, api_handle, launchfile_args)
Definition: sick_scan_api.py:1076
api.sick_scan_api.SickScanApiDeregisterImuMsg
def SickScanApiDeregisterImuMsg(sick_scan_library, api_handle, imu_callback)
Definition: sick_scan_api.py:1122
api.sick_scan_api.SickScanApiNavOdomVelocityMsg
def SickScanApiNavOdomVelocityMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1368
api.sick_scan_api.SickScanApiRegisterRadarScanMsg
def SickScanApiRegisterRadarScanMsg(sick_scan_library, api_handle, radarscan_callback)
Definition: sick_scan_api.py:1152
api.sick_scan_api.SickScanApiDeregisterVisualizationMarkerMsg
def SickScanApiDeregisterVisualizationMarkerMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback)
Definition: sick_scan_api.py:1182
api.sick_scan_api.SickScanLdmrsObject
Definition: sick_scan_api.py:545
api.sick_scan_api.SickScanPointCloudMsg
Definition: sick_scan_api.py:127
api.sick_scan_api.SickScanApiDeregisterDiagnosticMsg
def SickScanApiDeregisterDiagnosticMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1210
api.sick_scan_api.SickScanVisualizationMarker
Definition: sick_scan_api.py:623
api.sick_scan_api.SickScanApiWaitNextLIDoutputstateMsg
def SickScanApiWaitNextLIDoutputstateMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1308
api.sick_scan_api.SickScanApiDeregisterLogMsg
def SickScanApiDeregisterLogMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1222
api.sick_scan_api.SickScanApiFreeLIDoutputstateMsg
def SickScanApiFreeLIDoutputstateMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1314
api.sick_scan_api.SickScanApiFreeLFErecMsg
def SickScanApiFreeLFErecMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1302
api.sick_scan_api.SickScanVisualizationMarkerMsg
Definition: sick_scan_api.py:703
api.sick_scan_api.SickScanRadarObjectArray
Definition: sick_scan_api.py:504
api.sick_scan_api.SickScanApiFreeVisualizationMarkerMsg
def SickScanApiFreeVisualizationMarkerMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1350
api.sick_scan_api.SickScanApiErrorCodes.__int__
def __int__(self)
Definition: sick_scan_api.py:857
api.sick_scan_api.SickScanApiGetStatus
def SickScanApiGetStatus(sick_scan_library, api_handle, status_code, message_buffer, message_buffer_size)
Definition: sick_scan_api.py:1228
api.sick_scan_api.SickScanApiRegisterPolarPointCloudMsg
def SickScanApiRegisterPolarPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback)
Definition: sick_scan_api.py:1104
api.sick_scan_api.SickScanApiErrorCodes.__str__
def __str__(self)
Definition: sick_scan_api.py:859
api.sick_scan_api.SickScanApiLoadLibrary
def SickScanApiLoadLibrary(paths, lib_filname)
Definition: sick_scan_api.py:898
api.sick_scan_api.SickScanOdomVelocityMsg
Definition: sick_scan_api.py:808
api.sick_scan_api.SickScanPointFieldArray
Definition: sick_scan_api.py:108
api.sick_scan_api.SickScanApiRegisterLIDoutputstateMsg
def SickScanApiRegisterLIDoutputstateMsg(sick_scan_library, api_handle, lidoutputstate_callback)
Definition: sick_scan_api.py:1140
api.sick_scan_api.SickScanApiUnloadLibrary
def SickScanApiUnloadLibrary(sick_scan_library)
Definition: sick_scan_api.py:1055
api.sick_scan_api.SickScanRadarPreHeader
Definition: sick_scan_api.py:375
api.sick_scan_api.SickScanApiGetVerboseLevel
def SickScanApiGetVerboseLevel(sick_scan_library, api_handle)
Definition: sick_scan_api.py:1256
api.sick_scan_api.SickScanApiFreeImuMsg
def SickScanApiFreeImuMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1290
api.sick_scan_api.SickScanApiWaitNextRadarScanMsg
def SickScanApiWaitNextRadarScanMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1320
api.sick_scan_api.SickScanNativeDataType
Definition: sick_scan_api.py:57
api.sick_scan_api.SickScanDiagnosticMsg
Definition: sick_scan_api.py:829
api.sick_scan_api.SickScanVector3Msg
Definition: sick_scan_api.py:175
api.sick_scan_api.SickScanApiRegisterDiagnosticMsg
def SickScanApiRegisterDiagnosticMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1204
api.sick_scan_api.SickScanApiWaitNextLdmrsObjectArrayMsg
def SickScanApiWaitNextLdmrsObjectArrayMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1332
api.sick_scan_api.SickScanApiRelease
def SickScanApiRelease(sick_scan_library, api_handle)
Definition: sick_scan_api.py:1070
api.sick_scan_api.SickScanApiClose
def SickScanApiClose(sick_scan_library, api_handle)
Definition: sick_scan_api.py:1082
api.sick_scan_api.SickScanApiWaitNextPolarPointCloudMsg
def SickScanApiWaitNextPolarPointCloudMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1272
api.sick_scan_api.SickScanNavReflector
Definition: sick_scan_api.py:716
api.sick_scan_api.SickScanApiFreePointCloudMsg
def SickScanApiFreePointCloudMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1278
api.sick_scan_api.SickScanApiRegisterVisualizationMarkerMsg
def SickScanApiRegisterVisualizationMarkerMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback)
Definition: sick_scan_api.py:1176
api.sick_scan_api.SickScanPointFieldMsg
Definition: sick_scan_api.py:75
api.sick_scan_api.SickScanApiDeregisterLdmrsObjectArrayMsg
def SickScanApiDeregisterLdmrsObjectArrayMsg(sick_scan_library, api_handle, ldmrsobjectarray_callback)
Definition: sick_scan_api.py:1170
api.sick_scan_api.SickScanPointArray
Definition: sick_scan_api.py:209
api.sick_scan_api.loadLibrary
def loadLibrary(paths, lib_filname)
Definition: sick_scan_api.py:888
api.sick_scan_api.SickScanImuMsg
Definition: sick_scan_api.py:228
api.sick_scan_api.SickScanApiCreate
def SickScanApiCreate(sick_scan_library)
Definition: sick_scan_api.py:1061
api.sick_scan_api.SickScanApiWaitNextNavPoseLandmarkMsg
def SickScanApiWaitNextNavPoseLandmarkMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1356
api.sick_scan_api.SickScanApiRegisterNavPoseLandmarkMsg
def SickScanApiRegisterNavPoseLandmarkMsg(sick_scan_library, api_handle, callback)
Definition: sick_scan_api.py:1188
api.sick_scan_api.SickScanApiWaitNextImuMsg
def SickScanApiWaitNextImuMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1284
api.sick_scan_api.SickScanApiFreeNavPoseLandmarkMsg
def SickScanApiFreeNavPoseLandmarkMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1362
api.sick_scan_api.SickScanApiDeregisterLIDoutputstateMsg
def SickScanApiDeregisterLIDoutputstateMsg(sick_scan_library, api_handle, lidoutputstate_callback)
Definition: sick_scan_api.py:1146
api.sick_scan_api.SickScanRadarScan
Definition: sick_scan_api.py:523
api.sick_scan_api.SickScanNavReflectorBuffer
Definition: sick_scan_api.py:750
api.sick_scan_api.SickScanApiDeregisterRadarScanMsg
def SickScanApiDeregisterRadarScanMsg(sick_scan_library, api_handle, radarscan_callback)
Definition: sick_scan_api.py:1158
api.sick_scan_api.SickScanApiSendSOPAS
def SickScanApiSendSOPAS(sick_scan_library, api_handle, sopas_command, response_buffer_size=1024)
Definition: sick_scan_api.py:1235
api.sick_scan_api.SickScanLIDoutputstateMsg
Definition: sick_scan_api.py:326
api.sick_scan_api.SickScanHeader
Definition: sick_scan_api.py:16
api.sick_scan_api.SickScanRadarObject
Definition: sick_scan_api.py:444
api.sick_scan_api.SickScanApiRegisterImuMsg
def SickScanApiRegisterImuMsg(sick_scan_library, api_handle, imu_callback)
Definition: sick_scan_api.py:1116
api.sick_scan_api.SickScanApiRegisterCartesianPointCloudMsg
def SickScanApiRegisterCartesianPointCloudMsg(sick_scan_library, api_handle, pointcloud_callback)
Definition: sick_scan_api.py:1092
api.sick_scan_api.SickScanApiFreeLdmrsObjectArrayMsg
def SickScanApiFreeLdmrsObjectArrayMsg(sick_scan_library, api_handle, msg)
Definition: sick_scan_api.py:1338
api.sick_scan_api.SickScanLogMsg
Definition: sick_scan_api.py:820
api.sick_scan_api.SickScanColorRGBA
Definition: sick_scan_api.py:586
api.sick_scan_api.SickScanColorRGBAArray
Definition: sick_scan_api.py:604
api.sick_scan_api.SickScanApiWaitNextCartesianPointCloudMsg
def SickScanApiWaitNextCartesianPointCloudMsg(sick_scan_library, api_handle, msg, timeout_sec)
Definition: sick_scan_api.py:1266
api.sick_scan_api.SickScanUint8Array
Definition: sick_scan_api.py:38


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10