sick_generic_caller.cpp
Go to the documentation of this file.
1 
71 #include <stdio.h>
72 #include <stdlib.h>
73 #include <string.h>
74 
77 #include "sick_scan/binScanf.hpp"
78 #include "sick_scan/binPrintf.hpp"
79 #include "sick_scan/dataDumper.h"
80 
81 #ifdef _MSC_VER
82 #include "sick_scan/rosconsole_simu.hpp"
83 #endif
84 
85 #define MAX_NAME_LEN (1024)
86 
87 // 001.001.000 Switch to multithreaded processing of data
88 // 001.001.001: Documentation added
89 // 001.002.001: Bug in bin_scanf fixed (number of counted arguments was always 1)
90 // 001.002.002: MRS1xxx/LMS1xxx - legacy device ident cmd. changed to new device ident cmd
91 // 001.002.003: MRS1xxx/LMS1xxx - support of hector_slam integrated
92 // 001.002.004: RMS3xx - profiling and radar support optimized
93 // 001.002.005: Startup process changed to state machine
94 // 001.002.006: Signal handler for ctrl-c added
95 // 001.002.007: Fix for multi echo handling with lookup table
96 // 001.002.008: IMU Parser structure added
97 // 001.002.009: Application setting modified for MRS1104
98 // 001.002.010: First version of IMU parser
99 // 001.002.011: Ip Address change added, bugfixing
100 // 001.003.000: Jan 2019 release 0.0.14
101 // 001.003.001: Jan 2019 release 0.0.14 address handling for ip v4 parsing fixed
102 // 001.003.002: Feb 2019 Fixing and optimizing console output
103 // 001.003.016: Feb 2019 Profiling+instructions, Caching of Ros-Params
104 // 001.003.017: May 2019 stability issues, scan rate and angular resolution settings added
105 // 001.003.018: May 2019 LMS1000 Min/Max angel settings added and tested
106 // 001.003.020: May 2019 Bloom process prepared
107 #define SICK_GENERIC_MAJOR_VER "001"
108 #define SICK_GENERIC_MINOR_VER "003"
109 #define SICK_GENERIC_PATCH_LEVEL "020"
110 
111 #include <algorithm> // for std::min
112 
113 
114 
115 
116 std::string getVersionInfo();
127 int main(int argc, char **argv)
128 {
129 
130 
131  DataDumper::instance().writeToFileNameWhenBufferIsFull("/tmp/sickscan_debug.csv");
132  char nameId[] = "__name:=";
133  char nameVal[MAX_NAME_LEN] = { 0 };
134  char **argv_tmp; // argv_tmp[0][0] argv_tmp[0] identisch ist zu (*argv_tmp)
135  int argc_tmp;
136  std::string scannerName = "????";
137 
138  // sick_scan::SickScanImu::imuParserTest();
139 
140  argc_tmp = argc;
141  argv_tmp = argv;
142 
143  const int MAX_STR_LEN = 1024;
144  char nameTagVal[MAX_STR_LEN] = { 0 };
145  char logTagVal[MAX_STR_LEN] = { 0 };
146  char internalDebugTagVal[MAX_STR_LEN] = { 0 };
147  char sensorEmulVal[MAX_STR_LEN] = { 0 };
148 
149  if (argc == 1) // just for testing without calling by roslaunch
150  {
151  // recommended call for internal debugging as an example: __name:=sick_rms_320 __internalDebug:=1
152  // strcpy(nameTagVal, "__name:=sick_rms_3xx"); // sick_rms_320 -> radar
153  strcpy(nameTagVal, "__name:=sick_tim_5xx"); // sick_rms_320 -> radar
154  strcpy(logTagVal, "__log:=/tmp/tmp.log");
155  strcpy(internalDebugTagVal, "__internalDebug:=1");
156  // strcpy(sensorEmulVal, "__emulSensor:=1");
157  strcpy(sensorEmulVal, "__emulSensor:=0");
158  argc_tmp = 5;
159  argv_tmp = (char **)malloc(sizeof(char *) * argc_tmp);
160 
161  argv_tmp[0] = argv[0];
162  argv_tmp[1] = nameTagVal;
163  argv_tmp[2] = logTagVal;
164  argv_tmp[3] = internalDebugTagVal;
165  argv_tmp[4] = sensorEmulVal;
166 
167  }
168  //
169  std::string versionInfo = "sick_generic_caller V. ";
170  versionInfo += std::string(SICK_GENERIC_MAJOR_VER) + '.';
171  versionInfo += std::string(SICK_GENERIC_MINOR_VER) + '.';
172  versionInfo += std::string(SICK_GENERIC_PATCH_LEVEL);
173 
174  setVersionInfo(versionInfo);
175  ROS_INFO("%s", versionInfo.c_str());
176  for (int i = 0; i < argc_tmp; i++)
177  {
178  if (strstr(argv_tmp[i], nameId) == argv_tmp[i])
179  {
180  strcpy(nameVal, argv_tmp[i] + strlen(nameId));
181  scannerName = nameVal;
182  }
183  ROS_INFO("Program arguments: %s", argv_tmp[i]);
184  }
185 
186  int result = mainGenericLaser(argc_tmp, argv_tmp, scannerName);
187  return result;
188 
189 }
static std::string versionInfo
#define SICK_GENERIC_MINOR_VER
int mainGenericLaser(int argc, char **argv, std::string nodeName)
Internal Startup routine.
std::string getVersionInfo()
#define SICK_GENERIC_PATCH_LEVEL
#define SICK_GENERIC_MAJOR_VER
int main(int argc, char **argv)
Startup routine - if called with no argmuments we assume debug session. Set scanner name variable by ...
#define ROS_INFO(...)
int writeToFileNameWhenBufferIsFull(std::string filename)
Definition: dataDumper.cpp:59
static DataDumper & instance()
Definition: dataDumper.h:13
#define MAX_NAME_LEN
void setVersionInfo(std::string _versionInfo)


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