Go to the documentation of this file.
63 #define _WIN32_WINNT 0x0501
64 #pragma warning(disable: 4996)
65 #pragma warning(disable: 4267)
81 #include "sick_scan/rosconsole_simu.hpp"
83 #define _USE_MATH_DEFINES
122 bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
126 pos = tagVal.find(
":=");
129 if (pos == std::string::npos)
135 tag = tagVal.substr(0, pos);
136 val = tagVal.substr(pos + 2);
145 ROS_INFO(
"Caught signal %d\n", signalRecv);
147 ROS_INFO(
"You are leaving the following version of this node:");
175 bool doInternalDebug =
false;
176 bool emulSensor =
false;
177 for (
int i = 0; i < argc; i++)
179 std::string
s = argv[i];
182 if (tag.compare(
"__internalDebug") == 0)
185 sscanf(val.c_str(),
"%d", &debugState);
188 doInternalDebug =
true;
191 if (tag.compare(
"__emulSensor") == 0)
194 sscanf(val.c_str(),
"%d", &dummyState);
209 std::string scannerName;
210 if (
false == nhPriv.
getParam(
"scanner_type", scannerName))
212 ROS_ERROR(
"cannot find parameter ""scanner_type"" in the param set. Please specify scanner_type.");
213 ROS_ERROR(
"Try to set %s as fallback.\n", nodeName.c_str());
214 scannerName = nodeName;
221 nhPriv.
setParam(
"name", scannerName);
222 rossimu_settings(nhPriv);
224 nhPriv.
setParam(
"hostname",
"192.168.0.4");
225 nhPriv.
setParam(
"imu_enable",
true);
226 nhPriv.
setParam(
"cloud_topic",
"pt_cloud");
232 std::string hostname;
233 if (nhPriv.
getParam(
"hostname", hostname))
237 bool changeIP =
false;
239 if (nhPriv.
getParam(
"new_IP_address", sNewIp))
244 nhPriv.
param<std::string>(
"port", port,
"2112");
247 nhPriv.
param(
"timelimit", timelimit, 5);
249 bool subscribe_datagram;
251 nhPriv.
param(
"subscribe_datagram", subscribe_datagram,
false);
252 nhPriv.
param(
"device_number", device_number, 0);
258 char colaDialectId =
'A';
276 bool use_binary_protocol =
true;
277 if (
true == nhPriv.
getParam(
"emul_sensor", emulSensor))
279 ROS_INFO(
"Found emul_sensor overwriting default settings. Emulation: %s", emulSensor ?
"True" :
"False");
281 if (
true == nhPriv.
getParam(
"use_binary_protocol", use_binary_protocol))
283 ROS_INFO(
"Found sopas_protocol_type param overwriting default protocol:");
284 if (use_binary_protocol ==
true)
286 ROS_INFO(
"Binary protocol activated");
292 nhPriv.
setParam(
"sopas_protocol_type",
true);
293 use_binary_protocol =
true;
294 ROS_WARN(
"This scanner type does not support ASCII communication.\n"
295 "Binary communication has been activated.\n"
296 "The parameter \"sopas_protocol_type\" has been set to \"True\".");
300 ROS_INFO(
"ASCII protocol activated");
316 bool start_services =
false;
320 sick_scan::SickScanConfig cfg;
329 ROS_INFO(
"Start initialising scanner [Ip: %s] [Port: %s]", hostname.c_str(), port.c_str());
338 ROS_ERROR(
"TCP is not switched on. Probably hostname or port not set. Use roslaunch to start node.");
350 if (
true == nhPriv.
getParam(
"start_services", start_services) &&
true == start_services)
353 ROS_INFO(
"SickScanServices: ros services initialized");
357 signal(SIGINT, SIG_DFL);
390 ROS_ERROR(
"Invalid run state in main loop");
void setParam(const std::string &key, bool b) const
void run(class_loader::ClassLoader *loader)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
ROSCPP_DECL void spinOnce()
ROSCPP_DECL void shutdown()
void my_handler(int signalRecv)
static bool isInitialized
void setEmulSensor(bool _emulFlag)
Set emulation flag (using emulation instead of "real" scanner - currently implemented for radar.
void set_range_min(float min)
Setting minimum range.
static std::string versionInfo
std::string getVersionInfo()
int mainGenericLaser(int argc, char **argv, std::string nodeName)
Internal Startup routine.
int loopOnce()
parsing datagram and publishing ros messages
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
T param(const std::string ¶m_name, const T &default_val) const
T param(const std::string ¶m_name, const T &default_val)
bool getTagVal(std::string tagVal, std::string &tag, std::string &val)
splitting expressions like <tag>:=into <tag> and
virtual int init()
init routine of scanner
void setVersionInfo(std::string _versionInfo)
static sick_scan::SickScanCommonTcp * s
void set_range_max(float max)
Setting maximum range.
int getNumberOfLayers(void)
Getting number of scanner layers.
void set_time_increment(float time)
setting time increment between shots
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
sick_scan
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19