sick_generic_laser.cpp
Go to the documentation of this file.
1 
62 #ifdef _MSC_VER
63 #define _WIN32_WINNT 0x0501
64 #pragma warning(disable: 4996)
65 #pragma warning(disable: 4267)
66 #endif
67 
68 #ifndef _MSC_VER
69 
70 
71 #endif
72 
74 
77 #ifdef _MSC_VER
78 #include "sick_scan/rosconsole_simu.hpp"
79 #endif
80 #define _USE_MATH_DEFINES
81 
82 #include <math.h>
83 #include <string>
84 #include <stdio.h>
85 #include <stdlib.h>
86 #include <signal.h>
87 
88 static bool isInitialized = false;
90 static std::string versionInfo = "???";
91 
92 void setVersionInfo(std::string _versionInfo)
93 {
94  versionInfo = _versionInfo;
95 }
96 
97 std::string getVersionInfo()
98 {
99 
100  return(versionInfo);
101 }
102 
104 
106 
107 
116 bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
117  {
118  bool ret = false;
119  std::size_t pos;
120  pos = tagVal.find(":=");
121  tag = "";
122  val = "";
123  if (pos == std::string::npos)
124  {
125  ret = false;
126  }
127  else
128  {
129  tag = tagVal.substr(0, pos);
130  val = tagVal.substr(pos + 2);
131  ret = true;
132  }
133  return (ret);
134  }
135 
136 
137 void my_handler(int signalRecv)
138 {
139  ROS_INFO("Caught signal %d\n",signalRecv);
140  ROS_INFO("good bye");
141  ROS_INFO("You are leaving the following version of this node:");
142  ROS_INFO("%s", getVersionInfo().c_str());
143  if (s != NULL)
144  {
145  if (isInitialized)
146  {
147  s->stopScanData();
148  }
149 
151  }
152  ros::shutdown();
153 }
154 
163 int mainGenericLaser(int argc, char **argv, std::string nodeName)
164  {
165  std::string tag;
166  std::string val;
167 
168 
169  bool doInternalDebug = false;
170  bool emulSensor = false;
171  for (int i = 0; i < argc; i++)
172  {
173  std::string s = argv[i];
174  if (getTagVal(s, tag, val))
175  {
176  if (tag.compare("__internalDebug") == 0)
177  {
178  int debugState = 0;
179  sscanf(val.c_str(), "%d", &debugState);
180  if (debugState > 0)
181  {
182  doInternalDebug = true;
183  }
184  }
185  if (tag.compare("__emulSensor") == 0)
186  {
187  int dummyState = 0;
188  sscanf(val.c_str(), "%d", &dummyState);
189  if (dummyState > 0)
190  {
191  emulSensor = true;
192  }
193  }
194  }
195  }
196 
197  ros::init(argc, argv, nodeName, ros::init_options::NoSigintHandler); // scannerName holds the node-name
198  signal (SIGINT,my_handler);
199 
200  ros::NodeHandle nhPriv("~");
201 
202 
203  std::string scannerName;
204  if (false == nhPriv.getParam("scanner_type", scannerName))
205  {
206  ROS_ERROR("cannot find parameter ""scanner_type"" in the param set. Please specify scanner_type.");
207  ROS_ERROR("Try to set %s as fallback.\n", nodeName.c_str());
208  scannerName = nodeName;
209  }
210 
211 
212  if (doInternalDebug)
213  {
214 #ifdef _MSC_VER
215  nhPriv.setParam("name", scannerName);
216  rossimu_settings(nhPriv); // just for tiny simulations under Visual C++
217 #else
218  nhPriv.setParam("hostname", "192.168.0.4");
219  nhPriv.setParam("imu_enable", true);
220  nhPriv.setParam("cloud_topic","pt_cloud");
221 #endif
222  }
223 
224 // check for TCP - use if ~hostname is set.
225  bool useTCP = false;
226  std::string hostname;
227  if (nhPriv.getParam("hostname", hostname))
228  {
229  useTCP = true;
230  }
231  bool changeIP = false;
232  std::string sNewIp;
233  if (nhPriv.getParam("new_IP_address", sNewIp))
234  {
235  changeIP = true;
236  }
237  std::string port;
238  nhPriv.param<std::string>("port", port, "2112");
239 
240  int timelimit;
241  nhPriv.param("timelimit", timelimit, 5);
242 
243  bool subscribe_datagram;
244  int device_number;
245  nhPriv.param("subscribe_datagram", subscribe_datagram, false);
246  nhPriv.param("device_number", device_number, 0);
247 
248 
250 
251  double param;
252  char colaDialectId = 'A'; // A or B (Ascii or Binary)
253 
254  if (nhPriv.getParam("range_min", param))
255  {
256  parser->set_range_min(param);
257  }
258  if (nhPriv.getParam("range_max", param))
259  {
260  parser->set_range_max(param);
261  }
262  if (nhPriv.getParam("time_increment", param))
263  {
264  parser->set_time_increment(param);
265  }
266 
267  /*
268  * Check, if parameter for protocol type is set
269  */
270  bool use_binary_protocol = true;
271  if (true == nhPriv.getParam("emul_sensor", emulSensor))
272  {
273  ROS_INFO("Found emul_sensor overwriting default settings. Emulation: %s\n", emulSensor ? "True" : "False");
274  }
275  if (true == nhPriv.getParam("use_binary_protocol", use_binary_protocol))
276  {
277  ROS_INFO("Found sopas_protocol_type param overwriting default protocol:");
278  if (use_binary_protocol == true)
279  {
280  ROS_INFO("Binary protocol activated");
281  } else
282  {
283  if (parser->getCurrentParamPtr()->getNumberOfLayers() > 4)
284  {
285  nhPriv.setParam("sopas_protocol_type", true);
286  use_binary_protocol = true;
287  ROS_WARN("This scanner type does not support ASCII communication.\n"
288  "Binary communication has been activated.\n"
289  "The parameter \"sopas_protocol_type\" has been set to \"True\".");
290  } else
291  {
292  ROS_INFO("ASCII protocol activated");
293  }
294  }
295  parser->getCurrentParamPtr()->setUseBinaryProtocol(use_binary_protocol);
296  }
297 
298 
299  if (parser->getCurrentParamPtr()->getUseBinaryProtocol())
300  {
301  colaDialectId = 'B';
302  } else
303  {
304  colaDialectId = 'A';
305  }
306 
307 
308  int result = sick_scan::ExitError;
309 
310  sick_scan::SickScanConfig cfg;
311 
312  while (ros::ok())
313  {
314  switch(runState)
315  {
316  case scanner_init:
317  ROS_INFO("Start initialising scanner [Ip: %s] [Port: %s]", hostname.c_str(), port.c_str());
318  // attempt to connect/reconnect
319  delete s; // disconnect scanner
320  if (useTCP)
321  s = new sick_scan::SickScanCommonTcp(hostname, port, timelimit, parser, colaDialectId);
322  else
323  {
324  ROS_ERROR("TCP is not switched on. Probably hostname or port not set. Use roslaunch to start node.");
325  exit(-1);
326  }
327 
328 
329  if (emulSensor)
330  {
331  s->setEmulSensor(true);
332  }
333  result = s->init();
334 
335  isInitialized = true;
336  signal(SIGINT, SIG_DFL); // change back to standard signal handler after initialising
337  if (result == sick_scan::ExitSuccess) // OK -> loop again
338  {
339  if(changeIP)
340  {
342  }
343 
344 
345  runState = scanner_run; // after initialising switch to run state
346  }
347  else
348  {
349  runState = scanner_init; // If there was an error, try to restart scanner
350 
351  }
352  break;
353 
354  case scanner_run:
355  if (result == sick_scan::ExitSuccess) // OK -> loop again
356  {
357  ros::spinOnce();
358  result = s->loopOnce();
359  }
360  else
361  {
362  runState = scanner_finalize; // interrupt
363  }
364  case scanner_finalize:
365  break; // ExitError or similiar -> interrupt while-Loop
366  default:
367  ROS_ERROR("Invalid run state in main loop");
368  break;
369  }
370  }
371  if (s != NULL)
372  {
373  delete s; // close connnect
374  }
375  if (parser != NULL)
376  {
377  delete parser; // close parser
378  }
379  return result;
380 
381  }
void set_range_max(float max)
Setting maximum range.
bool param(const std::string &param_name, T &param_val, const T &default_val)
static std::string versionInfo
std::string getVersionInfo()
static bool isInitialized
NodeRunState runState
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int mainGenericLaser(int argc, char **argv, std::string nodeName)
Internal Startup routine.
void my_handler(int signalRecv)
#define ROS_WARN(...)
int getNumberOfLayers(void)
Getting number of scanner layers.
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
splitting expressions like <tag>:=into <tag> and
ROSCPP_DECL bool ok()
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
bool getParam(const std::string &key, std::string &s) const
void set_time_increment(float time)
setting time increment between shots
parser
void set_range_min(float min)
Setting minimum range.
ROSCPP_DECL void shutdown()
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
static sick_scan::SickScanCommonTcp * s
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