sick_generic_caller.cpp
Go to the documentation of this file.
00001 
00071 #include <stdio.h>
00072 #include <stdlib.h>
00073 #include <string.h>
00074 
00075 #include "sick_scan/sick_generic_laser.h"
00076 #include "sick_scan/sick_generic_imu.h"
00077 #include "sick_scan/binScanf.hpp"
00078 #include "sick_scan/binPrintf.hpp"
00079 #include "sick_scan/dataDumper.h"
00080 
00081 #ifdef _MSC_VER
00082 #include "sick_scan/rosconsole_simu.hpp"
00083 #endif
00084 
00085 #define MAX_NAME_LEN (1024)
00086 
00087 // 001.001.000 Switch to multithreaded processing of data
00088 // 001.001.001: Documentation added
00089 // 001.002.001: Bug in bin_scanf fixed (number of counted arguments was always 1)
00090 // 001.002.002: MRS1xxx/LMS1xxx - legacy device ident cmd. changed to new device ident cmd
00091 // 001.002.003: MRS1xxx/LMS1xxx - support of hector_slam integrated
00092 // 001.002.004: RMS3xx - profiling and radar support optimized
00093 // 001.002.005: Startup process changed to state machine
00094 // 001.002.006: Signal handler for ctrl-c added
00095 // 001.002.007: Fix for multi echo handling with lookup table
00096 // 001.002.008: IMU Parser structure added
00097 // 001.002.009: Application setting modified for MRS1104
00098 // 001.002.010: First version of IMU parser
00099 // 001.002.011: Ip Address change added, bugfixing
00100 // 001.003.000: Jan 2019  release 0.0.14
00101 // 001.003.001: Jan 2019  release 0.0.14 address handling for ip v4 parsing fixed
00102 // 001.003.002: Feb 2019 Fixing and optimizing console output
00103 // 001.003.016: Feb 2019 Profiling+instructions, Caching of Ros-Params
00104 // 001.003.017: May 2019 stability issues, scan rate and angular resolution settings added
00105 // 001.003.018: May 2019 LMS1000 Min/Max angel settings added and tested
00106 // 001.003.020: May 2019 Bloom process prepared
00107 #define SICK_GENERIC_MAJOR_VER "001"
00108 #define SICK_GENERIC_MINOR_VER "003"
00109 #define SICK_GENERIC_PATCH_LEVEL "020"
00110 
00111 #include <algorithm> // for std::min
00112 
00113 
00114 
00115 
00116 std::string getVersionInfo();
00127 int main(int argc, char **argv)
00128 {
00129 
00130 
00131   DataDumper::instance().writeToFileNameWhenBufferIsFull("/tmp/sickscan_debug.csv");
00132         char nameId[] = "__name:=";
00133         char nameVal[MAX_NAME_LEN] = { 0 };
00134         char **argv_tmp; // argv_tmp[0][0] argv_tmp[0] identisch ist zu (*argv_tmp)
00135         int argc_tmp;
00136         std::string scannerName = "????";
00137 
00138         // sick_scan::SickScanImu::imuParserTest();
00139 
00140         argc_tmp = argc;
00141         argv_tmp = argv;
00142 
00143         const int MAX_STR_LEN = 1024;
00144         char nameTagVal[MAX_STR_LEN] = { 0 };
00145         char logTagVal[MAX_STR_LEN] = { 0 };
00146         char internalDebugTagVal[MAX_STR_LEN] = { 0 };
00147         char sensorEmulVal[MAX_STR_LEN] = { 0 };
00148 
00149         if (argc == 1) // just for testing without calling by roslaunch
00150         {
00151                 // recommended call for internal debugging as an example: __name:=sick_rms_320 __internalDebug:=1
00152                 // strcpy(nameTagVal, "__name:=sick_rms_3xx");  // sick_rms_320 -> radar
00153                 strcpy(nameTagVal, "__name:=sick_tim_5xx");  // sick_rms_320 -> radar
00154                 strcpy(logTagVal, "__log:=/tmp/tmp.log");
00155                 strcpy(internalDebugTagVal, "__internalDebug:=1");
00156                 // strcpy(sensorEmulVal, "__emulSensor:=1");
00157         strcpy(sensorEmulVal, "__emulSensor:=0");
00158                 argc_tmp = 5;
00159                 argv_tmp = (char **)malloc(sizeof(char *) * argc_tmp);
00160 
00161                 argv_tmp[0] = argv[0];
00162                 argv_tmp[1] = nameTagVal;
00163                 argv_tmp[2] = logTagVal;
00164                 argv_tmp[3] = internalDebugTagVal;
00165                 argv_tmp[4] = sensorEmulVal;
00166 
00167         }
00168   //
00169         std::string versionInfo = "sick_generic_caller V. ";
00170         versionInfo += std::string(SICK_GENERIC_MAJOR_VER) + '.';
00171         versionInfo += std::string(SICK_GENERIC_MINOR_VER) + '.';
00172         versionInfo += std::string(SICK_GENERIC_PATCH_LEVEL);
00173 
00174         setVersionInfo(versionInfo);
00175   ROS_INFO("%s", versionInfo.c_str());
00176         for (int i = 0; i < argc_tmp; i++)
00177         {
00178                 if (strstr(argv_tmp[i], nameId) == argv_tmp[i])
00179                 {
00180                         strcpy(nameVal, argv_tmp[i] + strlen(nameId));
00181                         scannerName = nameVal;
00182                 }
00183                 ROS_INFO("Program arguments: %s", argv_tmp[i]);
00184         }
00185 
00186         int result = mainGenericLaser(argc_tmp, argv_tmp, scannerName);
00187         return result;
00188 
00189 }


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 05:05:34