80 #include "sick_scan/rosconsole_simu.hpp" 83 #define MAX_NAME_LEN (1024) 122 #define SICK_GENERIC_MAJOR_VER "1" 123 #define SICK_GENERIC_MINOR_VER "10" 124 #define SICK_GENERIC_PATCH_LEVEL "1" 141 int main(
int argc,
char **argv)
145 char nameId[] =
"__name:=";
149 std::string scannerName =
"????";
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};
166 strcpy(nameTagVal,
"__name:=sick_tim_5xx");
167 strcpy(logTagVal,
"__log:=/tmp/tmp.log");
168 strcpy(internalDebugTagVal,
"__internalDebug:=1");
170 strcpy(sensorEmulVal,
"__emulSensor:=0");
172 argv_tmp = (
char **) malloc(
sizeof(
char *) * argc_tmp);
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;
182 std::string
versionInfo =
"sick_generic_caller V. ";
188 ROS_INFO(
"%s", versionInfo.c_str());
189 for (
int i = 0; i < argc_tmp; i++)
191 if (strstr(argv_tmp[i], nameId) == argv_tmp[i])
193 strcpy(nameVal, argv_tmp[i] + strlen(nameId));
194 scannerName = nameVal;
196 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)