YARP
Yet Another Robot Platform
Rangefinder2D_nws_ros.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: LGPL-2.1-or-later
4  */
5 
6 #define _USE_MATH_DEFINES
7 
9 
10 #include <yarp/os/LogStream.h>
11 
13 
14 #include <cmath>
15 #include <sstream>
16 
17 using namespace yarp::sig;
18 using namespace yarp::dev;
19 using namespace yarp::os;
20 
21 YARP_LOG_COMPONENT(RANGEFINDER2D_NWS_ROS, "yarp.devices.rangefinder2D_nws_ros")
22 
23 
24 
30  node(nullptr),
31  msgCounter(0),
32  sens_p(nullptr),
33  iTimed(nullptr),
34  _period(DEFAULT_THREAD_PERIOD),
35  minAngle(0),
36  maxAngle(0),
37  minDistance(0),
38  maxDistance(0),
39  resolution(0),
40  isDeviceOwned(false)
41 {}
42 
44 {
45  sens_p = nullptr;
46 }
47 
48 bool Rangefinder2D_nws_ros::checkROSParams(yarp::os::Searchable &config)
49 {
50  // check for ROS_nodeName parameter
51  if (!config.check("node_name"))
52  {
53  yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find node_name parameter, mandatory when using ROS message";
54  return false;
55  }
56  nodeName = config.find("node_name").asString();
57  if(nodeName[0] != '/'){
58  yCError(RANGEFINDER2D_NWS_ROS) << "node_name must begin with an initial /";
59  return false;
60  }
61  yCInfo(RANGEFINDER2D_NWS_ROS) << "node_name is " << nodeName;
62 
63  // check for ROS_topicName parameter
64  if (!config.check("topic_name"))
65  {
66  yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find topic_name parameter";
67  return false;
68  }
69  topicName = config.find("topic_name").asString();
70  if(topicName[0] != '/'){
71  yCError(RANGEFINDER2D_NWS_ROS) << "topic_name parameter must begin with an initial /";
72  return false;
73  }
74  yCInfo(RANGEFINDER2D_NWS_ROS) << "topic_name is " << topicName;
75 
76  // check for frame_id parameter
77  if (!config.check("frame_id"))
78  {
79  yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find frame_id parameter, mandatory when using ROS message";
80  return false;
81  }
82  frame_id = config.find("frame_id").asString();
83  yCInfo(RANGEFINDER2D_NWS_ROS) << "Frame_id is " << frame_id;
84 
85  return true;
86 }
87 
88 bool Rangefinder2D_nws_ros::initialize_ROS()
89 {
90  node = new yarp::os::Node(nodeName); // add a ROS node
91  if (node == nullptr)
92  {
93  yCError(RANGEFINDER2D_NWS_ROS) << " opening " << nodeName << " Node, check your yarp-ROS network configuration\n";
94  return false;
95  }
96  if (!publisherPort.topic(topicName))
97  {
98  yCError(RANGEFINDER2D_NWS_ROS) << " opening " << topicName << " Topic, check your yarp-ROS network configuration\n";
99  return false;
100  }
101  return true;
102 }
103 
109 {
110  if (driver->isValid())
111  {
112  driver->view(sens_p);
113  driver->view(iTimed);
114  }
115 
116  if (nullptr == sens_p)
117  {
118  yCError(RANGEFINDER2D_NWS_ROS, "Rangefinder2DWrapper: subdevice passed to attach method is invalid");
119  return false;
120  }
121  attach(sens_p);
122 
123  if(!sens_p->getDistanceRange(minDistance, maxDistance))
124  {
125  yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide min & max distance range.";
126  return false;
127  }
128 
129  if(!sens_p->getScanLimits(minAngle, maxAngle))
130  {
131  yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide min & max angle scan range.";
132  return false;
133  }
134 
135  if (!sens_p->getHorizontalResolution(resolution))
136  {
137  yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide horizontal resolution ";
138  return false;
139  }
140 
141  PeriodicThread::setPeriod(_period);
142  return PeriodicThread::start();
143 }
144 
146 {
147  sens_p = s;
148 }
149 
151 {
152  if (PeriodicThread::isRunning())
153  {
154  PeriodicThread::stop();
155  }
156  sens_p = nullptr;
157  return true;
158 }
159 
161 {
162  return true;
163 }
164 
166 {
167  Property params;
168  params.fromString(config.toString());
169 
170  if (!config.check("period"))
171  {
172  yCError(RANGEFINDER2D_NWS_ROS) << "Rangefinder2DWrapper: missing 'period' parameter. Check you configuration file\n";
173  return false;
174  }
175  _period = config.find("period").asFloat64();
176 
177  checkROSParams(config);
178 
179  // call ROS node/topic initialization, if needed
180  if (!initialize_ROS())
181  {
182  return false;
183  }
184 
185  if(config.check("subdevice"))
186  {
187  Property p;
188  p.fromString(config.toString(), false);
189  p.put("device", config.find("subdevice").asString());
190 
191  if(!m_driver.open(p) || !m_driver.isValid())
192  {
193  yCError(RANGEFINDER2D_NWS_ROS) << "failed to open subdevice.. check params";
194  return false;
195  }
196 
197  if(!attach(&m_driver))
198  {
199  yCError(RANGEFINDER2D_NWS_ROS) << "failed to open subdevice.. check params";
200  return false;
201  }
202  isDeviceOwned = true;
203  }
204  return true;
205 }
206 
207 
209 {
210  publisherPort.close();
211 }
212 
214 {
215  if (sens_p!=nullptr)
216  {
217  bool ret = true;
219  yarp::sig::Vector ranges;
220  ret &= sens_p->getRawData(ranges);
221  ret &= sens_p->getDeviceStatus(status);
222 
223  if (ret)
224  {
225  if (iTimed) {
226  lastStateStamp = iTimed->getLastInputStamp();
227  } else {
228  lastStateStamp.update(yarp::os::Time::now());
229  }
230 
231  int ranges_size = ranges.size();
232 
233  // publish ROS topic if required
234  yarp::rosmsg::sensor_msgs::LaserScan &rosData = publisherPort.prepare();
235  rosData.header.seq = msgCounter++;
236  rosData.header.stamp = lastStateStamp.getTime();
237  rosData.header.frame_id = frame_id;
238 
239  rosData.angle_min = minAngle * M_PI / 180.0;
240  rosData.angle_max = maxAngle * M_PI / 180.0;
241  rosData.angle_increment = resolution * M_PI / 180.0;
242  rosData.time_increment = 0; // all points in a single scan are considered took at the very same time
243  rosData.scan_time = getPeriod(); // time elapsed between two successive readings
244  rosData.range_min = minDistance;
245  rosData.range_max = maxDistance;
246  rosData.ranges.resize(ranges_size);
247  rosData.intensities.resize(ranges_size);
248 
249  for (int i = 0; i < ranges_size; i++)
250  {
251  // in yarp, NaN is used when a scan value is missing. For example when the angular range of the rangefinder is smaller than 360.
252  // is ros, NaN is not used. Hence this check replaces NaN with inf.
253  if (std::isnan(ranges[i]))
254  {
255  rosData.ranges[i] = std::numeric_limits<double>::infinity();
256  rosData.intensities[i] = 0.0;
257  }
258  else
259  {
260  rosData.ranges[i] = ranges[i];
261  rosData.intensities[i] = 0.0;
262  }
263  }
264  publisherPort.write();
265  }
266  else
267  {
268  yCError(RANGEFINDER2D_NWS_ROS, "Rangefinder2D_nws_ros: %s: Sensor returned error", topicName.c_str());
269  }
270  }
271 }
272 
274 {
275  yCTrace(RANGEFINDER2D_NWS_ROS, "Rangefinder2DWrapperROSROS::Close");
276  if (PeriodicThread::isRunning())
277  {
278  PeriodicThread::stop();
279  }
280  if(node!=nullptr) {
281  node->interrupt();
282  delete node;
283  node = nullptr;
284  }
285 
286  detach();
287  return true;
288 }
define control board standard interfaces
bool ret
constexpr double DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RANGEFINDER2D_NWS_ROS()
rangefinder2D_nws_ros: A Network grabber for 2D Rangefinder devices. This device will publish data on...
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
bool detach() override
Detach the object (you must have first called attach).
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
void attach(yarp::dev::IRangefinder2D *s)
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:74
A generic interface for planar laser range finders.
A container for a device driver.
Definition: PolyDriver.h:24
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
A class for storing options and configuration information.
Definition: Property.h:34
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
yarp::conf::float32_t range_min
Definition: LaserScan.h:64
yarp::conf::float32_t scan_time
Definition: LaserScan.h:63
yarp::conf::float32_t angle_min
Definition: LaserScan.h:59
yarp::conf::float32_t angle_increment
Definition: LaserScan.h:61
std::vector< yarp::conf::float32_t > intensities
Definition: LaserScan.h:67
std::vector< yarp::conf::float32_t > ranges
Definition: LaserScan.h:66
yarp::rosmsg::std_msgs::Header header
Definition: LaserScan.h:58
yarp::conf::float32_t time_increment
Definition: LaserScan.h:62
yarp::conf::float32_t range_max
Definition: LaserScan.h:65
yarp::conf::float32_t angle_max
Definition: LaserScan.h:60
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
size_t size() const
Definition: Vector.h:323
#define M_PI
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
An interface for the device drivers.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:22