82 #include "sick_scan/rosconsole_simu.hpp" 85 #define MAX_NAME_LEN (1024) 107 #define SICK_GENERIC_MAJOR_VER "001" 108 #define SICK_GENERIC_MINOR_VER "003" 109 #define SICK_GENERIC_PATCH_LEVEL "020" 127 int main(
int argc,
char **argv)
132 char nameId[] =
"__name:=";
136 std::string scannerName =
"????";
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 };
153 strcpy(nameTagVal,
"__name:=sick_tim_5xx");
154 strcpy(logTagVal,
"__log:=/tmp/tmp.log");
155 strcpy(internalDebugTagVal,
"__internalDebug:=1");
157 strcpy(sensorEmulVal,
"__emulSensor:=0");
159 argv_tmp = (
char **)malloc(
sizeof(
char *) * argc_tmp);
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;
169 std::string
versionInfo =
"sick_generic_caller V. ";
175 ROS_INFO(
"%s", versionInfo.c_str());
176 for (
int i = 0; i < argc_tmp; i++)
178 if (strstr(argv_tmp[i], nameId) == argv_tmp[i])
180 strcpy(nameVal, argv_tmp[i] + strlen(nameId));
181 scannerName = nameVal;
183 ROS_INFO(
"Program arguments: %s", argv_tmp[i]);
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 ...
int writeToFileNameWhenBufferIsFull(std::string filename)
static DataDumper & instance()
void setVersionInfo(std::string _versionInfo)