sick_scan_xd_api_wrapper.c
Go to the documentation of this file.
1 #if defined _MSC_VER && _MSC_VER >= 1300
2 # pragma warning( disable : 4996 ) // suppress warning 4996 about unsafe string functions like strcpy, sprintf, etc.
3 # ifndef _CRT_SECURE_NO_DEPRECATE
4 # define _CRT_SECURE_NO_DEPRECATE // suppress warning 4996 about unsafe string functions like strcpy, sprintf, etc.
5 # endif
6 #endif
7 #ifdef WIN32
8 # include <windows.h>
9 #else
10 # include <dlfcn.h>
11 #endif
12 
13 #include <stdio.h>
14 #include <stdlib.h>
15 #include <string.h>
16 #include <ctype.h>
17 
19 
20 #ifdef WIN32
21 #else
22 typedef void* HINSTANCE;
23 static HINSTANCE LoadLibrary(const char* szLibFilename)
24 {
25  return dlopen(szLibFilename,RTLD_GLOBAL|RTLD_LAZY);
26 }
27 static int FreeLibrary ( HINSTANCE hLib )
28 {
29  return !dlclose(hLib);
30 }
31 static void* GetProcAddress(HINSTANCE hLib, const char* szFunctionName)
32 {
33  return dlsym(hLib,szFunctionName);
34 }
35 #endif
36 
38 
39 #ifdef WIN32
42 #else
45 #endif
46 
49 
52 
53 typedef int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION *SickScanApiInitByCli_PROCTYPE)(SickScanApiHandle apiHandle, int argc, char** argv);
55 
58 
61 
64 
67 
70 
73 
76 
79 
82 
85 
88 
91 
94 
97 
100 
103 
106 
109 
112 
115 
118 
119 typedef int32_t (SICK_SCAN_XD_API_CALLING_CONVENTION *SickScanApiGetStatus_PROCTYPE)(SickScanApiHandle apiHandle, int32_t* status_code, char* message_buffer, int32_t message_buffer_size);
121 
122 typedef int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION *SickScanApiSendSOPAS_PROCTYPE)(SickScanApiHandle apiHandle, const char* sopas_command, char* sopas_response_buffer, int32_t response_buffer_size);
124 
127 
130 
133 
136 
139 
142 
145 
148 
151 
154 
157 
160 
163 
166 
169 
172 
175 
178 
181 
184 
187 
190 
193 
194 /*
195 * Functions and macros to initialize and close the API and a lidar
196 */
197 
198 // load a function by its name using GetProcAddress if not done before (i.e. if ptFunction is 0)
199 #define CACHE_FUNCTION_PTR(apiHandle, ptFunction, szFunctionName, procType) \
200 do \
201 { \
202  if (hinstLib == 0 || apiHandle == 0) \
203  { \
204  printf("## ERROR SickScanApi, cacheFunctionPtr(%s): library not initialized\n", szFunctionName); \
205  ptFunction = 0; \
206  } \
207  else if (ptFunction == 0) \
208  { \
209  ptFunction = (procType)GetProcAddress(hinstLib, szFunctionName); \
210  } \
211  if (ptFunction == 0) \
212  { \
213  printf("## ERROR SickScanApi, cacheFunctionPtr(%s): GetProcAddress failed\n", szFunctionName); \
214  } \
215 } while(0)
216 
217 // Load sick_scan_xd api library (dll or so file)
218 int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiLoadLibrary(const char* library_filepath)
219 {
220  int32_t ret = SICK_SCAN_API_SUCCESS;
221  if (hinstLib == NULL)
222  {
223  hinstLib = LoadLibrary(library_filepath);
224  }
225  if (hinstLib == NULL)
226  {
227  printf("## WARNING SickScanApiLoadLibrary: LoadLibrary(\"%s\") failed\n", library_filepath);
229  }
230  return ret;
231 }
232 
233 // Unload sick_scan_xd api library
235 {
236  int32_t ret = SICK_SCAN_API_SUCCESS;
237  if (hinstLib != 0)
238  {
239  if (!FreeLibrary(hinstLib))
240  {
241  printf("## ERROR SickScanApiUnloadLibrary: FreeLibrary() failed\n");
242  ret = SICK_SCAN_API_ERROR;
243  }
244  }
245  hinstLib = 0;
250  ptSickScanApiClose = 0;
296  return ret;
297 }
298 
299 /*
300 * Create an instance of sick_scan_xd api.
301 * Optional commandline arguments argc, argv identical to sick_generic_caller.
302 * Call SickScanApiInitByLaunchfile or SickScanApiInitByCli to process a lidar.
303 */
305 {
306  if (hinstLib == 0)
307  {
308  printf("## ERROR SickScanApiCreate: library not loaded\n");
309  return 0;
310  }
311  if (ptSickScanApiCreate == 0)
312  {
314  }
315  if (ptSickScanApiCreate == 0)
316  {
317  printf("## ERROR SickScanApiCreate: GetProcAddress failed\n");
318  return 0;
319  }
320  SickScanApiHandle apiHandle = ptSickScanApiCreate(argc, argv);
321  if (apiHandle == 0)
322  {
323  printf("## ERROR SickScanApiCreate: library call SickScanApiCreate() returned 0\n");
324  }
325  return apiHandle;
326 }
327 
328 // Release and free all resources of a handle; the handle is invalid after SickScanApiRelease
330 {
331  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiRelease, "SickScanApiRelease", SickScanApiRelease_PROCTYPE);
333  if (ret != SICK_SCAN_API_SUCCESS)
334  printf("## ERROR SickScanApiRelease: library call SickScanApiRelease() failed, error code %d\n", ret);
335  return ret;
336 }
337 
338 // Initializes a lidar by launchfile and starts message receiving and processing
340 {
342  int32_t ret = (ptSickScanApiInitByLaunchfile ? (ptSickScanApiInitByLaunchfile(apiHandle, launchfile_args)) : SICK_SCAN_API_NOT_INITIALIZED);
343  if (ret != SICK_SCAN_API_SUCCESS)
344  printf("## ERROR SickScanApiInitByLaunchfile: library call SickScanApiInitByLaunchfile() failed, error code %d\n", ret);
345  return ret;
346 }
347 
348 // Initializes a lidar by commandline arguments and starts message receiving and processing
350 {
351  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiInitByCli, "SickScanApiInitByCli", SickScanApiInitByCli_PROCTYPE);
352  int32_t ret = (ptSickScanApiInitByCli ? (ptSickScanApiInitByCli(apiHandle, argc, argv)) : SICK_SCAN_API_NOT_INITIALIZED);
353  if (ret != SICK_SCAN_API_SUCCESS)
354  printf("## ERROR SickScanApiInitByCli: library call SickScanApiInitByCli() failed, error code %d\n", ret);
355  return ret;
356 }
357 
358 // Stops message receiving and processing and closes a lidar
360 {
361  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiClose, "SickScanApiClose", SickScanApiClose_PROCTYPE);
363  if (ret != SICK_SCAN_API_SUCCESS)
364  printf("## ERROR SickScanApiClose: library call SickScanApiClose() failed, error code %d\n", ret);
365  return ret;
366 }
367 
368 /*
369 * Registration / deregistration of message callbacks
370 */
371 
372 // Register / deregister a callback for cartesian PointCloud messages, pointcloud in cartesian coordinates with fields x, y, z, intensity
374 {
377  if (ret != SICK_SCAN_API_SUCCESS)
378  printf("## ERROR SickScanApiRegisterCartesianPointCloudMsg: library call SickScanApiRegisterCartesianPointCloudMsg() failed, error code %d\n", ret);
379  return ret;
380 }
382 {
385  if (ret != SICK_SCAN_API_SUCCESS)
386  printf("## ERROR SickScanApiDeregisterCartesianPointCloudMsg: library call SickScanApiDeregisterCartesianPointCloudMsg() failed, error code %d\n", ret);
387  return ret;
388 }
389 
390 // Register / deregister a callback for polar PointCloud messages, pointcloud in polar coordinates with fields range, azimuth, elevation, intensity
392 {
395  if (ret != SICK_SCAN_API_SUCCESS)
396  printf("## ERROR SickScanApiRegisterPolarPointCloudMsg: library call SickScanApiRegisterPolarPointCloudMsg() failed, error code %d\n", ret);
397  return ret;
398 }
400 {
403  if (ret != SICK_SCAN_API_SUCCESS)
404  printf("## ERROR SickScanApiDeregisterPolarPointCloudMsg: library call SickScanApiDeregisterPolarPointCloudMsg() failed, error code %d\n", ret);
405  return ret;
406 }
407 
408 // Register / deregister a callback for Imu messages
410 {
413  if (ret != SICK_SCAN_API_SUCCESS)
414  printf("## ERROR SickScanApiRegisterImuMsg: library call SickScanApiRegisterImuMsg() failed, error code %d\n", ret);
415  return ret;
416 }
418 {
421  if (ret != SICK_SCAN_API_SUCCESS)
422  printf("## ERROR SickScanApiDeregisterImuMsg: library call SickScanApiDeregisterImuMsg() failed, error code %d\n", ret);
423  return ret;
424 }
425 
426 // Register / deregister a callback for SickScanLFErecMsg messages
428 {
431  if (ret != SICK_SCAN_API_SUCCESS)
432  printf("## ERROR SickScanApiRegisterLFErecMsg: library call SickScanApiRegisterLFErecMsg() failed, error code %d\n", ret);
433  return ret;
434 }
436 {
439  if (ret != SICK_SCAN_API_SUCCESS)
440  printf("## ERROR SickScanApiDeregisterLFErecMsg: library call SickScanApiDeregisterLFErecMsg() failed, error code %d\n", ret);
441  return ret;
442 }
443 
444 // Register / deregister a callback for SickScanLIDoutputstateMsg messages
446 {
449  if (ret != SICK_SCAN_API_SUCCESS)
450  printf("## ERROR SickScanApiRegisterLIDoutputstateMsg: library call SickScanApiRegisterLIDoutputstateMsg() failed, error code %d\n", ret);
451  return ret;
452 }
454 {
457  if (ret != SICK_SCAN_API_SUCCESS)
458  printf("## ERROR SickScanApiDeregisterLIDoutputstateMsg: library call SickScanApiDeregisterLIDoutputstateMsg() failed, error code %d\n", ret);
459  return ret;
460 }
461 
462 // Register / deregister a callback for SickScanRadarScan messages
464 {
467  if (ret != SICK_SCAN_API_SUCCESS)
468  printf("## ERROR SickScanApiRegisterRadarScanMsg: library call SickScanApiRegisterRadarScanMsg() failed, error code %d\n", ret);
469  return ret;
470 }
472 {
475  if (ret != SICK_SCAN_API_SUCCESS)
476  printf("## ERROR SickScanApiDeregisterRadarScanMsg: library call SickScanApiDeregisterRadarScanMsg() failed, error code %d\n", ret);
477  return ret;
478 }
479 
480 // Register / deregister a callback for SickScanLdmrsObjectArray messages
482 {
485  if (ret != SICK_SCAN_API_SUCCESS)
486  printf("## ERROR SickScanApiRegisterLdmrsObjectArrayMsg: library call SickScanApiRegisterLdmrsObjectArrayMsg() failed, error code %d\n", ret);
487  return ret;
488 }
490 {
493  if (ret != SICK_SCAN_API_SUCCESS)
494  printf("## ERROR SickScanApiDeregisterLdmrsObjectArrayMsg: library call SickScanApiDeregisterLdmrsObjectArrayMsg() failed, error code %d\n", ret);
495  return ret;
496 }
497 
498 // Register / deregister a callback for VisualizationMarker messages
500 {
503  if (ret != SICK_SCAN_API_SUCCESS)
504  printf("## ERROR SickScanApiRegisterVisualizationMarkerMsg: library call SickScanApiRegisterVisualizationMarkerMsg() failed, error code %d\n", ret);
505  return ret;
506 }
508 {
511  if (ret != SICK_SCAN_API_SUCCESS)
512  printf("## ERROR SickScanApiDeregisterVisualizationMarkerMsg: library call SickScanApiDeregisterVisualizationMarkerMsg() failed, error code %d\n", ret);
513  return ret;
514 }
515 
516 /*
517 * Functions for diagnostic and logging
518 */
519 
520 // Register / deregister a callback for diagnostic messages (notification in case of changed status, e.g. after errors)
522 {
525  if (ret != SICK_SCAN_API_SUCCESS)
526  printf("## ERROR SickScanApiRegisterDiagnosticMsg: library call SickScanApiRegisterDiagnosticMsg() failed, error code %d\n", ret);
527  return ret;
528 }
530 {
533  if (ret != SICK_SCAN_API_SUCCESS)
534  printf("## ERROR SickScanApiDeregisterDiagnosticMsg: library call SickScanApiDeregisterDiagnosticMsg() failed, error code %d\n", ret);
535  return ret;
536 }
537 
538 // Register / deregister a callback for log messages (all informational and error messages)
540 {
543  if (ret != SICK_SCAN_API_SUCCESS)
544  printf("## ERROR SickScanApiRegisterLogMsg: library call SickScanApiRegisterLogMsg() failed, error code %d\n", ret);
545  return ret;
546 }
548 {
551  if (ret != SICK_SCAN_API_SUCCESS)
552  printf("## ERROR SickScanApiDeregisterLogMsg: library call SickScanApiDeregisterLogMsg() failed, error code %d\n", ret);
553  return ret;
554 }
555 
556 // Query current status and status message
557 int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t* status_code, char* message_buffer, int32_t message_buffer_size)
558 {
559  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiGetStatus, "SickScanApiGetStatus", SickScanApiGetStatus_PROCTYPE);
560  int32_t ret = (ptSickScanApiGetStatus ? (ptSickScanApiGetStatus(apiHandle, status_code, message_buffer, message_buffer_size)) : SICK_SCAN_API_NOT_INITIALIZED);
561  if (ret != SICK_SCAN_API_SUCCESS)
562  printf("## ERROR SickScanApiGetStatus: library call SickScanApiGetStatus() failed, error code %d\n", ret);
563  return ret;
564 }
565 
566 // Sends a SOPAS command like "sRN SCdevicestate" or "sRN ContaminationResult" and returns the lidar response
567 int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSendSOPAS(SickScanApiHandle apiHandle, const char* sopas_command, char* sopas_response_buffer, int32_t response_buffer_size)
568 {
569  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiSendSOPAS, "SickScanApiSendSOPAS", SickScanApiSendSOPAS_PROCTYPE);
570  int32_t ret = (ptSickScanApiSendSOPAS ? (ptSickScanApiSendSOPAS(apiHandle, sopas_command, sopas_response_buffer, response_buffer_size)) : SICK_SCAN_API_NOT_INITIALIZED);
571  if (ret != SICK_SCAN_API_SUCCESS)
572  printf("## ERROR SickScanApiSendSOPAS: library call SickScanApiSendSOPAS() failed, error code %d\n", ret);
573  return ret;
574 }
575 
576 // Set verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET (equivalent to ros::console::levels),
577 // i.e. print messages on console above the given verbose level.
578 // Default verbose level is 1 (INFO), i.e. print informational, warnings and error messages.
580 {
583  if (ret != SICK_SCAN_API_SUCCESS)
584  printf("## ERROR SickScanApiSetVerboseLevel: library call SickScanApiSetVerboseLevel() failed, error code %d\n", ret);
585  return ret;
586 }
587 
588 // Returns the current verbose level 0=DEBUG, 1=INFO, 2=WARN, 3=ERROR, 4=FATAL or 5=QUIET. Default verbose level is 1 (INFO)
590 {
593  return verbose_level;
594 }
595 
596 /*
597 * Polling functions
598 */
599 
600 // Wait for and return the next cartesian resp. polar PointCloud messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
602 {
605  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
606  printf("## ERROR SickScanApiWaitNextCartesianPointCloudMsg: library call SickScanApiWaitNextCartesianPointCloudMsg() failed, error code %d\n", ret);
607  return ret;
608 }
610 {
613  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
614  printf("## ERROR SickScanApiWaitNextPolarPointCloudMsg: library call SickScanApiWaitNextPolarPointCloudMsg() failed, error code %d\n", ret);
615  return ret;
616 }
618 {
621  if (ret != SICK_SCAN_API_SUCCESS)
622  printf("## ERROR SickScanApiFreePointCloudMsg: library call SickScanApiFreePointCloudMsg() failed, error code %d\n", ret);
623  return ret;
624 }
625 
626 // Wait for and return the next Imu messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
628 {
630  int32_t ret = (ptSickScanApiWaitNextImuMsg ? (ptSickScanApiWaitNextImuMsg(apiHandle, msg, timeout_sec)) : SICK_SCAN_API_NOT_INITIALIZED);
631  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
632  printf("## ERROR SickScanApiWaitNextImuMsg: library call SickScanApiWaitNextImuMsg() failed, error code %d\n", ret);
633  return ret;
634 }
636 {
637  CACHE_FUNCTION_PTR(apiHandle, ptSickScanApiFreeImuMsg, "SickScanApiFreeImuMsg", SickScanApiFreeImuMsg_PROCTYPE);
639  if (ret != SICK_SCAN_API_SUCCESS)
640  printf("## ERROR SickScanApiFreeImuMsg: library call SickScanApiFreeImuMsg() failed, error code %d\n", ret);
641  return ret;
642 }
643 
644 // Wait for and return the next LFErec messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
646 {
649  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
650  printf("## ERROR SickScanApiWaitNextLFErecMsg: library call SickScanApiWaitNextLFErecMsg() failed, error code %d\n", ret);
651  return ret;
652 }
654 {
657  if (ret != SICK_SCAN_API_SUCCESS)
658  printf("## ERROR SickScanApiFreeLFErecMsg: library call SickScanApiFreeLFErecMsg() failed, error code %d\n", ret);
659  return ret;
660 }
661 
662 // Wait for and return the next LIDoutputstate messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
664 {
667  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
668  printf("## ERROR SickScanApiWaitNextLIDoutputstateMsg: library call SickScanApiWaitNextLIDoutputstateMsg() failed, error code %d\n", ret);
669  return ret;
670 }
672 {
675  if (ret != SICK_SCAN_API_SUCCESS)
676  printf("## ERROR SickScanApiFreeLIDoutputstateMsg: library call SickScanApiFreeLIDoutputstateMsg() failed, error code %d\n", ret);
677  return ret;
678 }
679 
680 // Wait for and return the next RadarScan messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
682 {
685  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
686  printf("## ERROR SickScanApiWaitNextRadarScanMsg: library call SickScanApiWaitNextRadarScanMsg() failed, error code %d\n", ret);
687  return ret;
688 }
690 {
693  if (ret != SICK_SCAN_API_SUCCESS)
694  printf("## ERROR SickScanApiFreeRadarScanMsg: library call SickScanApiFreeRadarScanMsg() failed, error code %d\n", ret);
695  return ret;
696 }
697 
698 // Wait for and return the next LdmrsObjectArray messages. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
700 {
703  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
704  printf("## ERROR SickScanApiWaitNextLdmrsObjectArrayMsg: library call SickScanApiWaitNextLdmrsObjectArrayMsg() failed, error code %d\n", ret);
705  return ret;
706 }
708 {
711  if (ret != SICK_SCAN_API_SUCCESS)
712  printf("## ERROR SickScanApiFreeLdmrsObjectArrayMsg: library call SickScanApiFreeLdmrsObjectArrayMsg() failed, error code %d\n", ret);
713  return ret;
714 }
715 
716 // Wait for and return the next VisualizationMarker message. Note: SickScanApiWait...Msg() allocates a message. Use function SickScanApiFree...Msg() to deallocate it after use.
718 {
721  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
722  printf("## ERROR SickScanApiWaitNextVisualizationMarkerMsg: library call SickScanApiWaitNextVisualizationMarkerMsg() failed, error code %d\n", ret);
723  return ret;
724 }
726 {
729  if (ret != SICK_SCAN_API_SUCCESS)
730  printf("## ERROR SickScanApiFreeVisualizationMarkerMsg: library call SickScanApiFreeVisualizationMarkerMsg() failed, error code %d\n", ret);
731  return ret;
732 }
733 
734 /*
735 * NAV350 support
736 */
737 
739 {
742  if (ret != SICK_SCAN_API_SUCCESS)
743  printf("## ERROR SickScanApiRegisterNavPoseLandmarkMsg: library call SickScanApiRegisterNavPoseLandmarkMsg() failed, error code %d\n", ret);
744  return ret;
745 }
747 {
750  if (ret != SICK_SCAN_API_SUCCESS)
751  printf("## ERROR SickScanApiDeregisterNavPoseLandmarkMsg: library call SickScanApiDeregisterNavPoseLandmarkMsg() failed, error code %d\n", ret);
752  return ret;
753 }
755 {
758  if (ret != SICK_SCAN_API_SUCCESS && ret != SICK_SCAN_API_TIMEOUT)
759  printf("## ERROR SickScanApiWaitNextNavPoseLandmarkMsg: library call SickScanApiWaitNextNavPoseLandmarkMsg() failed, error code %d\n", ret);
760  return ret;
761 }
763 {
766  if (ret != SICK_SCAN_API_SUCCESS)
767  printf("## ERROR SickScanApiFreeNavPoseLandmarkMsg: library call SickScanApiFreeNavPoseLandmarkMsg() failed, error code %d\n", ret);
768  return ret;
769 }
771 {
774  if (ret != SICK_SCAN_API_SUCCESS)
775  printf("## ERROR SickScanApiNavOdomVelocityMsg: library call SickScanApiNavOdomVelocityMsg() failed, error code %d\n", ret);
776  return ret;
777 }
779 {
782  if (ret != SICK_SCAN_API_SUCCESS)
783  printf("## ERROR SickScanApiOdomVelocityMsg: library call SickScanApiOdomVelocityMsg() failed, error code %d\n", ret);
784  return ret;
785 }
SickScanApiDeregisterDiagnosticMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterDiagnosticMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:110
SickScanApiRegisterImuMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:71
SickScanApiFreeNavPoseLandmarkMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:185
SickScanApiInitByLaunchfile
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByLaunchfile(SickScanApiHandle apiHandle, const char *launchfile_args)
Definition: sick_scan_xd_api_wrapper.c:339
SickScanApiFreeRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg)
Definition: sick_scan_xd_api_wrapper.c:689
ptSickScanApiSendSOPAS
static SickScanApiSendSOPAS_PROCTYPE ptSickScanApiSendSOPAS
Definition: sick_scan_xd_api_wrapper.c:123
HINSTANCE
void * HINSTANCE
Definition: sick_scan_xd_api_wrapper.c:22
ptSickScanApiClose
static SickScanApiClose_PROCTYPE ptSickScanApiClose
Definition: sick_scan_xd_api_wrapper.c:57
SickScanOdomVelocityMsgType
Definition: sick_scan_api.h:431
ptSickScanApiDeregisterLIDoutputstateMsg
static SickScanApiDeregisterLIDoutputstateMsg_PROCTYPE ptSickScanApiDeregisterLIDoutputstateMsg
Definition: sick_scan_xd_api_wrapper.c:87
LoadLibrary
static HINSTANCE LoadLibrary(const char *szLibFilename)
Definition: sick_scan_xd_api_wrapper.c:23
SickScanApiSendSOPAS
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: sick_scan_xd_api_wrapper.c:567
SickScanApiDeregisterLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:435
ptSickScanApiWaitNextLFErecMsg
static SickScanApiWaitNextLFErecMsg_PROCTYPE ptSickScanApiWaitNextLFErecMsg
Definition: sick_scan_xd_api_wrapper.c:147
ptSickScanApiRegisterLdmrsObjectArrayMsg
static SickScanApiRegisterLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiRegisterLdmrsObjectArrayMsg
Definition: sick_scan_xd_api_wrapper.c:96
SICK_SCAN_API_SUCCESS
@ SICK_SCAN_API_SUCCESS
Definition: sick_scan_api.h:609
SickScanApiFreeLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg)
Definition: sick_scan_xd_api_wrapper.c:707
msg
msg
SickScanApiWaitNextLdmrsObjectArrayMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:164
NULL
#define NULL
SickScanApiDeregisterLogMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLogMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:116
SickScanApiNavOdomVelocityMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiNavOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:770
SickScanApiDeregisterImuMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:417
ptSickScanApiDeregisterLFErecMsg
static SickScanApiDeregisterLFErecMsg_PROCTYPE ptSickScanApiDeregisterLFErecMsg
Definition: sick_scan_xd_api_wrapper.c:81
SickScanApiDeregisterLFErecMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:80
SickScanApiGetVerboseLevel
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetVerboseLevel(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:589
SickScanApiWaitNextImuMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:627
SickScanApiWaitNextPolarPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:609
SickScanApiSetVerboseLevel_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiSetVerboseLevel_PROCTYPE)(SickScanApiHandle apiHandle, int32_t verbose_level)
Definition: sick_scan_xd_api_wrapper.c:125
SickScanApiSetVerboseLevel
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSetVerboseLevel(SickScanApiHandle apiHandle, int32_t verbose_level)
Definition: sick_scan_xd_api_wrapper.c:579
SickScanApiOdomVelocityMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:778
SickScanApiClose_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiClose_PROCTYPE)(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:56
SickScanPointCloudMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanPointCloudMsgCallback)(SickScanApiHandle apiHandle, const SickScanPointCloudMsg *msg)
Definition: sick_scan_api.h:457
SickScanApiWaitNextNavPoseLandmarkMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:754
ptSickScanApiDeregisterVisualizationMarkerMsg
static SickScanApiDeregisterVisualizationMarkerMsg_PROCTYPE ptSickScanApiDeregisterVisualizationMarkerMsg
Definition: sick_scan_xd_api_wrapper.c:105
ptSickScanApiFreeRadarScanMsg
static SickScanApiFreeRadarScanMsg_PROCTYPE ptSickScanApiFreeRadarScanMsg
Definition: sick_scan_xd_api_wrapper.c:162
SickScanApiFreeLFErecMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:149
ptSickScanApiRegisterVisualizationMarkerMsg
static SickScanApiRegisterVisualizationMarkerMsg_PROCTYPE ptSickScanApiRegisterVisualizationMarkerMsg
Definition: sick_scan_xd_api_wrapper.c:102
SickScanApiRegisterCartesianPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:59
SickScanLdmrsObjectArrayCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLdmrsObjectArrayCallback)(SickScanApiHandle apiHandle, const SickScanLdmrsObjectArray *msg)
Definition: sick_scan_api.h:462
SickScanApiRegisterRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: sick_scan_xd_api_wrapper.c:463
SickScanApiGetStatus_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiGetStatus_PROCTYPE)(SickScanApiHandle apiHandle, int32_t *status_code, char *message_buffer, int32_t message_buffer_size)
Definition: sick_scan_xd_api_wrapper.c:119
SickScanApiWaitNextLIDoutputstateMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:663
ptSickScanApiFreeImuMsg
static SickScanApiFreeImuMsg_PROCTYPE ptSickScanApiFreeImuMsg
Definition: sick_scan_xd_api_wrapper.c:144
SickScanApiFreeImuMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:143
SickScanApiRegisterLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:427
SickScanApiDeregisterImuMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:74
SickScanApiDeregisterPolarPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:68
ptSickScanApiWaitNextRadarScanMsg
static SickScanApiWaitNextRadarScanMsg_PROCTYPE ptSickScanApiWaitNextRadarScanMsg
Definition: sick_scan_xd_api_wrapper.c:159
SickScanApiDeregisterLIDoutputstateMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:453
ptSickScanApiWaitNextLIDoutputstateMsg
static SickScanApiWaitNextLIDoutputstateMsg_PROCTYPE ptSickScanApiWaitNextLIDoutputstateMsg
Definition: sick_scan_xd_api_wrapper.c:153
ptSickScanApiOdomVelocityMsg
static SickScanApiOdomVelocityMsg_PROCTYPE ptSickScanApiOdomVelocityMsg
Definition: sick_scan_xd_api_wrapper.c:192
SickScanApiInitByCli_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiInitByCli_PROCTYPE)(SickScanApiHandle apiHandle, int argc, char **argv)
Definition: sick_scan_xd_api_wrapper.c:53
ptSickScanApiRegisterDiagnosticMsg
static SickScanApiRegisterDiagnosticMsg_PROCTYPE ptSickScanApiRegisterDiagnosticMsg
Definition: sick_scan_xd_api_wrapper.c:108
SickScanApiRelease_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRelease_PROCTYPE)(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:47
SickScanApiWaitNextImuMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:140
SickScanApiLoadLibrary
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiLoadLibrary(const char *library_filepath)
Definition: sick_scan_xd_api_wrapper.c:218
SickScanLFErecMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLFErecMsgCallback)(SickScanApiHandle apiHandle, const SickScanLFErecMsg *msg)
Definition: sick_scan_api.h:459
SickScanApiWaitNextRadarScanMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScan *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:158
SickScanApiDeregisterVisualizationMarkerMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: sick_scan_xd_api_wrapper.c:104
SickScanApiWaitNextLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:699
SickScanApiDeregisterPolarPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:399
ptSickScanApiGetVerboseLevel
static SickScanApiGetVerboseLevel_PROCTYPE ptSickScanApiGetVerboseLevel
Definition: sick_scan_xd_api_wrapper.c:129
SickScanApiRegisterNavPoseLandmarkMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: sick_scan_xd_api_wrapper.c:738
ptSickScanApiWaitNextImuMsg
static SickScanApiWaitNextImuMsg_PROCTYPE ptSickScanApiWaitNextImuMsg
Definition: sick_scan_xd_api_wrapper.c:141
SickScanApiDeregisterLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: sick_scan_xd_api_wrapper.c:489
SickScanApiFreeVisualizationMarkerMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:173
SickScanNavPoseLandmarkCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanNavPoseLandmarkCallback)(SickScanApiHandle apiHandle, const SickScanNavPoseLandmarkMsg *msg)
Definition: sick_scan_api.h:464
ptSickScanApiDeregisterLogMsg
static SickScanApiDeregisterLogMsg_PROCTYPE ptSickScanApiDeregisterLogMsg
Definition: sick_scan_xd_api_wrapper.c:117
SickScanImuMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanImuMsgCallback)(SickScanApiHandle apiHandle, const SickScanImuMsg *msg)
Definition: sick_scan_api.h:458
CACHE_FUNCTION_PTR
#define CACHE_FUNCTION_PTR(apiHandle, ptFunction, szFunctionName, procType)
Definition: sick_scan_xd_api_wrapper.c:199
SICK_SCAN_XD_API_CALLING_CONVENTION
#define SICK_SCAN_XD_API_CALLING_CONVENTION
Definition: sick_scan_api.h:77
SickScanApiFreeLdmrsObjectArrayMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg)
Definition: sick_scan_xd_api_wrapper.c:167
SickScanApiRegisterImuMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:409
SickScanApiDeregisterCartesianPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:62
ptSickScanApiFreeLIDoutputstateMsg
static SickScanApiFreeLIDoutputstateMsg_PROCTYPE ptSickScanApiFreeLIDoutputstateMsg
Definition: sick_scan_xd_api_wrapper.c:156
ptSickScanApiDeregisterRadarScanMsg
static SickScanApiDeregisterRadarScanMsg_PROCTYPE ptSickScanApiDeregisterRadarScanMsg
Definition: sick_scan_xd_api_wrapper.c:93
SICK_SCAN_API_TIMEOUT
@ SICK_SCAN_API_TIMEOUT
Definition: sick_scan_api.h:614
SickScanApiFreeVisualizationMarkerMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:725
ptSickScanApiDeregisterNavPoseLandmarkMsg
static SickScanApiDeregisterNavPoseLandmarkMsg_PROCTYPE ptSickScanApiDeregisterNavPoseLandmarkMsg
Definition: sick_scan_xd_api_wrapper.c:180
SickScanDiagnosticMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanDiagnosticMsgCallback)(SickScanApiHandle apiHandle, const SickScanDiagnosticMsg *msg)
Definition: sick_scan_api.h:466
ptSickScanApiDeregisterDiagnosticMsg
static SickScanApiDeregisterDiagnosticMsg_PROCTYPE ptSickScanApiDeregisterDiagnosticMsg
Definition: sick_scan_xd_api_wrapper.c:111
SickScanApiDeregisterCartesianPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:381
SickScanApiWaitNextRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:681
SickScanApiFreeNavPoseLandmarkMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:762
SickScanRadarScanType
Definition: sick_scan_api.h:292
SickScanApiCreate
SickScanApiHandle SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiCreate(int argc, char **argv)
Definition: sick_scan_xd_api_wrapper.c:304
sick_scan_api.h
ptSickScanApiRegisterLIDoutputstateMsg
static SickScanApiRegisterLIDoutputstateMsg_PROCTYPE ptSickScanApiRegisterLIDoutputstateMsg
Definition: sick_scan_xd_api_wrapper.c:84
SICK_SCAN_API_ERROR
@ SICK_SCAN_API_ERROR
Definition: sick_scan_api.h:610
SickScanApiWaitNextVisualizationMarkerMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:170
ptSickScanApiInitByCli
static SickScanApiInitByCli_PROCTYPE ptSickScanApiInitByCli
Definition: sick_scan_xd_api_wrapper.c:54
SickScanApiFreeLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:653
ptSickScanApiWaitNextVisualizationMarkerMsg
static SickScanApiWaitNextVisualizationMarkerMsg_PROCTYPE ptSickScanApiWaitNextVisualizationMarkerMsg
Definition: sick_scan_xd_api_wrapper.c:171
SickScanApiWaitNextCartesianPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:131
SickScanPointCloudMsgType
Definition: sick_scan_api.h:137
ptSickScanApiWaitNextNavPoseLandmarkMsg
static SickScanApiWaitNextNavPoseLandmarkMsg_PROCTYPE ptSickScanApiWaitNextNavPoseLandmarkMsg
Definition: sick_scan_xd_api_wrapper.c:183
ptSickScanApiWaitNextCartesianPointCloudMsg
static SickScanApiWaitNextCartesianPointCloudMsg_PROCTYPE ptSickScanApiWaitNextCartesianPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:132
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
SickScanApiRegisterDiagnosticMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterDiagnosticMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:107
ptSickScanApiRegisterNavPoseLandmarkMsg
static SickScanApiRegisterNavPoseLandmarkMsg_PROCTYPE ptSickScanApiRegisterNavPoseLandmarkMsg
Definition: sick_scan_xd_api_wrapper.c:177
ptSickScanApiRegisterLFErecMsg
static SickScanApiRegisterLFErecMsg_PROCTYPE ptSickScanApiRegisterLFErecMsg
Definition: sick_scan_xd_api_wrapper.c:78
SickScanApiRegisterVisualizationMarkerMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: sick_scan_xd_api_wrapper.c:499
SickScanVisualizationMarkerCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanVisualizationMarkerCallback)(SickScanApiHandle apiHandle, const SickScanVisualizationMarkerMsg *msg)
Definition: sick_scan_api.h:463
SickScanApiRegisterRadarScanMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: sick_scan_xd_api_wrapper.c:89
ptSickScanApiInitByLaunchfile
static SickScanApiInitByLaunchfile_PROCTYPE ptSickScanApiInitByLaunchfile
Definition: sick_scan_xd_api_wrapper.c:51
SickScanApiHandle
void * SickScanApiHandle
Definition: sick_scan_api.h:456
SickScanApiWaitNextLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:645
SickScanApiInitByCli
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByCli(SickScanApiHandle apiHandle, int argc, char **argv)
Definition: sick_scan_xd_api_wrapper.c:349
SickScanApiOdomVelocityMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiOdomVelocityMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:191
SICK_SCAN_API_NOT_INITIALIZED
@ SICK_SCAN_API_NOT_INITIALIZED
Definition: sick_scan_api.h:612
SickScanApiWaitNextLFErecMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:146
SickScanApiGetVerboseLevel_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiGetVerboseLevel_PROCTYPE)(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:128
SickScanApiDeregisterRadarScanMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: sick_scan_xd_api_wrapper.c:92
SickScanApiSendSOPAS_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiSendSOPAS_PROCTYPE)(SickScanApiHandle apiHandle, const char *sopas_command, char *sopas_response_buffer, int32_t response_buffer_size)
Definition: sick_scan_xd_api_wrapper.c:122
ptSickScanApiDeregisterImuMsg
static SickScanApiDeregisterImuMsg_PROCTYPE ptSickScanApiDeregisterImuMsg
Definition: sick_scan_xd_api_wrapper.c:75
ptSickScanApiDeregisterCartesianPointCloudMsg
static SickScanApiDeregisterCartesianPointCloudMsg_PROCTYPE ptSickScanApiDeregisterCartesianPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:63
ptSickScanApiRegisterImuMsg
static SickScanApiRegisterImuMsg_PROCTYPE ptSickScanApiRegisterImuMsg
Definition: sick_scan_xd_api_wrapper.c:72
sick_scan_xd_api_test.verbose_level
verbose_level
Definition: sick_scan_xd_api_test.py:346
SickScanApiInitByLaunchfile_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiInitByLaunchfile_PROCTYPE)(SickScanApiHandle apiHandle, const char *launchfile)
Definition: sick_scan_xd_api_wrapper.c:50
SickScanApiRegisterLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: sick_scan_xd_api_wrapper.c:481
ptSickScanApiDeregisterPolarPointCloudMsg
static SickScanApiDeregisterPolarPointCloudMsg_PROCTYPE ptSickScanApiDeregisterPolarPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:69
SickScanApiDeregisterNavPoseLandmarkMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: sick_scan_xd_api_wrapper.c:746
SickScanApiWaitNextPolarPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:134
SickScanApiFreePointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreePointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:617
SickScanApiRegisterNavPoseLandmarkMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: sick_scan_xd_api_wrapper.c:176
ptSickScanApiFreeNavPoseLandmarkMsg
static SickScanApiFreeNavPoseLandmarkMsg_PROCTYPE ptSickScanApiFreeNavPoseLandmarkMsg
Definition: sick_scan_xd_api_wrapper.c:186
SickScanApiCreate_PROCTYPE
SickScanApiHandle(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiCreate_PROCTYPE)(int argc, char **argv)
Definition: sick_scan_xd_api_wrapper.c:43
ptSickScanApiFreeLdmrsObjectArrayMsg
static SickScanApiFreeLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiFreeLdmrsObjectArrayMsg
Definition: sick_scan_xd_api_wrapper.c:168
SickScanLdmrsObjectArrayType
Definition: sick_scan_api.h:309
SickScanApiClose
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiClose(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:359
SickScanApiRelease
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRelease(SickScanApiHandle apiHandle)
Definition: sick_scan_xd_api_wrapper.c:329
ptSickScanApiFreePointCloudMsg
static SickScanApiFreePointCloudMsg_PROCTYPE ptSickScanApiFreePointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:138
ptSickScanApiRegisterPolarPointCloudMsg
static SickScanApiRegisterPolarPointCloudMsg_PROCTYPE ptSickScanApiRegisterPolarPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:66
SickScanApiWaitNextCartesianPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:601
SickScanApiRegisterLdmrsObjectArrayMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: sick_scan_xd_api_wrapper.c:95
SickScanApiRegisterLIDoutputstateMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:445
FreeLibrary
static int FreeLibrary(HINSTANCE hLib)
Definition: sick_scan_xd_api_wrapper.c:27
SickScanApiFreeImuMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:635
SickScanRadarScanCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanRadarScanCallback)(SickScanApiHandle apiHandle, const SickScanRadarScan *msg)
Definition: sick_scan_api.h:461
ptSickScanApiRegisterLogMsg
static SickScanApiRegisterLogMsg_PROCTYPE ptSickScanApiRegisterLogMsg
Definition: sick_scan_xd_api_wrapper.c:114
SickScanNavOdomVelocityMsgType
Definition: sick_scan_api.h:422
SickScanApiFreeLIDoutputstateMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:155
ptSickScanApiFreeVisualizationMarkersg
static SickScanApiFreeVisualizationMarkerMsg_PROCTYPE ptSickScanApiFreeVisualizationMarkersg
Definition: sick_scan_xd_api_wrapper.c:174
SickScanApiFreeRadarScanMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScan *msg)
Definition: sick_scan_xd_api_wrapper.c:161
SickScanApiDeregisterLogMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:547
SickScanApiFreePointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreePointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:137
ptSickScanApiNavOdomVelocityMsg
static SickScanApiNavOdomVelocityMsg_PROCTYPE ptSickScanApiNavOdomVelocityMsg
Definition: sick_scan_xd_api_wrapper.c:189
SickScanApiRegisterDiagnosticMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:521
SickScanApiDeregisterDiagnosticMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:529
SickScanApiWaitNextVisualizationMarkerMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:717
SickScanLFErecMsgType
Definition: sick_scan_api.h:210
ptSickScanApiWaitNextPolarPointCloudMsg
static SickScanApiWaitNextPolarPointCloudMsg_PROCTYPE ptSickScanApiWaitNextPolarPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:135
hinstLib
static HINSTANCE hinstLib
Definition: sick_scan_xd_api_wrapper.c:37
ptSickScanApiSetVerboseLevel
static SickScanApiSetVerboseLevel_PROCTYPE ptSickScanApiSetVerboseLevel
Definition: sick_scan_xd_api_wrapper.c:126
SickScanApiDeregisterLIDoutputstateMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:86
SickScanApiWaitNextLIDoutputstateMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:152
SickScanApiRegisterPolarPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:391
SickScanApiRegisterCartesianPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:373
SickScanVisualizationMarkerMsgType
Definition: sick_scan_api.h:358
ptSickScanApiRelease
static SickScanApiRelease_PROCTYPE ptSickScanApiRelease
Definition: sick_scan_xd_api_wrapper.c:48
GetProcAddress
static void * GetProcAddress(HINSTANCE hLib, const char *szFunctionName)
Definition: sick_scan_xd_api_wrapper.c:31
ptSickScanApiWaitNextLdmrsObjectArrayMsg
static SickScanApiWaitNextLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiWaitNextLdmrsObjectArrayMsg
Definition: sick_scan_xd_api_wrapper.c:165
SickScanApiDeregisterNavPoseLandmarkMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
Definition: sick_scan_xd_api_wrapper.c:179
ptSickScanApiDeregisterLdmrsObjectArrayMsg
static SickScanApiDeregisterLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiDeregisterLdmrsObjectArrayMsg
Definition: sick_scan_xd_api_wrapper.c:99
SickScanNavPoseLandmarkMsgType
Definition: sick_scan_api.h:398
SickScanApiDeregisterRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
Definition: sick_scan_xd_api_wrapper.c:471
ptSickScanApiCreate
static SickScanApiCreate_PROCTYPE ptSickScanApiCreate
Definition: sick_scan_xd_api_wrapper.c:44
SickScanApiRegisterLogMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:539
SickScanApiRegisterLogMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLogMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:113
SickScanLIDoutputstateMsgType
Definition: sick_scan_api.h:217
SickScanImuMsgType
Definition: sick_scan_api.h:179
SickScanApiNavOdomVelocityMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiNavOdomVelocityMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:188
ptSickScanApiRegisterCartesianPointCloudMsg
static SickScanApiRegisterCartesianPointCloudMsg_PROCTYPE ptSickScanApiRegisterCartesianPointCloudMsg
Definition: sick_scan_xd_api_wrapper.c:60
SickScanApiDeregisterVisualizationMarkerMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: sick_scan_xd_api_wrapper.c:507
ptSickScanApiRegisterRadarScanMsg
static SickScanApiRegisterRadarScanMsg_PROCTYPE ptSickScanApiRegisterRadarScanMsg
Definition: sick_scan_xd_api_wrapper.c:90
SickScanApiRegisterLIDoutputstateMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:83
SickScanApiRegisterLFErecMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:77
ptSickScanApiFreeLFErecMsg
static SickScanApiFreeLFErecMsg_PROCTYPE ptSickScanApiFreeLFErecMsg
Definition: sick_scan_xd_api_wrapper.c:150
SickScanApiGetStatus
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t *status_code, char *message_buffer, int32_t message_buffer_size)
Definition: sick_scan_xd_api_wrapper.c:557
SickScanLogMsgCallback
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLogMsgCallback)(SickScanApiHandle apiHandle, const SickScanLogMsg *msg)
Definition: sick_scan_api.h:465
SickScanApiDeregisterLdmrsObjectArrayMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
Definition: sick_scan_xd_api_wrapper.c:98
SickScanApiWaitNextNavPoseLandmarkMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg, double timeout_sec)
Definition: sick_scan_xd_api_wrapper.c:182
SickScanApiRegisterPolarPointCloudMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
Definition: sick_scan_xd_api_wrapper.c:65
callback
void callback(const sick_scan_xd::RadarScan::ConstPtr &oa)
Definition: radar_object_marker.cpp:157
ptSickScanApiGetStatus
static SickScanApiGetStatus_PROCTYPE ptSickScanApiGetStatus
Definition: sick_scan_xd_api_wrapper.c:120
SickScanApiRegisterVisualizationMarkerMsg_PROCTYPE
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
Definition: sick_scan_xd_api_wrapper.c:101
SickScanApiFreeLIDoutputstateMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg)
Definition: sick_scan_xd_api_wrapper.c:671
SickScanApiUnloadLibrary
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiUnloadLibrary()
Definition: sick_scan_xd_api_wrapper.c:234


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