sick_generic_laser.cpp
Go to the documentation of this file.
00001 
00062 #ifdef _MSC_VER
00063 #define _WIN32_WINNT 0x0501
00064 #pragma warning(disable: 4996)
00065 #pragma warning(disable: 4267)
00066 #endif
00067 
00068 #ifndef _MSC_VER
00069 
00070 
00071 #endif
00072 
00073 #include <sick_scan/sick_scan_common_tcp.h>
00074 
00075 #include <sick_scan/sick_generic_parser.h>
00076 #include <sick_scan/sick_generic_laser.h>
00077 #ifdef _MSC_VER
00078 #include "sick_scan/rosconsole_simu.hpp"
00079 #endif
00080 #define _USE_MATH_DEFINES
00081 
00082 #include <math.h>
00083 #include <string>
00084 #include <stdio.h>
00085 #include <stdlib.h>
00086 #include <signal.h>
00087 
00088 static bool isInitialized = false;
00089 static sick_scan::SickScanCommonTcp *s = NULL;
00090 static std::string versionInfo = "???";
00091 
00092 void setVersionInfo(std::string _versionInfo)
00093 {
00094   versionInfo = _versionInfo;
00095 }
00096 
00097 std::string getVersionInfo()
00098 {
00099 
00100   return(versionInfo);
00101 }
00102 
00103 enum NodeRunState { scanner_init, scanner_run, scanner_finalize };
00104 
00105 NodeRunState runState = scanner_init;  //
00106 
00107 
00116 bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
00117   {
00118   bool ret = false;
00119   std::size_t pos;
00120   pos = tagVal.find(":=");
00121   tag = "";
00122   val = "";
00123   if (pos == std::string::npos)
00124   {
00125     ret = false;
00126   }
00127   else
00128   {
00129     tag = tagVal.substr(0, pos);
00130     val = tagVal.substr(pos + 2);
00131     ret = true;
00132   }
00133   return (ret);
00134   }
00135 
00136 
00137 void my_handler(int signalRecv)
00138 {
00139   ROS_INFO("Caught signal %d\n",signalRecv);
00140   ROS_INFO("good bye");
00141   ROS_INFO("You are leaving the following version of this node:");
00142   ROS_INFO("%s", getVersionInfo().c_str());
00143   if (s != NULL)
00144   {
00145     if (isInitialized)
00146     {
00147       s->stopScanData();
00148     }
00149 
00150     runState = scanner_finalize;
00151   }
00152   ros::shutdown();
00153 }
00154 
00163 int mainGenericLaser(int argc, char **argv, std::string nodeName)
00164   {
00165   std::string tag;
00166   std::string val;
00167 
00168 
00169   bool doInternalDebug = false;
00170   bool emulSensor = false;
00171   for (int i = 0; i < argc; i++)
00172   {
00173     std::string s = argv[i];
00174     if (getTagVal(s, tag, val))
00175     {
00176       if (tag.compare("__internalDebug") == 0)
00177       {
00178         int debugState = 0;
00179         sscanf(val.c_str(), "%d", &debugState);
00180         if (debugState > 0)
00181         {
00182           doInternalDebug = true;
00183         }
00184       }
00185       if (tag.compare("__emulSensor") == 0)
00186       {
00187         int dummyState = 0;
00188         sscanf(val.c_str(), "%d", &dummyState);
00189         if (dummyState > 0)
00190         {
00191           emulSensor = true;
00192         }
00193       }
00194     }
00195   }
00196 
00197   ros::init(argc, argv, nodeName, ros::init_options::NoSigintHandler);  // scannerName holds the node-name
00198   signal (SIGINT,my_handler);
00199 
00200   ros::NodeHandle nhPriv("~");
00201 
00202 
00203   std::string scannerName;
00204   if (false == nhPriv.getParam("scanner_type", scannerName))
00205   {
00206     ROS_ERROR("cannot find parameter ""scanner_type"" in the param set. Please specify scanner_type.");
00207     ROS_ERROR("Try to set %s as fallback.\n", nodeName.c_str());
00208     scannerName = nodeName;
00209   }
00210 
00211 
00212   if (doInternalDebug)
00213   {
00214 #ifdef _MSC_VER
00215     nhPriv.setParam("name", scannerName);
00216     rossimu_settings(nhPriv);  // just for tiny simulations under Visual C++
00217 #else
00218     nhPriv.setParam("hostname", "192.168.0.4");
00219     nhPriv.setParam("imu_enable", true);
00220     nhPriv.setParam("cloud_topic","pt_cloud");
00221 #endif
00222   }
00223 
00224 // check for TCP - use if ~hostname is set.
00225   bool useTCP = false;
00226   std::string hostname;
00227   if (nhPriv.getParam("hostname", hostname))
00228   {
00229     useTCP = true;
00230   }
00231   bool changeIP = false;
00232   std::string sNewIp;
00233   if (nhPriv.getParam("new_IP_address", sNewIp))
00234   {
00235     changeIP = true;
00236   }
00237   std::string port;
00238   nhPriv.param<std::string>("port", port, "2112");
00239 
00240   int timelimit;
00241   nhPriv.param("timelimit", timelimit, 5);
00242 
00243   bool subscribe_datagram;
00244   int device_number;
00245   nhPriv.param("subscribe_datagram", subscribe_datagram, false);
00246   nhPriv.param("device_number", device_number, 0);
00247 
00248 
00249   sick_scan::SickGenericParser *parser = new sick_scan::SickGenericParser(scannerName);
00250 
00251   double param;
00252   char colaDialectId = 'A'; // A or B (Ascii or Binary)
00253 
00254   if (nhPriv.getParam("range_min", param))
00255   {
00256     parser->set_range_min(param);
00257   }
00258   if (nhPriv.getParam("range_max", param))
00259   {
00260     parser->set_range_max(param);
00261   }
00262   if (nhPriv.getParam("time_increment", param))
00263   {
00264     parser->set_time_increment(param);
00265   }
00266 
00267   /*
00268    *  Check, if parameter for protocol type is set
00269    */
00270   bool use_binary_protocol = true;
00271   if (true == nhPriv.getParam("emul_sensor", emulSensor))
00272   {
00273     ROS_INFO("Found emul_sensor overwriting default settings. Emulation: %s\n", emulSensor ? "True" : "False");
00274   }
00275   if (true == nhPriv.getParam("use_binary_protocol", use_binary_protocol))
00276   {
00277     ROS_INFO("Found sopas_protocol_type param overwriting default protocol:");
00278     if (use_binary_protocol == true)
00279     {
00280       ROS_INFO("Binary protocol activated");
00281     } else
00282     {
00283       if (parser->getCurrentParamPtr()->getNumberOfLayers() > 4)
00284       {
00285         nhPriv.setParam("sopas_protocol_type", true);
00286         use_binary_protocol = true;
00287         ROS_WARN("This scanner type does not support ASCII communication.\n"
00288                          "Binary communication has been activated.\n"
00289                          "The parameter \"sopas_protocol_type\" has been set to \"True\".");
00290       } else
00291       {
00292         ROS_INFO("ASCII protocol activated");
00293       }
00294     }
00295     parser->getCurrentParamPtr()->setUseBinaryProtocol(use_binary_protocol);
00296   }
00297 
00298 
00299   if (parser->getCurrentParamPtr()->getUseBinaryProtocol())
00300   {
00301     colaDialectId = 'B';
00302   } else
00303   {
00304     colaDialectId = 'A';
00305   }
00306 
00307 
00308   int result = sick_scan::ExitError;
00309 
00310   sick_scan::SickScanConfig cfg;
00311 
00312   while (ros::ok())
00313   {
00314     switch(runState)
00315     {
00316       case scanner_init:
00317         ROS_INFO("Start initialising scanner [Ip: %s] [Port: %s]", hostname.c_str(), port.c_str());
00318         // attempt to connect/reconnect
00319         delete s;  // disconnect scanner
00320         if (useTCP)
00321           s = new sick_scan::SickScanCommonTcp(hostname, port, timelimit, parser, colaDialectId);
00322         else
00323         {
00324           ROS_ERROR("TCP is not switched on. Probably hostname or port not set. Use roslaunch to start node.");
00325           exit(-1);
00326         }
00327 
00328 
00329         if (emulSensor)
00330         {
00331           s->setEmulSensor(true);
00332         }
00333         result = s->init();
00334 
00335         isInitialized = true;
00336         signal(SIGINT, SIG_DFL); // change back to standard signal handler after initialising
00337         if (result == sick_scan::ExitSuccess) // OK -> loop again
00338         {
00339           if(changeIP)
00340           {
00341             runState = scanner_finalize;
00342           }
00343 
00344 
00345           runState = scanner_run; // after initialising switch to run state
00346         }
00347         else
00348         {
00349           runState = scanner_init; // If there was an error, try to restart scanner
00350 
00351         }
00352         break;
00353 
00354       case scanner_run:
00355         if (result == sick_scan::ExitSuccess) // OK -> loop again
00356         {
00357           ros::spinOnce();
00358           result = s->loopOnce();
00359         }
00360         else
00361         {
00362           runState = scanner_finalize; // interrupt
00363         }
00364       case scanner_finalize:
00365         break; // ExitError or similiar -> interrupt while-Loop
00366       default:
00367         ROS_ERROR("Invalid run state in main loop");
00368         break;
00369     }
00370   }
00371   if (s != NULL)
00372   {
00373     delete s; // close connnect
00374   }
00375   if (parser != NULL)
00376   {
00377     delete parser; // close parser
00378   }
00379   return result;
00380 
00381   }


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