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 
76 #include "sick_scan/dataDumper.h"
77 
79 #ifdef _MSC_VER
80 #include "sick_scan/rosconsole_simu.hpp"
81 #endif
82 
83 #define MAX_NAME_LEN (1024)
84 
85 // 001.001.000 Switch to multithreaded processing of data
86 // 001.001.001: Documentation added
87 // 001.002.001: Bug in bin_scanf fixed (number of counted arguments was always 1)
88 // 001.002.002: MRS1xxx/LMS1xxx - legacy device ident cmd. changed to new device ident cmd
89 // 001.002.003: MRS1xxx/LMS1xxx - support of hector_slam integrated
90 // 001.002.004: RMS3xx - profiling and radar support optimized
91 // 001.002.005: Startup process changed to state machine
92 // 001.002.006: Signal handler for ctrl-c added
93 // 001.002.007: Fix for multi echo handling with lookup table
94 // 001.002.008: IMU Parser structure added
95 // 001.002.009: Application setting modified for MRS1104
96 // 001.002.010: First version of IMU parser
97 // 001.002.011: Ip Address change added, bugfixing
98 // 001.003.000: Jan 2019 release 0.0.14
99 // 001.003.001: Jan 2019 release 0.0.14 address handling for ip v4 parsing fixed
100 // 001.003.002: Feb 2019 Fixing and optimizing console output
101 // 001.003.016: Feb 2019 Profiling+instructions, Caching of Ros-Params
102 // 001.003.017: May 2019 stability issues, scan rate and angular resolution settings added
103 // 001.003.018: May 2019 LMS1000 Min/Max angel settings added and tested
104 // 001.003.020: May 2019 Bloom process prepared
105 // 001.003.022: Sep 2019 LMS 4xxx added
106 // 001.004.000: Oct 2019 ENCODER Support added
107 // 001.004.001: Nov 2019 IMU Timestamp Fix
108 // 1.5.0: 2019-11-20: Radar implementation moved to a singleton
109 // 1.5.1: 2020-03-04: First support of TiM240 prototype
110 // 1.5.3: 2020-03-19: Fixes for LMS1xx
111 // 1.5.4: 2020-03-26: Fixes for 16 bit resolution flag
112 // 1.5.5: 2020-04-01: MRS6xxx check
113 // 1.5.5: 2020-05-14: NAV 2xx support
114 // 1.7.0: 2020-06-01: TiM443 added
115 // 1.7.1: 2020-06-04: NAV 2xx angle correction added
116 // 1.7.2: 2020-06-09: TiM433 added and launch file info for TiM4xx added
117 // 1.7.3: 2020-06-10: NAV 3xx angle correction added
118 // 1.7.4: 2020-06-10: NAV 3xx angle correction improved
119 // 1.7.5: 2020-06-25: Preparing for Release Noetic
120 // 1.7.6: 2020-07-14: NAV310 handling optimized (angle calculation and compensation), barebone quaterion to euler
121 // 1.7.7: 2020-07-21: barebone quaterion to euler
122 #define SICK_GENERIC_MAJOR_VER "1"
123 #define SICK_GENERIC_MINOR_VER "10"
124 #define SICK_GENERIC_PATCH_LEVEL "1"
125 
126 #include <algorithm> // for std::min
127 
128 
129 std::string getVersionInfo();
130 
141 int main(int argc, char **argv)
142 {
143 
144  DataDumper::instance().writeToFileNameWhenBufferIsFull("/tmp/sickscan_debug.csv");
145  char nameId[] = "__name:=";
146  char nameVal[MAX_NAME_LEN] = {0};
147  char **argv_tmp; // argv_tmp[0][0] argv_tmp[0] identisch ist zu (*argv_tmp)
148  int argc_tmp;
149  std::string scannerName = "????";
150 
151  // sick_scan::SickScanImu::imuParserTest();
152 
153  argc_tmp = argc;
154  argv_tmp = argv;
155 
156  const int MAX_STR_LEN = 1024;
157  char nameTagVal[MAX_STR_LEN] = {0};
158  char logTagVal[MAX_STR_LEN] = {0};
159  char internalDebugTagVal[MAX_STR_LEN] = {0};
160  char sensorEmulVal[MAX_STR_LEN] = {0};
161 
162  if (argc == 1) // just for testing without calling by roslaunch
163  {
164  // recommended call for internal debugging as an example: __name:=sick_rms_320 __internalDebug:=1
165  // strcpy(nameTagVal, "__name:=sick_rms_3xx"); // sick_rms_320 -> radar
166  strcpy(nameTagVal, "__name:=sick_tim_5xx"); // sick_rms_320 -> radar
167  strcpy(logTagVal, "__log:=/tmp/tmp.log");
168  strcpy(internalDebugTagVal, "__internalDebug:=1");
169  // strcpy(sensorEmulVal, "__emulSensor:=1");
170  strcpy(sensorEmulVal, "__emulSensor:=0");
171  argc_tmp = 5;
172  argv_tmp = (char **) malloc(sizeof(char *) * argc_tmp);
173 
174  argv_tmp[0] = argv[0];
175  argv_tmp[1] = nameTagVal;
176  argv_tmp[2] = logTagVal;
177  argv_tmp[3] = internalDebugTagVal;
178  argv_tmp[4] = sensorEmulVal;
179 
180  }
181  //
182  std::string versionInfo = "sick_generic_caller V. ";
183  versionInfo += std::string(SICK_GENERIC_MAJOR_VER) + '.';
184  versionInfo += std::string(SICK_GENERIC_MINOR_VER) + '.';
185  versionInfo += std::string(SICK_GENERIC_PATCH_LEVEL);
186 
187  setVersionInfo(versionInfo);
188  ROS_INFO("%s", versionInfo.c_str());
189  for (int i = 0; i < argc_tmp; i++)
190  {
191  if (strstr(argv_tmp[i], nameId) == argv_tmp[i])
192  {
193  strcpy(nameVal, argv_tmp[i] + strlen(nameId));
194  scannerName = nameVal;
195  }
196  ROS_INFO("Program arguments: %s", argv_tmp[i]);
197  }
198 
199  int result = mainGenericLaser(argc_tmp, argv_tmp, scannerName);
200  return result;
201 
202 }
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:61
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 Wed May 5 2021 03:05:48