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.
25 return dlopen(szLibFilename,RTLD_GLOBAL|RTLD_LAZY);
29 return !dlclose(hLib);
33 return dlsym(hLib,szFunctionName);
199 #define CACHE_FUNCTION_PTR(apiHandle, ptFunction, szFunctionName, procType) \
202 if (hinstLib == 0 || apiHandle == 0) \
204 printf("## ERROR SickScanApi, cacheFunctionPtr(%s): library not initialized\n", szFunctionName); \
207 else if (ptFunction == 0) \
209 ptFunction = (procType)GetProcAddress(hinstLib, szFunctionName); \
211 if (ptFunction == 0) \
213 printf("## ERROR SickScanApi, cacheFunctionPtr(%s): GetProcAddress failed\n", szFunctionName); \
227 printf(
"## WARNING SickScanApiLoadLibrary: LoadLibrary(\"%s\") failed\n", library_filepath);
241 printf(
"## ERROR SickScanApiUnloadLibrary: FreeLibrary() failed\n");
308 printf(
"## ERROR SickScanApiCreate: library not loaded\n");
317 printf(
"## ERROR SickScanApiCreate: GetProcAddress failed\n");
323 printf(
"## ERROR SickScanApiCreate: library call SickScanApiCreate() returned 0\n");
334 printf(
"## ERROR SickScanApiRelease: library call SickScanApiRelease() failed, error code %d\n", ret);
344 printf(
"## ERROR SickScanApiInitByLaunchfile: library call SickScanApiInitByLaunchfile() failed, error code %d\n", ret);
354 printf(
"## ERROR SickScanApiInitByCli: library call SickScanApiInitByCli() failed, error code %d\n", ret);
364 printf(
"## ERROR SickScanApiClose: library call SickScanApiClose() failed, error code %d\n", ret);
378 printf(
"## ERROR SickScanApiRegisterCartesianPointCloudMsg: library call SickScanApiRegisterCartesianPointCloudMsg() failed, error code %d\n", ret);
386 printf(
"## ERROR SickScanApiDeregisterCartesianPointCloudMsg: library call SickScanApiDeregisterCartesianPointCloudMsg() failed, error code %d\n", ret);
396 printf(
"## ERROR SickScanApiRegisterPolarPointCloudMsg: library call SickScanApiRegisterPolarPointCloudMsg() failed, error code %d\n", ret);
404 printf(
"## ERROR SickScanApiDeregisterPolarPointCloudMsg: library call SickScanApiDeregisterPolarPointCloudMsg() failed, error code %d\n", ret);
414 printf(
"## ERROR SickScanApiRegisterImuMsg: library call SickScanApiRegisterImuMsg() failed, error code %d\n", ret);
422 printf(
"## ERROR SickScanApiDeregisterImuMsg: library call SickScanApiDeregisterImuMsg() failed, error code %d\n", ret);
432 printf(
"## ERROR SickScanApiRegisterLFErecMsg: library call SickScanApiRegisterLFErecMsg() failed, error code %d\n", ret);
440 printf(
"## ERROR SickScanApiDeregisterLFErecMsg: library call SickScanApiDeregisterLFErecMsg() failed, error code %d\n", ret);
450 printf(
"## ERROR SickScanApiRegisterLIDoutputstateMsg: library call SickScanApiRegisterLIDoutputstateMsg() failed, error code %d\n", ret);
458 printf(
"## ERROR SickScanApiDeregisterLIDoutputstateMsg: library call SickScanApiDeregisterLIDoutputstateMsg() failed, error code %d\n", ret);
468 printf(
"## ERROR SickScanApiRegisterRadarScanMsg: library call SickScanApiRegisterRadarScanMsg() failed, error code %d\n", ret);
476 printf(
"## ERROR SickScanApiDeregisterRadarScanMsg: library call SickScanApiDeregisterRadarScanMsg() failed, error code %d\n", ret);
486 printf(
"## ERROR SickScanApiRegisterLdmrsObjectArrayMsg: library call SickScanApiRegisterLdmrsObjectArrayMsg() failed, error code %d\n", ret);
494 printf(
"## ERROR SickScanApiDeregisterLdmrsObjectArrayMsg: library call SickScanApiDeregisterLdmrsObjectArrayMsg() failed, error code %d\n", ret);
504 printf(
"## ERROR SickScanApiRegisterVisualizationMarkerMsg: library call SickScanApiRegisterVisualizationMarkerMsg() failed, error code %d\n", ret);
512 printf(
"## ERROR SickScanApiDeregisterVisualizationMarkerMsg: library call SickScanApiDeregisterVisualizationMarkerMsg() failed, error code %d\n", ret);
526 printf(
"## ERROR SickScanApiRegisterDiagnosticMsg: library call SickScanApiRegisterDiagnosticMsg() failed, error code %d\n", ret);
534 printf(
"## ERROR SickScanApiDeregisterDiagnosticMsg: library call SickScanApiDeregisterDiagnosticMsg() failed, error code %d\n", ret);
544 printf(
"## ERROR SickScanApiRegisterLogMsg: library call SickScanApiRegisterLogMsg() failed, error code %d\n", ret);
552 printf(
"## ERROR SickScanApiDeregisterLogMsg: library call SickScanApiDeregisterLogMsg() failed, error code %d\n", ret);
562 printf(
"## ERROR SickScanApiGetStatus: library call SickScanApiGetStatus() failed, error code %d\n", ret);
572 printf(
"## ERROR SickScanApiSendSOPAS: library call SickScanApiSendSOPAS() failed, error code %d\n", ret);
584 printf(
"## ERROR SickScanApiSetVerboseLevel: library call SickScanApiSetVerboseLevel() failed, error code %d\n", ret);
606 printf(
"## ERROR SickScanApiWaitNextCartesianPointCloudMsg: library call SickScanApiWaitNextCartesianPointCloudMsg() failed, error code %d\n", ret);
614 printf(
"## ERROR SickScanApiWaitNextPolarPointCloudMsg: library call SickScanApiWaitNextPolarPointCloudMsg() failed, error code %d\n", ret);
622 printf(
"## ERROR SickScanApiFreePointCloudMsg: library call SickScanApiFreePointCloudMsg() failed, error code %d\n", ret);
632 printf(
"## ERROR SickScanApiWaitNextImuMsg: library call SickScanApiWaitNextImuMsg() failed, error code %d\n", ret);
640 printf(
"## ERROR SickScanApiFreeImuMsg: library call SickScanApiFreeImuMsg() failed, error code %d\n", ret);
650 printf(
"## ERROR SickScanApiWaitNextLFErecMsg: library call SickScanApiWaitNextLFErecMsg() failed, error code %d\n", ret);
658 printf(
"## ERROR SickScanApiFreeLFErecMsg: library call SickScanApiFreeLFErecMsg() failed, error code %d\n", ret);
668 printf(
"## ERROR SickScanApiWaitNextLIDoutputstateMsg: library call SickScanApiWaitNextLIDoutputstateMsg() failed, error code %d\n", ret);
676 printf(
"## ERROR SickScanApiFreeLIDoutputstateMsg: library call SickScanApiFreeLIDoutputstateMsg() failed, error code %d\n", ret);
686 printf(
"## ERROR SickScanApiWaitNextRadarScanMsg: library call SickScanApiWaitNextRadarScanMsg() failed, error code %d\n", ret);
694 printf(
"## ERROR SickScanApiFreeRadarScanMsg: library call SickScanApiFreeRadarScanMsg() failed, error code %d\n", ret);
704 printf(
"## ERROR SickScanApiWaitNextLdmrsObjectArrayMsg: library call SickScanApiWaitNextLdmrsObjectArrayMsg() failed, error code %d\n", ret);
712 printf(
"## ERROR SickScanApiFreeLdmrsObjectArrayMsg: library call SickScanApiFreeLdmrsObjectArrayMsg() failed, error code %d\n", ret);
722 printf(
"## ERROR SickScanApiWaitNextVisualizationMarkerMsg: library call SickScanApiWaitNextVisualizationMarkerMsg() failed, error code %d\n", ret);
730 printf(
"## ERROR SickScanApiFreeVisualizationMarkerMsg: library call SickScanApiFreeVisualizationMarkerMsg() failed, error code %d\n", ret);
743 printf(
"## ERROR SickScanApiRegisterNavPoseLandmarkMsg: library call SickScanApiRegisterNavPoseLandmarkMsg() failed, error code %d\n", ret);
751 printf(
"## ERROR SickScanApiDeregisterNavPoseLandmarkMsg: library call SickScanApiDeregisterNavPoseLandmarkMsg() failed, error code %d\n", ret);
759 printf(
"## ERROR SickScanApiWaitNextNavPoseLandmarkMsg: library call SickScanApiWaitNextNavPoseLandmarkMsg() failed, error code %d\n", ret);
767 printf(
"## ERROR SickScanApiFreeNavPoseLandmarkMsg: library call SickScanApiFreeNavPoseLandmarkMsg() failed, error code %d\n", ret);
775 printf(
"## ERROR SickScanApiNavOdomVelocityMsg: library call SickScanApiNavOdomVelocityMsg() failed, error code %d\n", ret);
783 printf(
"## ERROR SickScanApiOdomVelocityMsg: library call SickScanApiOdomVelocityMsg() failed, error code %d\n", ret);
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterDiagnosticMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByLaunchfile(SickScanApiHandle apiHandle, const char *launchfile_args)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg)
static SickScanApiSendSOPAS_PROCTYPE ptSickScanApiSendSOPAS
static SickScanApiClose_PROCTYPE ptSickScanApiClose
static SickScanApiDeregisterLIDoutputstateMsg_PROCTYPE ptSickScanApiDeregisterLIDoutputstateMsg
static HINSTANCE LoadLibrary(const char *szLibFilename)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSendSOPAS(SickScanApiHandle apiHandle, const char *sopas_command, char *sopas_response_buffer, int32_t response_buffer_size)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
static SickScanApiWaitNextLFErecMsg_PROCTYPE ptSickScanApiWaitNextLFErecMsg
static SickScanApiRegisterLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiRegisterLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLogMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiNavOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
static SickScanApiDeregisterLFErecMsg_PROCTYPE ptSickScanApiDeregisterLFErecMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetVerboseLevel(SickScanApiHandle apiHandle)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiSetVerboseLevel_PROCTYPE)(SickScanApiHandle apiHandle, int32_t verbose_level)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiSetVerboseLevel(SickScanApiHandle apiHandle, int32_t verbose_level)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiOdomVelocityMsg(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiClose_PROCTYPE)(SickScanApiHandle apiHandle)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanPointCloudMsgCallback)(SickScanApiHandle apiHandle, const SickScanPointCloudMsg *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg, double timeout_sec)
static SickScanApiDeregisterVisualizationMarkerMsg_PROCTYPE ptSickScanApiDeregisterVisualizationMarkerMsg
static SickScanApiFreeRadarScanMsg_PROCTYPE ptSickScanApiFreeRadarScanMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg)
static SickScanApiRegisterVisualizationMarkerMsg_PROCTYPE ptSickScanApiRegisterVisualizationMarkerMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLdmrsObjectArrayCallback)(SickScanApiHandle apiHandle, const SickScanLdmrsObjectArray *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiGetStatus_PROCTYPE)(SickScanApiHandle apiHandle, int32_t *status_code, char *message_buffer, int32_t message_buffer_size)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg, double timeout_sec)
static SickScanApiFreeImuMsg_PROCTYPE ptSickScanApiFreeImuMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsg *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
static SickScanApiWaitNextRadarScanMsg_PROCTYPE ptSickScanApiWaitNextRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
static SickScanApiWaitNextLIDoutputstateMsg_PROCTYPE ptSickScanApiWaitNextLIDoutputstateMsg
static SickScanApiOdomVelocityMsg_PROCTYPE ptSickScanApiOdomVelocityMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiInitByCli_PROCTYPE)(SickScanApiHandle apiHandle, int argc, char **argv)
static SickScanApiRegisterDiagnosticMsg_PROCTYPE ptSickScanApiRegisterDiagnosticMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRelease_PROCTYPE)(SickScanApiHandle apiHandle)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextImuMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanImuMsg *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiLoadLibrary(const char *library_filepath)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLFErecMsgCallback)(SickScanApiHandle apiHandle, const SickScanLFErecMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScan *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
static SickScanApiGetVerboseLevel_PROCTYPE ptSickScanApiGetVerboseLevel
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
static SickScanApiWaitNextImuMsg_PROCTYPE ptSickScanApiWaitNextImuMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanNavPoseLandmarkCallback)(SickScanApiHandle apiHandle, const SickScanNavPoseLandmarkMsg *msg)
static SickScanApiDeregisterLogMsg_PROCTYPE ptSickScanApiDeregisterLogMsg
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanImuMsgCallback)(SickScanApiHandle apiHandle, const SickScanImuMsg *msg)
#define CACHE_FUNCTION_PTR(apiHandle, ptFunction, szFunctionName, procType)
#define SICK_SCAN_XD_API_CALLING_CONVENTION
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArray *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterImuMsg(SickScanApiHandle apiHandle, SickScanImuMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
static SickScanApiFreeLIDoutputstateMsg_PROCTYPE ptSickScanApiFreeLIDoutputstateMsg
static SickScanApiDeregisterRadarScanMsg_PROCTYPE ptSickScanApiDeregisterRadarScanMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg)
static SickScanApiDeregisterNavPoseLandmarkMsg_PROCTYPE ptSickScanApiDeregisterNavPoseLandmarkMsg
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanDiagnosticMsgCallback)(SickScanApiHandle apiHandle, const SickScanDiagnosticMsg *msg)
static SickScanApiDeregisterDiagnosticMsg_PROCTYPE ptSickScanApiDeregisterDiagnosticMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScan *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg)
SickScanApiHandle SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiCreate(int argc, char **argv)
static SickScanApiRegisterLIDoutputstateMsg_PROCTYPE ptSickScanApiRegisterLIDoutputstateMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg, double timeout_sec)
static SickScanApiInitByCli_PROCTYPE ptSickScanApiInitByCli
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg)
static SickScanApiWaitNextVisualizationMarkerMsg_PROCTYPE ptSickScanApiWaitNextVisualizationMarkerMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextCartesianPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
static SickScanApiWaitNextNavPoseLandmarkMsg_PROCTYPE ptSickScanApiWaitNextNavPoseLandmarkMsg
static SickScanApiWaitNextCartesianPointCloudMsg_PROCTYPE ptSickScanApiWaitNextCartesianPointCloudMsg
@ SICK_SCAN_API_NOT_LOADED
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLIDoutputstateMsgCallback)(SickScanApiHandle apiHandle, const SickScanLIDoutputstateMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterDiagnosticMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
static SickScanApiRegisterNavPoseLandmarkMsg_PROCTYPE ptSickScanApiRegisterNavPoseLandmarkMsg
static SickScanApiRegisterLFErecMsg_PROCTYPE ptSickScanApiRegisterLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanVisualizationMarkerCallback)(SickScanApiHandle apiHandle, const SickScanVisualizationMarkerMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
static SickScanApiInitByLaunchfile_PROCTYPE ptSickScanApiInitByLaunchfile
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextLFErecMsg(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiInitByCli(SickScanApiHandle apiHandle, int argc, char **argv)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiOdomVelocityMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *msg)
@ SICK_SCAN_API_NOT_INITIALIZED
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsg *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiGetVerboseLevel_PROCTYPE)(SickScanApiHandle apiHandle)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
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)
static SickScanApiDeregisterImuMsg_PROCTYPE ptSickScanApiDeregisterImuMsg
static SickScanApiDeregisterCartesianPointCloudMsg_PROCTYPE ptSickScanApiDeregisterCartesianPointCloudMsg
static SickScanApiRegisterImuMsg_PROCTYPE ptSickScanApiRegisterImuMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiInitByLaunchfile_PROCTYPE)(SickScanApiHandle apiHandle, const char *launchfile)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLdmrsObjectArrayMsg(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
static SickScanApiDeregisterPolarPointCloudMsg_PROCTYPE ptSickScanApiDeregisterPolarPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterNavPoseLandmarkMsg(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreePointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
static SickScanApiFreeNavPoseLandmarkMsg_PROCTYPE ptSickScanApiFreeNavPoseLandmarkMsg
SickScanApiHandle(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiCreate_PROCTYPE)(int argc, char **argv)
static SickScanApiFreeLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiFreeLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiClose(SickScanApiHandle apiHandle)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRelease(SickScanApiHandle apiHandle)
static SickScanApiFreePointCloudMsg_PROCTYPE ptSickScanApiFreePointCloudMsg
static SickScanApiRegisterPolarPointCloudMsg_PROCTYPE ptSickScanApiRegisterPolarPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
static int FreeLibrary(HINSTANCE hLib)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeImuMsg(SickScanApiHandle apiHandle, SickScanImuMsg *msg)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanRadarScanCallback)(SickScanApiHandle apiHandle, const SickScanRadarScan *msg)
static SickScanApiRegisterLogMsg_PROCTYPE ptSickScanApiRegisterLogMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg)
static SickScanApiFreeVisualizationMarkerMsg_PROCTYPE ptSickScanApiFreeVisualizationMarkersg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreeRadarScanMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanRadarScan *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiFreePointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsg *msg)
static SickScanApiNavOdomVelocityMsg_PROCTYPE ptSickScanApiNavOdomVelocityMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterDiagnosticMsg(SickScanApiHandle apiHandle, SickScanDiagnosticMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiWaitNextVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerMsg *msg, double timeout_sec)
static SickScanApiWaitNextPolarPointCloudMsg_PROCTYPE ptSickScanApiWaitNextPolarPointCloudMsg
static HINSTANCE hinstLib
static SickScanApiSetVerboseLevel_PROCTYPE ptSickScanApiSetVerboseLevel
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg, double timeout_sec)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterPolarPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterCartesianPointCloudMsg(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
static SickScanApiRelease_PROCTYPE ptSickScanApiRelease
static void * GetProcAddress(HINSTANCE hLib, const char *szFunctionName)
static SickScanApiWaitNextLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiWaitNextLdmrsObjectArrayMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkCallback callback)
static SickScanApiDeregisterLdmrsObjectArrayMsg_PROCTYPE ptSickScanApiDeregisterLdmrsObjectArrayMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterRadarScanMsg(SickScanApiHandle apiHandle, SickScanRadarScanCallback callback)
static SickScanApiCreate_PROCTYPE ptSickScanApiCreate
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiRegisterLogMsg(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLogMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLogMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiNavOdomVelocityMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *msg)
static SickScanApiRegisterCartesianPointCloudMsg_PROCTYPE ptSickScanApiRegisterCartesianPointCloudMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiDeregisterVisualizationMarkerMsg(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
static SickScanApiRegisterRadarScanMsg_PROCTYPE ptSickScanApiRegisterRadarScanMsg
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLIDoutputstateMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsgCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterLFErecMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLFErecMsgCallback callback)
static SickScanApiFreeLFErecMsg_PROCTYPE ptSickScanApiFreeLFErecMsg
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiGetStatus(SickScanApiHandle apiHandle, int32_t *status_code, char *message_buffer, int32_t message_buffer_size)
void(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanLogMsgCallback)(SickScanApiHandle apiHandle, const SickScanLogMsg *msg)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiDeregisterLdmrsObjectArrayMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanLdmrsObjectArrayCallback callback)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiWaitNextNavPoseLandmarkMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanNavPoseLandmarkMsg *msg, double timeout_sec)
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterPolarPointCloudMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanPointCloudMsgCallback callback)
void callback(const sick_scan_xd::RadarScan::ConstPtr &oa)
static SickScanApiGetStatus_PROCTYPE ptSickScanApiGetStatus
int32_t(SICK_SCAN_XD_API_CALLING_CONVENTION * SickScanApiRegisterVisualizationMarkerMsg_PROCTYPE)(SickScanApiHandle apiHandle, SickScanVisualizationMarkerCallback callback)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiFreeLIDoutputstateMsg(SickScanApiHandle apiHandle, SickScanLIDoutputstateMsg *msg)
int32_t SICK_SCAN_XD_API_CALLING_CONVENTION SickScanApiUnloadLibrary()
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:11