63 #define _WIN32_WINNT 0x0501 64 #pragma warning(disable: 4996) 65 #pragma warning(disable: 4267) 78 #include "sick_scan/rosconsole_simu.hpp" 80 #define _USE_MATH_DEFINES 116 bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
120 pos = tagVal.find(
":=");
123 if (pos == std::string::npos)
129 tag = tagVal.substr(0, pos);
130 val = tagVal.substr(pos + 2);
139 ROS_INFO(
"Caught signal %d\n",signalRecv);
141 ROS_INFO(
"You are leaving the following version of this node:");
169 bool doInternalDebug =
false;
170 bool emulSensor =
false;
171 for (
int i = 0; i < argc; i++)
173 std::string s = argv[i];
176 if (tag.compare(
"__internalDebug") == 0)
179 sscanf(val.c_str(),
"%d", &debugState);
182 doInternalDebug =
true;
185 if (tag.compare(
"__emulSensor") == 0)
188 sscanf(val.c_str(),
"%d", &dummyState);
203 std::string scannerName;
204 if (
false == nhPriv.
getParam(
"scanner_type", scannerName))
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;
215 nhPriv.
setParam(
"name", scannerName);
216 rossimu_settings(nhPriv);
218 nhPriv.
setParam(
"hostname",
"192.168.0.4");
219 nhPriv.
setParam(
"imu_enable",
true);
220 nhPriv.
setParam(
"cloud_topic",
"pt_cloud");
226 std::string hostname;
227 if (nhPriv.
getParam(
"hostname", hostname))
231 bool changeIP =
false;
233 if (nhPriv.
getParam(
"new_IP_address", sNewIp))
238 nhPriv.
param<std::string>(
"port", port,
"2112");
241 nhPriv.
param(
"timelimit", timelimit, 5);
243 bool subscribe_datagram;
245 nhPriv.
param(
"subscribe_datagram", subscribe_datagram,
false);
246 nhPriv.
param(
"device_number", device_number, 0);
252 char colaDialectId =
'A';
254 if (nhPriv.
getParam(
"range_min", param))
258 if (nhPriv.
getParam(
"range_max", param))
262 if (nhPriv.
getParam(
"time_increment", param))
270 bool use_binary_protocol =
true;
271 if (
true == nhPriv.
getParam(
"emul_sensor", emulSensor))
273 ROS_INFO(
"Found emul_sensor overwriting default settings. Emulation: %s\n", emulSensor ?
"True" :
"False");
275 if (
true == nhPriv.
getParam(
"use_binary_protocol", use_binary_protocol))
277 ROS_INFO(
"Found sopas_protocol_type param overwriting default protocol:");
278 if (use_binary_protocol ==
true)
280 ROS_INFO(
"Binary protocol activated");
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\".");
292 ROS_INFO(
"ASCII protocol activated");
310 sick_scan::SickScanConfig cfg;
317 ROS_INFO(
"Start initialising scanner [Ip: %s] [Port: %s]", hostname.c_str(), port.c_str());
324 ROS_ERROR(
"TCP is not switched on. Probably hostname or port not set. Use roslaunch to start node.");
331 s->setEmulSensor(
true);
336 signal(SIGINT, SIG_DFL);
358 result = s->loopOnce();
367 ROS_ERROR(
"Invalid run state in main loop");
void set_range_max(float max)
Setting maximum range.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
static std::string versionInfo
std::string getVersionInfo()
static bool isInitialized
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)
int getNumberOfLayers(void)
Getting number of scanner layers.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
splitting expressions like <tag>:=into <tag> and
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
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()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
static sick_scan::SickScanCommonTcp * s
void setVersionInfo(std::string _versionInfo)