sick_scan_api.h
Go to the documentation of this file.
1 /*
2 * Copyright (C) 2022, Ing.-Buero Dr. Michael Lehning, Hildesheim
3 * Copyright (C) 2022, SICK AG, Waldkirch
4 * All rights reserved.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License");
7 * you may not use this file except in compliance with the License.
8 * You may obtain a copy of the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS,
14 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 * See the License for the specific language governing permissions and
16 * limitations under the License.
17 *
18 *
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions are met:
23 *
24 * * Redistributions of source code must retain the above copyright
25 * notice, this list of conditions and the following disclaimer.
26 * * Redistributions in binary form must reproduce the above copyright
27 * notice, this list of conditions and the following disclaimer in the
28 * documentation and/or other materials provided with the distribution.
29 * * Neither the name of Osnabrueck University nor the names of its
30 * contributors may be used to endorse or promote products derived from
31 * this software without specific prior written permission.
32 * * Neither the name of SICK AG nor the names of its
33 * contributors may be used to endorse or promote products derived from
34 * this software without specific prior written permission
35 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
36 * contributors may be used to endorse or promote products derived from
37 * this software without specific prior written permission
38 *
39 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
40 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
41 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
42 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
43 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
44 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
45 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
46 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
47 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
48 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
49 * POSSIBILITY OF SUCH DAMAGE.
50 *
51 * Authors:
52 * Michael Lehning <michael.lehning@lehning.de>
53 *
54 */
55 
56 #ifndef __SICK_SCAN_API_H_INCLUDED
57 #define __SICK_SCAN_API_H_INCLUDED
58 
59 /*
60 * This file declares the functions and datatypes of the sick_scan_xd C-API.
61 * See doc/sick_scan_api/sick_scan_api.md for further information.
62 */
63 
64 #include <stdint.h>
65 
66 #ifdef __cplusplus
67 extern "C" {
68 #endif
69 
70 #ifdef _MSC_VER
71 #define SICK_SCAN_API_DECLSPEC_EXPORT __declspec(dllexport)
72 #else
73 #define SICK_SCAN_API_DECLSPEC_EXPORT __attribute__ ((visibility ("default")))
74 #endif
75 
76 #ifndef SICK_SCAN_XD_API_CALLING_CONVENTION
77 #define SICK_SCAN_XD_API_CALLING_CONVENTION
78 #endif
79 
80 /*
81 * Message definitions
82 */
83 
84 typedef struct SickScanHeaderType // equivalent to ros::std_msgs::Header
85 {
86  uint32_t seq; // sequence ID: consecutively increasing ID
87  uint32_t timestamp_sec; // seconds part of message timestamps: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
88  uint32_t timestamp_nsec; // nanoseconds part of message timestamps: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
89  char frame_id[256]; // Frame this data is associated with
91 
92 typedef struct SickScanUint8ArrayType // Array of 8 bit values, which can be serialized and imported in C, C++ or Python
93 {
94  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(uint8_t)
95  uint64_t size; // Number of currently used elements in the buffer
96  uint8_t* buffer; // Memory, data in plain order (buffer == 0, if size == 0 && capacity == 0, otherwise allocated memory), allocation/deallocation always managed by the caller.
98 
99 enum SickScanNativeDataType // This message holds the description of one point entry in the PointCloud2 message format, equivalent to type enum im ros::sensor_msgs::PointField
100 {
109 };
110 
111 typedef struct SickScanPointFieldMsgType // equivalent to ros::sensor_msgs::PointField
112 {
113  // SickScanPointFieldArray is an array of SickScanPointFieldMsg, which defines the structure of the binary data of a SickScanPointCloudMsg.
114  // SickScanPointFieldMsg for pointclouds in cartesian coordinates with fields (x, y, z, intensity):
115  // [ SickScanPointFieldMsg(name="x", offset=0, datatype=FLOAT32, count=1),
116  // SickScanPointFieldMsg(name="y", offset=4, datatype=FLOAT32, count=1),
117  // SickScanPointFieldMsg(name="z", offset=8, datatype=FLOAT32, count=1),
118  // SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
119  // SickScanPointFieldMsg for pointclouds in polar coordinates with fields (range, azimuth, elevation, intensity):
120  // [ SickScanPointFieldMsg(name="range", offset=0, datatype=FLOAT32, count=1),
121  // SickScanPointFieldMsg(name="azimuth", offset=4, datatype=FLOAT32, count=1),
122  // SickScanPointFieldMsg(name="elevation", offset=8, datatype=FLOAT32, count=1),
123  // SickScanPointFieldMsg(name="intensity", offset=12, datatype=FLOAT32, count=1) ]
124  char name[256]; // Name of field (max. length 256 characters)
125  uint32_t offset; // Offset from start of point struct
126  uint8_t datatype; // Datatype enumeration, see SickScanNativeDataType above
127  uint32_t count; // How many elements in the field
129 
130 typedef struct SickScanPointFieldArrayType // Array of SickScanPointFieldMsg, which can be serialized and imported in C, C++ or python
131 {
132  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanPointFieldMsg)
133  uint64_t size; // Number of currently used elements in the buffer
134  SickScanPointFieldMsg* buffer; // 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.
136 
137 typedef struct SickScanPointCloudMsgType // equivalent to ros::std_msgs::PointCloud2
138 {
139  // SickScanPointCloudMsg contains the polar or cartesian pointcloud data.
140  // A SickScanPointCloudMsg in cartesian coordinates has fields (x, y, z, intensity).
141  // A SickScanPointCloudMsg in polar coordinates has fields (range, azimuth, elevation, intensity).
142  // Note: The pointcloud contains always <num_echos> echos. Invalid echos are filled with 0 values in the data array.
143  SickScanHeader header; // message timestamp
144  uint32_t height; // 2D structure of the point cloud. If the cloud is unordered, height is 1
145  uint32_t width; // and width is the length of the point cloud.
146  SickScanPointFieldArray fields; // Describes the channels and their layout in the binary data blob.
147  uint8_t is_bigendian; // Is this data bigendian?
148  uint32_t point_step; // Length of a point in bytes
149  uint32_t row_step; // Length of a row in bytes
150  SickScanUint8Array data; // Actual point data, size is (row_step*height)
151  uint8_t is_dense; // True if there are no invalid points
152  int32_t num_echos; // number of echos
153  int32_t segment_idx; // segment index (or -1 if pointcloud contains data from multiple segments)
154  char topic[256]; // ros topic this pointcloud is published
156 
157 typedef struct SickScanVector3MsgType // equivalent to geometry_msgs/Vector3
158 {
159  double x;
160  double y;
161  double z;
163 
164 typedef struct SickScanQuaternionMsgType // equivalent to geometry_msgs/Quaternion
165 {
166  double x;
167  double y;
168  double z;
169  double w;
171 
172 typedef struct SickScanPointArrayType // Array of SickScanVector3Msg, which can be serialized and imported in C, C++ or python
173 {
174  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVector3Msg)
175  uint64_t size; // Number of currently used elements in the buffer
176  SickScanVector3Msg* buffer; // 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.
178 
179 typedef struct SickScanImuMsgType // equivalent to ros sensor_msgs::Imu
180 {
181  SickScanHeader header; // message timestamp
183  double orientation_covariance[9]; // Row major about x, y, z axes
185  double angular_velocity_covariance[9]; // Row major about x, y, z axes
187  double linear_acceleration_covariance[9]; // Row major x, y z
189 
190 typedef struct SickScanLFErecFieldMsgType // equivalent to LFErecFieldMsg.msg
191 {
192  uint16_t version_number;
193  uint8_t field_index;
194  uint32_t sys_count;
199  uint8_t field_result_mrs; // field result is 0 (invalid/incorrect), 1 (free/clear) or 2 (infringed)
200  uint16_t time_state; // No time data: 0, Time data: 1
201  uint16_t year; // f.e. 2021
202  uint8_t month; // 1 ... 12
203  uint8_t day; // 1 ... 31
204  uint8_t hour; // 0 ... 23
205  uint8_t minute; // 0 ... 59
206  uint8_t second; // 0 ... 59
207  uint32_t microsecond; // 0 ... 999999
209 
210 typedef struct SickScanLFErecMsgType // equivalent to LFErecMsg.msg
211 {
212  SickScanHeader header; // message timestamp
213  uint16_t fields_number; // number of valid fields
214  SickScanLFErecFieldMsg fields[3]; // max. 3 valid fields
216 
217 typedef struct SickScanLIDoutputstateMsgType // equivalent to LIDoutputstateMsg.msg
218 {
219  SickScanHeader header; // message timestamp
220  uint16_t version_number; // Status code version number
221  uint32_t system_counter; // Status code system counter (time in microsec since power up, max. 71 min then starting from 0 again)
222  uint8_t output_state[8]; // array of max. 8 output states, each state with value 0 (not active), 1 (active) or 2 (not used)
223  uint32_t output_count[8]; // array of max. 8 output counter
224  uint16_t time_state; // No time data: 0, Time data: 1 (sensortime from the last change of min. one of the outputs)
225  uint16_t year; // f.e. 2021
226  uint8_t month; // 1 ... 12
227  uint8_t day; // 1 ... 31
228  uint8_t hour; // 0 ... 23
229  uint8_t minute; // 0 ... 59
230  uint8_t second; // 0 ... 59
231  uint32_t microsecond; // 0 ... 999999
233 
234 typedef struct SickScanRadarPreHeaderType // equivalent to RadarPreHeader.msg
235 {
236  uint16_t uiversionno; // version number
237  // sick_scan/RadarPreHeaderDeviceBlock:
238  uint32_t uiident; // Logical number of the device"
239  uint32_t udiserialno; // Serial number of the device
240  uint8_t bdeviceerror; // State of the device
241  uint8_t bcontaminationwarning; // Contamination Warning
242  uint8_t bcontaminationerror; // Contamination Error
243  // sick_scan/RadarPreHeaderStatusBlock:
244  uint32_t uitelegramcount; // telegram number
245  uint32_t uicyclecount; // "scan number"
246  uint32_t udisystemcountscan; // system time since power on of scan gen. [us]
247  uint32_t udisystemcounttransmit; // system time since power on of scan transmission [us]
248  uint16_t uiinputs; // state of digital inputs
249  uint16_t uioutputs; // state of digital outputs
250  // sick_scan/RadarPreHeaderMeasurementParam1Block:
251  uint32_t uicycleduration; // Time in microseconds to detect this items
252  uint32_t uinoiselevel; // [1/100dB]
253  // sick_scan/RadarPreHeaderEncoderBlock[]:
254  uint16_t numencoder; // number of valid encoders (0)
255  uint32_t udiencoderpos[3]; // array of max. 3 encoder position [inc]
256  int16_t iencoderspeed[3]; // array of max. 3 encoder speed [inc/mm]
258 
259 typedef struct SickScanRadarObjectType // equivalent to RadarObject.msg
260 {
261  int32_t id;
262  uint32_t tracking_time_sec; // seconds part of tracking_time (since when the object is tracked): seconds (stamp_secs) since epoch
263  uint32_t tracking_time_nsec; // nanoseconds part of tracking_time (since when the object is tracked): nanoseconds since stamp_secs
264  uint32_t last_seen_sec; // seconds part of last_seen timestamp: seconds (stamp_secs) since epoch
265  uint32_t last_seen_nsec; // nanoseconds part of last_seen timestamp: nanoseconds since stamp_secs
266  // geometry_msgs/TwistWithCovariance velocity
269  double velocity_covariance[36]; // Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
270  // geometry_msgs/Pose bounding_box_center
273  // geometry_msgs/Vector3 bounding_box_size
275  // geometry_msgs/PoseWithCovariance object_box_center
278  double object_box_center_covariance[36]; // Row-major representation of the 6x6 covariance matrix (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
279  // geometry_msgs/Vector3 object_box_size
281  // geometry_msgs/Point[] contour_points
284 
285 typedef struct SickScanRadarObjectArrayType // Array of SickScanRadarObject
286 {
287  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanRadarObject)
288  uint64_t size; // Number of currently used elements in the buffer
289  SickScanRadarObject* buffer; // 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.
291 
292 typedef struct SickScanRadarScanType // equivalent to RadarScan.msg
293 {
294  SickScanHeader header; // message timestamp
295  SickScanRadarPreHeader radarpreheader; // RadarPreHeader.msg
296  SickScanPointCloudMsg targets; // sensor_msgs/PointCloud2
297  SickScanRadarObjectArray objects; // Array of RadarObject.msg
299 
300 typedef SickScanRadarObject SickScanLdmrsObject; // equivalent to SickLdmrsObject.msg
301 
302 typedef struct SickScanLdmrsObjectBufferType // Array of SickScanLdmrsObject
303 {
304  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanLdmrsObject)
305  uint64_t size; // Number of currently used elements in the buffer
306  SickScanLdmrsObject* buffer; // 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.
308 
309 typedef struct SickScanLdmrsObjectArrayType // equivalent to SickLdmrsObjectArray.msg
310 {
311  SickScanHeader header; // message timestamp
312  SickScanLdmrsObjectBuffer objects; // Array of SickScanLdmrsObjects
314 
315 typedef struct SickScanColorRGBAType // equivalent to std_msgs::ColorRGBA
316 {
317  float r;
318  float g;
319  float b;
320  float a;
322 
323 typedef struct SickScanColorRGBAArrayType // Array of SickScanColorRGBA, which can be serialized and imported in C, C++ or python
324 {
325  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanColorRGBA)
326  uint64_t size; // Number of currently used elements in the buffer
327  SickScanColorRGBA* buffer; // 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.
329 
330 typedef struct SickScanVisualizationMarkerType // equivalent to visualization_msgs::Marker
331 {
332  SickScanHeader header; // message timestamp
333  char ns[1024]; // Namespace to place this object in... used in conjunction with id to create a unique name for the object
334  int32_t id; // object ID useful in conjunction with the namespace for manipulating and deleting the object later
335  int32_t type; // Type of object
336  int32_t action; // 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects
337  SickScanVector3Msg pose_position; // Pose of the object (positional part)
338  SickScanQuaternionMsg pose_orientation; // Pose of the object (rotational part)
339  SickScanVector3Msg scale; // Scale of the object 1,1,1 means default (usually 1 meter square)
340  SickScanColorRGBA color; // Color [0.0-1.0]
341  uint32_t lifetime_sec; // How long the object should last before being automatically deleted. 0 means forever (seconds part)
342  uint32_t lifetime_nsec; // How long the object should last before being automatically deleted. 0 means forever (nanoseconds part)
343  uint8_t frame_locked; // boolean, If this marker should be frame-locked, i.e. retransformed into its frame every timestep
344  SickScanPointArray points; // Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
345  SickScanColorRGBAArray colors; // 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
346  char text[1024]; // NOTE: only used for text markers
347  char mesh_resource[1024]; // NOTE: only used for MESH_RESOURCE markers
348  uint8_t mesh_use_embedded_materials; // boolean
350 
351 typedef struct SickScanVisualizationMarkerBufferType // Array of SickScanVisualizationMarkers
352 {
353  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanVisualizationMarker)
354  uint64_t size; // Number of currently used elements in the buffer
355  SickScanVisualizationMarker* buffer; // 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.
357 
358 typedef struct SickScanVisualizationMarkerMsgType // equivalent to visualization_msgs::MarkerArray
359 {
360  SickScanVisualizationMarkerBuffer markers; // Array of SickScanVisualizationMarkers
362 
363 typedef struct SickScanNavReflectorType // NAV-350 reflector
364 {
365  uint16_t pos_valid;
366  float pos_x; // reflector x-position in m, if pos_valid > 0
367  float pos_y; // reflector y-position in m, if pos_valid > 0
368  uint16_t cartesian_valid;
369  int32_t cartesian_x; // cartesian x in mm, if cartesian_valid > 0
370  int32_t cartesian_y; // cartesian y in mm, if cartesian_valid > 0
371  uint16_t polar_valid;
372  uint32_t polar_dist; // polar dist in mm, if polar_valid > 0
373  uint32_t polar_phi; // polar phi in mdeg, if polar_valid > 0
374  uint16_t opt_valid;
375  // Optional reflector data, if opt_valid > 0
376  uint16_t opt_local_id;
377  uint16_t opt_global_id;
378  uint8_t opt_type;
379  uint16_t opt_subtype;
380  uint16_t opt_quality;
381  uint32_t opt_timestamp; // lidar timestamp in milliseconds
382  uint16_t opt_size;
383  uint16_t opt_hitcount;
384  uint16_t opt_meanecho;
385  uint16_t opt_startindex;
386  uint16_t opt_endindex;
387  uint32_t opt_timestamp_sec; // timestamp converted to system time (seconds part, 0 if timestamp not valid)
388  uint32_t opt_timestamp_nsec; // timestamp converted to system time (nanoseconds part, 0 if timestamp not valid)
390 
391 typedef struct SickScanNavReflectorBufferType // Array of SickScanNavReflectors
392 {
393  uint64_t capacity; // Number of allocated elements, i.e. max. number of elements in buffer, allocated buffer size is capacity * sizeof(SickScanNavReflector)
394  uint64_t size; // Number of currently used elements in the buffer
395  SickScanNavReflector* buffer; // 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.
397 
398 typedef struct SickScanNavPoseLandmarkMsgType // NAV-350 pose and landmark message
399 {
400  uint16_t pose_valid;
401  // NAV pose, if pose_valid > 0:
402  float pose_x; // x-position in ros coordinates in m
403  float pose_y; // y-position in ros coordinates in m
404  float pose_yaw; // yaw angle in ros coordinates in radians
405  uint32_t pose_timestamp_sec; // timestamp of pose converted to system time (seconds part, 0 if timestamp not valid)
406  uint32_t pose_timestamp_nsec; // timestamp of pose converted to system time (nanoseconds part, 0 if timestamp not valid)
407  int32_t pose_nav_x; // x-position in lidar coordinates in mm
408  int32_t pose_nav_y; // y-position in lidar coordinates in mm
409  uint32_t pose_nav_phi; // orientation in lidar coordinates in 0 ... 360000 mdeg
410  uint16_t pose_opt_valid;
411  // Optional NAV pose data, if pose_opt_valid > 0:
413  uint32_t pose_opt_timestamp; // lidar timestamp in milliseconds
418  // NAV reflectors:
419  SickScanNavReflectorBuffer reflectors; // Array of SickScanNavReflectors
421 
422 typedef struct SickScanNavOdomVelocityMsgType // NAV350 velocity/odometry data, see NAVOdomVelocity.msg
423 {
424  float vel_x; // 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
425  float vel_y; // 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
426  float omega; // angular velocity of the NAV350 in radians/s, -2*PI ... +2*PI rad/s
427  uint32_t timestamp; // timestamp of the Velocity vector related to the NAV350 clock
428  uint8_t coordbase; // coordinate system of the velocity vector (local or global), 0 = local coordinate system of the NAV350, 1 = absolute coordinate system
430 
431 typedef struct SickScanOdomVelocityMsgType // Velocity/odometry data in system coordinates and time
432 {
433  float vel_x; // x-component of velocity in ros coordinates in m/s
434  float vel_y; // y-component of velocity in ros coordinates in m/s
435  float omega; // angular velocity in radians/s
436  uint32_t timestamp_sec; // seconds part of system timestamp of the odometry data
437  uint32_t timestamp_nsec; // nanoseconds part of system timestamp of the odometry data
439 
440 typedef struct SickScanLogMsgType // general log message
441 {
442  int32_t log_level; // log_level defined in ros::console::levels: Info=1, Warn=2, Error=3, Fatal=4
443  char* log_message; // log message
445 
446 typedef struct SickScanDiagnosticMsgType // general diagnostic message
447 {
448  int32_t status_code; // 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)
449  char* status_message; // diagnostic message
451 
452 /*
453 * Callback declarations
454 */
455 
456 typedef void* SickScanApiHandle;
467 
468 /*
469 * Functions to initialize and close the API and a lidar
470 */
471 
472 // Load sick_scan_xd api library (dll or so file)
473 int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiLoadLibrary(const char* library_filepath);
474 
475 // Unload sick_scan_xd api library
477 
478 /*
479 * Create an instance of sick_scan_xd api.
480 * Optional commandline arguments argc, argv identical to sick_generic_caller.
481 * Call SickScanApiInitByLaunchfile or SickScanApiInitByCli to process a lidar.
482 */
484 
485 // Release and free all resources of a handle; the handle is invalid after SickScanApiRelease
487 
488 // Initializes a lidar by launchfile and starts message receiving and processing
490 
491 // Initializes a lidar by commandline arguments and starts message receiving and processing
493 
494 // Stops message receiving and processing and closes a lidar
496 
497 /*
498 * Registration / deregistration of message callbacks
499 */
500 
501 // Register / deregister a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
504 
505 // Register / deregister a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
508 
509 // Register / deregister a callback for Imu messages
512 
513 // Register / deregister a callback for SickScanLFErecMsg messages
516 
517 // Register / deregister a callback for SickScanLIDoutputstateMsg messages
520 
521 // Register / deregister a callback for SickScanRadarScan messages
524 
525 // Register / deregister a callback for SickScanLdmrsObjectArray messages
528 
529 // Register / deregister a callback for VisualizationMarker messages
532 
533 // Register / deregister a callback for SickScanNavPoseLandmark messages
536 
537 /*
538 * Functions for diagnostic and logging
539 */
540 
541 // Register / deregister a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
544 
545 // Register / deregister a callback for log messages (all informational and error messages)
548 
549 // Query current status and status message
550 SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t* status_code, char* message_buffer, int32_t message_buffer_size);
551 
552 // Sends a SOPAS command like "sRN SCdevicestate" or "sRN ContaminationResult" and returns the lidar response
553 SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSendSOPAS(SickScanApiHandle apiHandle, const char* sopas_command, char* sopas_response_buffer, int32_t response_buffer_size);
554 
555 // Set verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET (equivalent to ros::console::levels),
556 // i.e. print messages on console above the given verbose level.
557 // Default verbose level is 1 (INFO), i.e. print informational, warnings and error messages.
559 
560 // Returns the current verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET. Default verbose level is 1 (INFO)
562 
563 /*
564 * Polling functions
565 */
566 
567 // Wait for and return the next cartesian resp. polar PointCloud message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
571 
572 // Wait for and return the next Imu message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
575 
576 // Wait for and return the next LFErec message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
579 
580 // Wait for and return the next LIDoutputstate message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
583 
584 // Wait for and return the next RadarScan message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
587 
588 // Wait for and return the next LdmrsObjectArray message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
591 
592 // Wait for and return the next VisualizationMarker message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
595 
596 // Wait for and return the next SickScanNavPoseLandmark message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
599 
600 // Send odometry data to NAV350
603 
604 /*
605 * Error codes, return values of SickScanApi-functions
606 */
608 {
609  SICK_SCAN_API_SUCCESS = 0, // function executed successfully
610  SICK_SCAN_API_ERROR = 1, // general (unspecified) error
611  SICK_SCAN_API_NOT_LOADED = 2, // sick_scan_xd library not loaded
612  SICK_SCAN_API_NOT_INITIALIZED = 3, // API not initialized
613  SICK_SCAN_API_NOT_IMPLEMENTED = 4, // function not implemented in sick_scan_xd library
614  SICK_SCAN_API_TIMEOUT = 5 // timeout during wait for response
615 };
616 
617 #ifdef __cplusplus
618 } // extern "C"
619 #endif
620 
621 #endif // __SICK_SCAN_API_H_INCLUDED
SickScanQuaternionMsgType::z
double z
Definition: sick_scan_api.h:168
SickScanApiDeregisterLFErecMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: api_impl.cpp:1042
SickScanApiGetVerboseLevel
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetVerboseLevel(SickScanApiHandle apiHandle)
Definition: api_impl.cpp:1459
SickScanLFErecFieldMsgType::field_index
uint8_t field_index
Definition: sick_scan_api.h:193
SickScanApiWaitNextCartesianPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1508
SickScanLIDoutputstateMsgType::output_count
uint32_t output_count[8]
Definition: sick_scan_api.h:223
SickScanApiWaitNextLdmrsObjectArrayMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg, double timeout_sec)
Definition: api_impl.cpp:1843
SickScanLFErecFieldMsgType::minute
uint8_t minute
Definition: sick_scan_api.h:205
SickScanApiWaitNextLFErecMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1675
SickScanHeaderType::timestamp_sec
uint32_t timestamp_sec
Definition: sick_scan_api.h:87
SickScanLIDoutputstateMsgType::microsecond
uint32_t microsecond
Definition: sick_scan_api.h:231
SICK_SCAN_API_NOT_IMPLEMENTED
@ SICK_SCAN_API_NOT_IMPLEMENTED
Definition: sick_scan_api.h:613
SickScanRadarObjectType::contour_points
SickScanPointArray contour_points
Definition: sick_scan_api.h:282
SickScanOdomVelocityMsgType
Definition: sick_scan_api.h:431
SickScanApiRegisterVisualizationMarkerMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: api_impl.cpp:1218
SickScanHeaderType::seq
uint32_t seq
Definition: sick_scan_api.h:86
SickScanLdmrsObjectBufferType::buffer
SickScanLdmrsObject * buffer
Definition: sick_scan_api.h:306
SickScanVisualizationMarkerMsgType::markers
SickScanVisualizationMarkerBuffer markers
Definition: sick_scan_api.h:360
SickScanVisualizationMarker
struct SickScanVisualizationMarkerType SickScanVisualizationMarker
SICK_SCAN_API_SUCCESS
@ SICK_SCAN_API_SUCCESS
Definition: sick_scan_api.h:609
SickScanColorRGBAType::b
float b
Definition: sick_scan_api.h:319
SickScanApiRegisterLdmrsObjectArrayMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: api_impl.cpp:1168
SickScanRadarObjectType::last_seen_sec
uint32_t last_seen_sec
Definition: sick_scan_api.h:264
SickScanRadarObjectArrayType::capacity
uint64_t capacity
Definition: sick_scan_api.h:287
SickScanNavPoseLandmarkMsgType::pose_opt_mean_dev
int32_t pose_opt_mean_dev
Definition: sick_scan_api.h:414
msg
msg
SickScanNavPoseLandmarkMsgType::pose_opt_nav_mode
uint8_t pose_opt_nav_mode
Definition: sick_scan_api.h:415
SickScanNavReflectorType::polar_valid
uint16_t polar_valid
Definition: sick_scan_api.h:371
SickScanPointCloudMsgType::is_dense
uint8_t is_dense
Definition: sick_scan_api.h:151
SickScanPointArray
struct SickScanPointArrayType SickScanPointArray
SickScanLFErecFieldMsgType::month
uint8_t month
Definition: sick_scan_api.h:202
SickScanApiErrorCodes
SickScanApiErrorCodes
Definition: sick_scan_api.h:607
SICK_SCAN_POINTFIELD_DATATYPE_INT32
@ SICK_SCAN_POINTFIELD_DATATYPE_INT32
Definition: sick_scan_api.h:105
SickScanLdmrsObjectBuffer
struct SickScanLdmrsObjectBufferType SickScanLdmrsObjectBuffer
SickScanPointFieldArrayType::size
uint64_t size
Definition: sick_scan_api.h:133
SickScanRadarPreHeaderType::udiencoderpos
uint32_t udiencoderpos[3]
Definition: sick_scan_api.h:255
SickScanPointArrayType::size
uint64_t size
Definition: sick_scan_api.h:175
SickScanVisualizationMarkerBuffer
struct SickScanVisualizationMarkerBufferType SickScanVisualizationMarkerBuffer
SickScanQuaternionMsgType::w
double w
Definition: sick_scan_api.h:169
SickScanRadarPreHeaderType::udiserialno
uint32_t udiserialno
Definition: sick_scan_api.h:239
SickScanPointCloudMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanPointCloudMsgCallback)(SickScanApiHandle apiHandle, const SickScanPointCloudMsg *msg)
Definition: sick_scan_api.h:457
SickScanApiNavOdomVelocityMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiNavOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *msg)
Definition: api_impl.cpp:2129
SickScanImuMsgType::linear_acceleration
SickScanVector3Msg linear_acceleration
Definition: sick_scan_api.h:186
SickScanOdomVelocityMsgType::timestamp_sec
uint32_t timestamp_sec
Definition: sick_scan_api.h:436
SickScanNavReflector
struct SickScanNavReflectorType SickScanNavReflector
SickScanNavOdomVelocityMsgType::timestamp
uint32_t timestamp
Definition: sick_scan_api.h:427
SickScanLFErecFieldMsgType::microsecond
uint32_t microsecond
Definition: sick_scan_api.h:207
SickScanNavPoseLandmarkMsg
struct SickScanNavPoseLandmarkMsgType SickScanNavPoseLandmarkMsg
SickScanDiagnosticMsgType
Definition: sick_scan_api.h:446
SickScanPointArrayType::capacity
uint64_t capacity
Definition: sick_scan_api.h:174
SickScanPointCloudMsgType::height
uint32_t height
Definition: sick_scan_api.h:144
SickScanRadarPreHeaderType::uiinputs
uint16_t uiinputs
Definition: sick_scan_api.h:248
SickScanNavPoseLandmarkMsgType::pose_valid
uint16_t pose_valid
Definition: sick_scan_api.h:400
SickScanNavPoseLandmarkMsgType::pose_nav_y
int32_t pose_nav_y
Definition: sick_scan_api.h:408
SickScanNavPoseLandmarkMsgType::reflectors
SickScanNavReflectorBuffer reflectors
Definition: sick_scan_api.h:419
SickScanUint8ArrayType
Definition: sick_scan_api.h:92
SickScanNavReflectorType::opt_timestamp_sec
uint32_t opt_timestamp_sec
Definition: sick_scan_api.h:387
SickScanLdmrsObjectArrayCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLdmrsObjectArrayCallback)(SickScanApiHandle apiHandle, const SickScanLdmrsObjectArray *msg)
Definition: sick_scan_api.h:462
SickScanApiUnloadLibrary
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiUnloadLibrary()
Definition: sick_scan_xd_api_wrapper.c:234
SickScanColorRGBA
struct SickScanColorRGBAType SickScanColorRGBA
SickScanLFErecFieldMsgType::year
uint16_t year
Definition: sick_scan_api.h:201
SickScanLogMsgType::log_level
int32_t log_level
Definition: sick_scan_api.h:442
SickScanVisualizationMarkerType::mesh_resource
char mesh_resource[1024]
Definition: sick_scan_api.h:347
SickScanRadarObjectType::velocity_covariance
double velocity_covariance[36]
Definition: sick_scan_api.h:269
SickScanRadarPreHeaderType::uitelegramcount
uint32_t uitelegramcount
Definition: sick_scan_api.h:244
SickScanRadarObjectArrayType::size
uint64_t size
Definition: sick_scan_api.h:288
SickScanRadarPreHeaderType::bdeviceerror
uint8_t bdeviceerror
Definition: sick_scan_api.h:240
SickScanRadarPreHeaderType::uicyclecount
uint32_t uicyclecount
Definition: sick_scan_api.h:245
SickScanLFErecFieldMsgType::dist_scale_factor
float dist_scale_factor
Definition: sick_scan_api.h:195
SickScanRadarPreHeaderType
Definition: sick_scan_api.h:234
SickScanNavReflectorBufferType::size
uint64_t size
Definition: sick_scan_api.h:394
SickScanApiDeregisterLdmrsObjectArrayMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: api_impl.cpp:1192
SickScanLFErecMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLFErecMsgCallback)(SickScanApiHandle apiHandle, const SickScanLFErecMsg *msg)
Definition: sick_scan_api.h:459
SickScanLdmrsObjectBufferType
Definition: sick_scan_api.h:302
SickScanVisualizationMarkerType::points
SickScanPointArray points
Definition: sick_scan_api.h:344
SickScanLogMsgType::log_message
char * log_message
Definition: sick_scan_api.h:443
SickScanLIDoutputstateMsgType::month
uint8_t month
Definition: sick_scan_api.h:226
SickScanRadarObjectType::velocity_linear
SickScanVector3Msg velocity_linear
Definition: sick_scan_api.h:267
SickScanApiWaitNextLIDoutputstateMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1731
SickScanLIDoutputstateMsgType::system_counter
uint32_t system_counter
Definition: sick_scan_api.h:221
SickScanHeader
struct SickScanHeaderType SickScanHeader
SickScanPointCloudMsgType::topic
char topic[256]
Definition: sick_scan_api.h:154
SickScanLIDoutputstateMsgType::version_number
uint16_t version_number
Definition: sick_scan_api.h:220
SickScanNavReflectorType::opt_timestamp
uint32_t opt_timestamp
Definition: sick_scan_api.h:381
SickScanLFErecFieldMsg
struct SickScanLFErecFieldMsgType SickScanLFErecFieldMsg
SickScanApiDeregisterRadarScanMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: api_impl.cpp:1142
SickScanApiFreeVisualizationMarkerMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg)
Definition: api_impl.cpp:1944
SickScanImuMsgType::orientation
SickScanQuaternionMsg orientation
Definition: sick_scan_api.h:182
SickScanPointFieldMsgType::offset
uint32_t offset
Definition: sick_scan_api.h:125
SickScanNavReflectorType::pos_x
float pos_x
Definition: sick_scan_api.h:366
SickScanApiRegisterRadarScanMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: api_impl.cpp:1118
SickScanApiRegisterDiagnosticMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: api_impl.cpp:1271
SickScanRadarPreHeaderType::numencoder
uint16_t numencoder
Definition: sick_scan_api.h:254
SickScanRadarObjectType::velocity_angular
SickScanVector3Msg velocity_angular
Definition: sick_scan_api.h:268
SickScanApiLoadLibrary
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiLoadLibrary(const char *library_filepath)
Definition: sick_scan_xd_api_wrapper.c:218
SickScanRadarPreHeaderType::uiident
uint32_t uiident
Definition: sick_scan_api.h:238
SickScanNavPoseLandmarkCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanNavPoseLandmarkCallback)(SickScanApiHandle apiHandle, const SickScanNavPoseLandmarkMsg *msg)
Definition: sick_scan_api.h:464
SickScanOdomVelocityMsg
struct SickScanOdomVelocityMsgType SickScanOdomVelocityMsg
SickScanNavPoseLandmarkMsgType::pose_opt_timestamp
uint32_t pose_opt_timestamp
Definition: sick_scan_api.h:413
SickScanVector3MsgType::y
double y
Definition: sick_scan_api.h:160
SickScanLFErecFieldMsgType
Definition: sick_scan_api.h:190
SickScanImuMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanImuMsgCallback)(SickScanApiHandle apiHandle, const SickScanImuMsg *msg)
Definition: sick_scan_api.h:458
SickScanVisualizationMarkerBufferType::capacity
uint64_t capacity
Definition: sick_scan_api.h:353
SickScanOdomVelocityMsgType::vel_x
float vel_x
Definition: sick_scan_api.h:433
SICK_SCAN_XD_API_CALLING_CONVENTION
#define SICK_SCAN_XD_API_CALLING_CONVENTION
Definition: sick_scan_api.h:77
SickScanApiInitByLaunchfile
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByLaunchfile(SickScanApiHandle apiHandle, const char *launchfile_args)
Definition: api_impl.cpp:710
SickScanPointArrayType::buffer
SickScanVector3Msg * buffer
Definition: sick_scan_api.h:176
SickScanImuMsgType::linear_acceleration_covariance
double linear_acceleration_covariance[9]
Definition: sick_scan_api.h:187
SICK_SCAN_POINTFIELD_DATATYPE_UINT8
@ SICK_SCAN_POINTFIELD_DATATYPE_UINT8
Definition: sick_scan_api.h:102
SickScanQuaternionMsg
struct SickScanQuaternionMsgType SickScanQuaternionMsg
SickScanNavReflectorType::polar_phi
uint32_t polar_phi
Definition: sick_scan_api.h:373
SickScanNavReflectorType::opt_type
uint8_t opt_type
Definition: sick_scan_api.h:378
SickScanRadarObjectType
Definition: sick_scan_api.h:259
SickScanRadarPreHeaderType::udisystemcounttransmit
uint32_t udisystemcounttransmit
Definition: sick_scan_api.h:247
SICK_SCAN_POINTFIELD_DATATYPE_INT8
@ SICK_SCAN_POINTFIELD_DATATYPE_INT8
Definition: sick_scan_api.h:101
SICK_SCAN_API_TIMEOUT
@ SICK_SCAN_API_TIMEOUT
Definition: sick_scan_api.h:614
SickScanNavReflectorType::pos_y
float pos_y
Definition: sick_scan_api.h:367
SickScanDiagnosticMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanDiagnosticMsgCallback)(SickScanApiHandle apiHandle, const SickScanDiagnosticMsg *msg)
Definition: sick_scan_api.h:466
SickScanNavPoseLandmarkMsgType::pose_nav_x
int32_t pose_nav_x
Definition: sick_scan_api.h:407
SickScanNavReflectorBufferType
Definition: sick_scan_api.h:391
SickScanColorRGBAArrayType
Definition: sick_scan_api.h:323
SickScanLFErecFieldMsgType::hour
uint8_t hour
Definition: sick_scan_api.h:204
SickScanVisualizationMarkerType::type
int32_t type
Definition: sick_scan_api.h:335
SickScanRadarObjectType::tracking_time_nsec
uint32_t tracking_time_nsec
Definition: sick_scan_api.h:263
SickScanRadarObjectType::bounding_box_size
SickScanVector3Msg bounding_box_size
Definition: sick_scan_api.h:274
SickScanRadarScanType
Definition: sick_scan_api.h:292
SickScanApiWaitNextImuMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1619
SickScanVisualizationMarkerType::lifetime_sec
uint32_t lifetime_sec
Definition: sick_scan_api.h:341
SickScanPointFieldArrayType::buffer
SickScanPointFieldMsg * buffer
Definition: sick_scan_api.h:134
SickScanNavReflectorType::opt_timestamp_nsec
uint32_t opt_timestamp_nsec
Definition: sick_scan_api.h:388
SickScanNativeDataType
SickScanNativeDataType
Definition: sick_scan_api.h:99
SickScanPointFieldArrayType
Definition: sick_scan_api.h:130
SickScanNavReflectorType::opt_endindex
uint16_t opt_endindex
Definition: sick_scan_api.h:386
SickScanPointCloudMsgType::data
SickScanUint8Array data
Definition: sick_scan_api.h:150
SickScanNavOdomVelocityMsg
struct SickScanNavOdomVelocityMsgType SickScanNavOdomVelocityMsg
SickScanQuaternionMsgType::x
double x
Definition: sick_scan_api.h:166
SICK_SCAN_API_ERROR
@ SICK_SCAN_API_ERROR
Definition: sick_scan_api.h:610
SickScanUint8ArrayType::size
uint64_t size
Definition: sick_scan_api.h:95
SickScanApiRegisterCartesianPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: api_impl.cpp:868
SickScanRadarObjectType::bounding_box_center_position
SickScanVector3Msg bounding_box_center_position
Definition: sick_scan_api.h:271
SickScanColorRGBAArrayType::capacity
uint64_t capacity
Definition: sick_scan_api.h:325
SickScanVisualizationMarkerType::text
char text[1024]
Definition: sick_scan_api.h:346
SickScanColorRGBAArrayType::size
uint64_t size
Definition: sick_scan_api.h:326
SickScanRadarScanType::objects
SickScanRadarObjectArray objects
Definition: sick_scan_api.h:297
SickScanApiWaitNextVisualizationMarkerMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1899
SickScanPointFieldArray
struct SickScanPointFieldArrayType SickScanPointFieldArray
SickScanLFErecMsg
struct SickScanLFErecMsgType SickScanLFErecMsg
SickScanRadarObjectArrayType
Definition: sick_scan_api.h:285
SickScanApiFreeImuMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg)
Definition: api_impl.cpp:1664
SickScanLIDoutputstateMsg
struct SickScanLIDoutputstateMsgType SickScanLIDoutputstateMsg
SICK_SCAN_API_DECLSPEC_EXPORT
#define SICK_SCAN_API_DECLSPEC_EXPORT
Definition: sick_scan_api.h:73
SickScanLFErecFieldMsgType::day
uint8_t day
Definition: sick_scan_api.h:203
SickScanUint8Array
struct SickScanUint8ArrayType SickScanUint8Array
SickScanRadarObjectType::tracking_time_sec
uint32_t tracking_time_sec
Definition: sick_scan_api.h:262
SickScanImuMsgType::angular_velocity
SickScanVector3Msg angular_velocity
Definition: sick_scan_api.h:184
SickScanPointCloudMsgType
Definition: sick_scan_api.h:137
SickScanVisualizationMarkerType::lifetime_nsec
uint32_t lifetime_nsec
Definition: sick_scan_api.h:342
SickScanNavReflectorType::cartesian_y
int32_t cartesian_y
Definition: sick_scan_api.h:370
SickScanNavReflectorType::cartesian_x
int32_t cartesian_x
Definition: sick_scan_api.h:369
SickScanRadarObject
struct SickScanRadarObjectType SickScanRadarObject
SickScanUint8ArrayType::buffer
uint8_t * buffer
Definition: sick_scan_api.h:96
SickScanApiInitByCli
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByCli(SickScanApiHandle apiHandle, int argc, char **argv)
Definition: api_impl.cpp:765
SICK_SCAN_API_NOT_LOADED
@ SICK_SCAN_API_NOT_LOADED
Definition: sick_scan_api.h:611
SickScanLIDoutputstateMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLIDoutputstateMsgCallback)(SickScanApiHandle apiHandle, const SickScanLIDoutputstateMsg *msg)
Definition: sick_scan_api.h:460
SickScanNavPoseLandmarkMsgType::pose_x
float pose_x
Definition: sick_scan_api.h:402
SickScanApiOdomVelocityMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *msg)
Definition: api_impl.cpp:2133
SickScanVisualizationMarkerType::color
SickScanColorRGBA color
Definition: sick_scan_api.h:340
SickScanVisualizationMarkerCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanVisualizationMarkerCallback)(SickScanApiHandle apiHandle, const SickScanVisualizationMarkerMsg *msg)
Definition: sick_scan_api.h:463
SickScanLFErecMsgType::header
SickScanHeader header
Definition: sick_scan_api.h:212
SickScanNavPoseLandmarkMsgType::pose_opt_quant_used_reflectors
uint8_t pose_opt_quant_used_reflectors
Definition: sick_scan_api.h:417
SickScanVisualizationMarkerType::pose_position
SickScanVector3Msg pose_position
Definition: sick_scan_api.h:337
SickScanVector3MsgType::z
double z
Definition: sick_scan_api.h:161
SickScanNavReflectorBufferType::buffer
SickScanNavReflector * buffer
Definition: sick_scan_api.h:395
SickScanImuMsgType::orientation_covariance
double orientation_covariance[9]
Definition: sick_scan_api.h:183
SickScanVisualizationMarkerType::action
int32_t action
Definition: sick_scan_api.h:336
SickScanLFErecFieldMsgType::angle_scale_offset
int32_t angle_scale_offset
Definition: sick_scan_api.h:198
SickScanApiSendSOPAS
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSendSOPAS(SickScanApiHandle apiHandle, const char *sopas_command, char *sopas_response_buffer, int32_t response_buffer_size)
Definition: api_impl.cpp:1397
SickScanApiDeregisterDiagnosticMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: api_impl.cpp:1295
SickScanApiRegisterNavPoseLandmarkMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: api_impl.cpp:2030
SickScanRadarPreHeaderType::uiversionno
uint16_t uiversionno
Definition: sick_scan_api.h:236
SickScanApiWaitNextPolarPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: api_impl.cpp:1558
SickScanRadarObjectType::object_box_size
SickScanVector3Msg object_box_size
Definition: sick_scan_api.h:280
SickScanApiFreeLIDoutputstateMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg)
Definition: api_impl.cpp:1776
SickScanNavReflectorType::opt_size
uint16_t opt_size
Definition: sick_scan_api.h:382
SickScanApiHandle
void * SickScanApiHandle
Definition: sick_scan_api.h:456
SickScanNavPoseLandmarkMsgType::pose_nav_phi
uint32_t pose_nav_phi
Definition: sick_scan_api.h:409
SickScanLdmrsObjectBufferType::capacity
uint64_t capacity
Definition: sick_scan_api.h:304
SickScanNavReflectorType::cartesian_valid
uint16_t cartesian_valid
Definition: sick_scan_api.h:368
SickScanVisualizationMarkerType::frame_locked
uint8_t frame_locked
Definition: sick_scan_api.h:343
SickScanApiRegisterLogMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: api_impl.cpp:1319
SickScanColorRGBAType::r
float r
Definition: sick_scan_api.h:317
SickScanNavReflectorBuffer
struct SickScanNavReflectorBufferType SickScanNavReflectorBuffer
SickScanLFErecFieldMsgType::dist_scale_offset
float dist_scale_offset
Definition: sick_scan_api.h:196
SickScanApiFreePointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreePointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg)
Definition: api_impl.cpp:1608
SickScanApiFreeLdmrsObjectArrayMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg)
Definition: api_impl.cpp:1888
SICK_SCAN_API_NOT_INITIALIZED
@ SICK_SCAN_API_NOT_INITIALIZED
Definition: sick_scan_api.h:612
SickScanNavReflectorType::opt_subtype
uint16_t opt_subtype
Definition: sick_scan_api.h:379
SickScanRadarScanType::targets
SickScanPointCloudMsg targets
Definition: sick_scan_api.h:296
SickScanLdmrsObjectArray
struct SickScanLdmrsObjectArrayType SickScanLdmrsObjectArray
SickScanVisualizationMarkerMsg
struct SickScanVisualizationMarkerMsgType SickScanVisualizationMarkerMsg
SickScanLIDoutputstateMsgType::day
uint8_t day
Definition: sick_scan_api.h:227
SickScanNavPoseLandmarkMsgType::pose_yaw
float pose_yaw
Definition: sick_scan_api.h:404
SickScanRadarPreHeader
struct SickScanRadarPreHeaderType SickScanRadarPreHeader
SickScanNavReflectorType::opt_hitcount
uint16_t opt_hitcount
Definition: sick_scan_api.h:383
SickScanRadarObjectType::object_box_center_orientation
SickScanQuaternionMsg object_box_center_orientation
Definition: sick_scan_api.h:277
SickScanApiDeregisterCartesianPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: api_impl.cpp:892
SickScanLIDoutputstateMsgType::hour
uint8_t hour
Definition: sick_scan_api.h:228
SickScanRadarScan
struct SickScanRadarScanType SickScanRadarScan
SickScanDiagnosticMsgType::status_code
int32_t status_code
Definition: sick_scan_api.h:448
SickScanVisualizationMarkerType::ns
char ns[1024]
Definition: sick_scan_api.h:333
SickScanApiFreeRadarScanMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg)
Definition: api_impl.cpp:1832
SickScanPointArrayType
Definition: sick_scan_api.h:172
SickScanApiFreeLFErecMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg)
Definition: api_impl.cpp:1720
SickScanApiSetVerboseLevel
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSetVerboseLevel(SickScanApiHandle apiHandle, int32_t verbose_level)
Definition: api_impl.cpp:1435
SickScanVisualizationMarkerBufferType
Definition: sick_scan_api.h:351
SickScanNavReflectorType::opt_quality
uint16_t opt_quality
Definition: sick_scan_api.h:380
SickScanApiDeregisterLogMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: api_impl.cpp:1343
SickScanHeaderType::timestamp_nsec
uint32_t timestamp_nsec
Definition: sick_scan_api.h:88
sick_scan_xd_api_test.verbose_level
verbose_level
Definition: sick_scan_xd_api_test.py:346
SickScanOdomVelocityMsgType::vel_y
float vel_y
Definition: sick_scan_api.h:434
SickScanLFErecFieldMsgType::version_number
uint16_t version_number
Definition: sick_scan_api.h:192
SickScanLFErecMsgType::fields_number
uint16_t fields_number
Definition: sick_scan_api.h:213
SickScanNavReflectorType::pos_valid
uint16_t pos_valid
Definition: sick_scan_api.h:365
SickScanNavOdomVelocityMsgType::vel_x
float vel_x
Definition: sick_scan_api.h:424
SickScanVector3MsgType
Definition: sick_scan_api.h:157
SickScanApiDeregisterLIDoutputstateMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: api_impl.cpp:1092
SickScanImuMsgType::angular_velocity_covariance
double angular_velocity_covariance[9]
Definition: sick_scan_api.h:185
SickScanNavPoseLandmarkMsgType::pose_opt_output_mode
uint8_t pose_opt_output_mode
Definition: sick_scan_api.h:412
SickScanNavReflectorType::opt_startindex
uint16_t opt_startindex
Definition: sick_scan_api.h:385
SickScanVisualizationMarkerType::pose_orientation
SickScanQuaternionMsg pose_orientation
Definition: sick_scan_api.h:338
SickScanLIDoutputstateMsgType::second
uint8_t second
Definition: sick_scan_api.h:230
SickScanNavReflectorType
Definition: sick_scan_api.h:363
SickScanVisualizationMarkerBufferType::size
uint64_t size
Definition: sick_scan_api.h:354
SickScanVisualizationMarkerBufferType::buffer
SickScanVisualizationMarker * buffer
Definition: sick_scan_api.h:355
SickScanNavReflectorType::opt_valid
uint16_t opt_valid
Definition: sick_scan_api.h:374
SickScanImuMsg
struct SickScanImuMsgType SickScanImuMsg
SickScanVector3MsgType::x
double x
Definition: sick_scan_api.h:159
SickScanApiRegisterLIDoutputstateMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: api_impl.cpp:1068
SickScanRadarPreHeaderType::bcontaminationwarning
uint8_t bcontaminationwarning
Definition: sick_scan_api.h:241
SickScanVisualizationMarkerType
Definition: sick_scan_api.h:330
SickScanColorRGBAType
Definition: sick_scan_api.h:315
SickScanApiDeregisterPolarPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: api_impl.cpp:942
SickScanLdmrsObjectArrayType
Definition: sick_scan_api.h:309
SickScanNavReflectorBufferType::capacity
uint64_t capacity
Definition: sick_scan_api.h:393
SickScanApiWaitNextRadarScanMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg, double timeout_sec)
Definition: api_impl.cpp:1787
SickScanPointCloudMsgType::segment_idx
int32_t segment_idx
Definition: sick_scan_api.h:153
SickScanOdomVelocityMsgType::timestamp_nsec
uint32_t timestamp_nsec
Definition: sick_scan_api.h:437
SickScanLFErecFieldMsgType::time_state
uint16_t time_state
Definition: sick_scan_api.h:200
SickScanApiDeregisterVisualizationMarkerMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: api_impl.cpp:1242
SickScanRadarObjectArrayType::buffer
SickScanRadarObject * buffer
Definition: sick_scan_api.h:289
SickScanVector3Msg
struct SickScanVector3MsgType SickScanVector3Msg
SickScanOdomVelocityMsgType::omega
float omega
Definition: sick_scan_api.h:435
SickScanApiRegisterLFErecMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: api_impl.cpp:1018
SickScanNavPoseLandmarkMsgType::pose_timestamp_nsec
uint32_t pose_timestamp_nsec
Definition: sick_scan_api.h:406
SickScanNavPoseLandmarkMsgType::pose_opt_info_state
uint32_t pose_opt_info_state
Definition: sick_scan_api.h:416
SickScanPointCloudMsgType::width
uint32_t width
Definition: sick_scan_api.h:145
SickScanRadarObjectType::last_seen_nsec
uint32_t last_seen_nsec
Definition: sick_scan_api.h:265
SickScanColorRGBAArray
struct SickScanColorRGBAArrayType SickScanColorRGBAArray
SickScanNavOdomVelocityMsgType::vel_y
float vel_y
Definition: sick_scan_api.h:425
SICK_SCAN_POINTFIELD_DATATYPE_UINT32
@ SICK_SCAN_POINTFIELD_DATATYPE_UINT32
Definition: sick_scan_api.h:106
SickScanQuaternionMsgType::y
double y
Definition: sick_scan_api.h:167
SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32
@ SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32
Definition: sick_scan_api.h:107
SickScanLdmrsObjectArrayType::header
SickScanHeader header
Definition: sick_scan_api.h:311
SickScanNavPoseLandmarkMsgType::pose_opt_valid
uint16_t pose_opt_valid
Definition: sick_scan_api.h:410
SickScanRadarScanCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanRadarScanCallback)(SickScanApiHandle apiHandle, const SickScanRadarScan *msg)
Definition: sick_scan_api.h:461
SickScanRadarObjectArray
struct SickScanRadarObjectArrayType SickScanRadarObjectArray
SickScanLFErecFieldMsgType::second
uint8_t second
Definition: sick_scan_api.h:206
SickScanNavOdomVelocityMsgType
Definition: sick_scan_api.h:422
SICK_SCAN_POINTFIELD_DATATYPE_UINT16
@ SICK_SCAN_POINTFIELD_DATATYPE_UINT16
Definition: sick_scan_api.h:104
SickScanNavReflectorType::opt_meanecho
uint16_t opt_meanecho
Definition: sick_scan_api.h:384
SickScanRadarPreHeaderType::uinoiselevel
uint32_t uinoiselevel
Definition: sick_scan_api.h:252
SickScanPointFieldMsgType
Definition: sick_scan_api.h:111
SickScanApiCreate
SICK_SCAN_API_DECLSPEC_EXPORT SickScanApiHandle SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiCreate(int argc, char **argv)
Definition: api_impl.cpp:637
SickScanApiRegisterImuMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: api_impl.cpp:968
SickScanPointCloudMsgType::row_step
uint32_t row_step
Definition: sick_scan_api.h:149
SickScanVisualizationMarkerType::id
int32_t id
Definition: sick_scan_api.h:334
SickScanApiRelease
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRelease(SickScanApiHandle apiHandle)
Definition: api_impl.cpp:674
SickScanColorRGBAType::a
float a
Definition: sick_scan_api.h:320
SickScanRadarPreHeaderType::udisystemcountscan
uint32_t udisystemcountscan
Definition: sick_scan_api.h:246
SickScanLIDoutputstateMsgType::year
uint16_t year
Definition: sick_scan_api.h:225
SickScanColorRGBAType::g
float g
Definition: sick_scan_api.h:318
SickScanLogMsg
struct SickScanLogMsgType SickScanLogMsg
SickScanVisualizationMarkerType::header
SickScanHeader header
Definition: sick_scan_api.h:332
SickScanColorRGBAArrayType::buffer
SickScanColorRGBA * buffer
Definition: sick_scan_api.h:327
SickScanHeaderType::frame_id
char frame_id[256]
Definition: sick_scan_api.h:89
SickScanImuMsgType::header
SickScanHeader header
Definition: sick_scan_api.h:181
SickScanApiWaitNextNavPoseLandmarkMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg, double timeout_sec)
Definition: api_impl.cpp:2078
SickScanNavReflectorType::opt_global_id
uint16_t opt_global_id
Definition: sick_scan_api.h:377
SickScanLFErecMsgType
Definition: sick_scan_api.h:210
SickScanPointCloudMsg
struct SickScanPointCloudMsgType SickScanPointCloudMsg
SickScanPointFieldMsgType::datatype
uint8_t datatype
Definition: sick_scan_api.h:126
SickScanVisualizationMarkerType::colors
SickScanColorRGBAArray colors
Definition: sick_scan_api.h:345
SickScanApiDeregisterImuMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: api_impl.cpp:992
SickScanLdmrsObjectArrayType::objects
SickScanLdmrsObjectBuffer objects
Definition: sick_scan_api.h:312
SickScanLIDoutputstateMsgType::minute
uint8_t minute
Definition: sick_scan_api.h:229
SickScanLFErecFieldMsgType::field_result_mrs
uint8_t field_result_mrs
Definition: sick_scan_api.h:199
SickScanVisualizationMarkerType::mesh_use_embedded_materials
uint8_t mesh_use_embedded_materials
Definition: sick_scan_api.h:348
SickScanLIDoutputstateMsgType::header
SickScanHeader header
Definition: sick_scan_api.h:219
SickScanApiDeregisterNavPoseLandmarkMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: api_impl.cpp:2054
SickScanRadarScanType::header
SickScanHeader header
Definition: sick_scan_api.h:294
SickScanRadarObjectType::id
int32_t id
Definition: sick_scan_api.h:261
SickScanLdmrsObject
SickScanRadarObject SickScanLdmrsObject
Definition: sick_scan_api.h:300
SickScanPointCloudMsgType::is_bigendian
uint8_t is_bigendian
Definition: sick_scan_api.h:147
SickScanDiagnosticMsgType::status_message
char * status_message
Definition: sick_scan_api.h:449
SickScanRadarPreHeaderType::uioutputs
uint16_t uioutputs
Definition: sick_scan_api.h:249
SickScanVisualizationMarkerMsgType
Definition: sick_scan_api.h:358
SickScanQuaternionMsgType
Definition: sick_scan_api.h:164
SickScanRadarObjectType::bounding_box_center_orientation
SickScanQuaternionMsg bounding_box_center_orientation
Definition: sick_scan_api.h:272
SickScanVisualizationMarkerType::scale
SickScanVector3Msg scale
Definition: sick_scan_api.h:339
SickScanRadarPreHeaderType::uicycleduration
uint32_t uicycleduration
Definition: sick_scan_api.h:251
SickScanNavPoseLandmarkMsgType::pose_timestamp_sec
uint32_t pose_timestamp_sec
Definition: sick_scan_api.h:405
SickScanLIDoutputstateMsgType::output_state
uint8_t output_state[8]
Definition: sick_scan_api.h:222
SickScanLFErecMsgType::fields
SickScanLFErecFieldMsg fields[3]
Definition: sick_scan_api.h:214
SickScanLFErecFieldMsgType::sys_count
uint32_t sys_count
Definition: sick_scan_api.h:194
SickScanPointCloudMsgType::fields
SickScanPointFieldArray fields
Definition: sick_scan_api.h:146
SickScanNavOdomVelocityMsgType::omega
float omega
Definition: sick_scan_api.h:426
SickScanLogMsgType
Definition: sick_scan_api.h:440
SickScanRadarPreHeaderType::bcontaminationerror
uint8_t bcontaminationerror
Definition: sick_scan_api.h:242
SickScanNavPoseLandmarkMsgType
Definition: sick_scan_api.h:398
SickScanLdmrsObjectBufferType::size
uint64_t size
Definition: sick_scan_api.h:305
SickScanPointCloudMsgType::header
SickScanHeader header
Definition: sick_scan_api.h:143
SICK_SCAN_POINTFIELD_DATATYPE_INT16
@ SICK_SCAN_POINTFIELD_DATATYPE_INT16
Definition: sick_scan_api.h:103
SickScanRadarScanType::radarpreheader
SickScanRadarPreHeader radarpreheader
Definition: sick_scan_api.h:295
SickScanUint8ArrayType::capacity
uint64_t capacity
Definition: sick_scan_api.h:94
SickScanApiGetStatus
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t *status_code, char *message_buffer, int32_t message_buffer_size)
Definition: api_impl.cpp:1367
SickScanPointFieldArrayType::capacity
uint64_t capacity
Definition: sick_scan_api.h:132
SICK_SCAN_POINTFIELD_DATATYPE_FLOAT64
@ SICK_SCAN_POINTFIELD_DATATYPE_FLOAT64
Definition: sick_scan_api.h:108
SickScanPointFieldMsg
struct SickScanPointFieldMsgType SickScanPointFieldMsg
SickScanApiClose
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiClose(SickScanApiHandle apiHandle)
Definition: api_impl.cpp:830
SickScanLIDoutputstateMsgType::time_state
uint16_t time_state
Definition: sick_scan_api.h:224
SickScanApiRegisterPolarPointCloudMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: api_impl.cpp:918
SickScanLIDoutputstateMsgType
Definition: sick_scan_api.h:217
SickScanRadarObjectType::object_box_center_covariance
double object_box_center_covariance[36]
Definition: sick_scan_api.h:278
SickScanImuMsgType
Definition: sick_scan_api.h:179
SickScanPointCloudMsgType::num_echos
int32_t num_echos
Definition: sick_scan_api.h:152
SickScanNavReflectorType::opt_local_id
uint16_t opt_local_id
Definition: sick_scan_api.h:376
SickScanNavOdomVelocityMsgType::coordbase
uint8_t coordbase
Definition: sick_scan_api.h:428
SickScanLFErecFieldMsgType::angle_scale_factor
uint32_t angle_scale_factor
Definition: sick_scan_api.h:197
SickScanPointFieldMsgType::count
uint32_t count
Definition: sick_scan_api.h:127
SickScanNavPoseLandmarkMsgType::pose_y
float pose_y
Definition: sick_scan_api.h:403
SickScanDiagnosticMsg
struct SickScanDiagnosticMsgType SickScanDiagnosticMsg
SickScanApiFreeNavPoseLandmarkMsg
SICK_SCAN_API_DECLSPEC_EXPORT int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg)
Definition: api_impl.cpp:2117
SickScanRadarPreHeaderType::iencoderspeed
int16_t iencoderspeed[3]
Definition: sick_scan_api.h:256
SickScanLogMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLogMsgCallback)(SickScanApiHandle apiHandle, const SickScanLogMsg *msg)
Definition: sick_scan_api.h:465
SickScanPointFieldMsgType::name
char name[256]
Definition: sick_scan_api.h:124
SickScanHeaderType
Definition: sick_scan_api.h:84
SickScanPointCloudMsgType::point_step
uint32_t point_step
Definition: sick_scan_api.h:148
callback
void callback(const sick_scan_xd::RadarScan::ConstPtr &oa)
Definition: radar_object_marker.cpp:157
SickScanNavReflectorType::polar_dist
uint32_t polar_dist
Definition: sick_scan_api.h:372
SickScanRadarObjectType::object_box_center_position
SickScanVector3Msg object_box_center_position
Definition: sick_scan_api.h:276


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