YARP
Yet Another Robot Platform
Rangefinder2D_nws_yarp.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_YARP, "yarp.devices.Rangefinder2D_nws_yarp")
22 
23 
24 
30  sens_p(nullptr),
31  iTimed(nullptr),
32  _period(DEFAULT_THREAD_PERIOD),
33  minAngle(0),
34  maxAngle(0),
35  minDistance(0),
36  maxDistance(0),
37  resolution(0),
38  isDeviceOwned(false)
39 {}
40 
42 {
43  sens_p = nullptr;
44 }
45 
51 {
52  if (driver->isValid())
53  {
54  driver->view(sens_p);
55  driver->view(iTimed);
56  }
57 
58  if (nullptr == sens_p)
59  {
60  yCError(RANGEFINDER2D_NWS_YARP, "subdevice passed to attach method is invalid");
61  return false;
62  }
63  attach(sens_p);
64 
65  if(!sens_p->getDistanceRange(minDistance, maxDistance))
66  {
67  yCError(RANGEFINDER2D_NWS_YARP) << "Laser device does not provide min & max distance range.";
68  return false;
69  }
70 
71  if(!sens_p->getScanLimits(minAngle, maxAngle))
72  {
73  yCError(RANGEFINDER2D_NWS_YARP) << "Laser device does not provide min & max angle scan range.";
74  return false;
75  }
76 
77  if (!sens_p->getHorizontalResolution(resolution))
78  {
79  yCError(RANGEFINDER2D_NWS_YARP) << "Laser device does not provide horizontal resolution ";
80  return false;
81  }
82 
83  PeriodicThread::setPeriod(_period);
84  return PeriodicThread::start();
85 }
86 
88 {
89  sens_p = s;
90 }
91 
93 {
94  if (PeriodicThread::isRunning())
95  {
96  PeriodicThread::stop();
97  }
98  sens_p = nullptr;
99  return true;
100 }
101 
103 {
104  yarp::os::Bottle in;
105  yarp::os::Bottle out;
106  bool ok = in.read(connection);
107  if (!ok) {
108  return false;
109  }
110 
111  // parse in, prepare out
112  int action = in.get(0).asVocab32();
113  int inter = in.get(1).asVocab32();
114  bool ret = false;
115 
116  if (inter == VOCAB_ILASER2D)
117  {
118  if (action == VOCAB_GET)
119  {
120  int cmd = in.get(2).asVocab32();
121  if (cmd == VOCAB_DEVICE_INFO)
122  {
123  if (sens_p)
124  {
125  std::string info;
126  if (sens_p->getDeviceInfo(info))
127  {
128  out.addVocab32(VOCAB_IS);
129  out.addVocab32(cmd);
130  out.addString(info);
131  ret = true;
132  }
133  else
134  {
135  ret = false;
136  }
137  }
138  }
139  else if (cmd == VOCAB_LASER_DISTANCE_RANGE)
140  {
141  if (sens_p)
142  {
143  double max = 0;
144  double min = 0;
145  if (sens_p->getDistanceRange(min, max))
146  {
147  out.addVocab32(VOCAB_IS);
148  out.addVocab32(cmd);
149  out.addFloat64(min);
150  out.addFloat64(max);
151  ret = true;
152  }
153  else
154  {
155  ret = false;
156  }
157  }
158  }
159  else if (cmd == VOCAB_LASER_ANGULAR_RANGE)
160  {
161  if (sens_p)
162  {
163  double max = 0;
164  double min = 0;
165  if (sens_p->getScanLimits(min, max))
166  {
167  out.addVocab32(VOCAB_IS);
168  out.addVocab32(cmd);
169  out.addFloat64(min);
170  out.addFloat64(max);
171  ret = true;
172  }
173  else
174  {
175  ret = false;
176  }
177  }
178  }
179  else if (cmd == VOCAB_LASER_ANGULAR_STEP)
180  {
181  if (sens_p)
182  {
183  double step = 0;
184  if (sens_p->getHorizontalResolution(step))
185  {
186  out.addVocab32(VOCAB_IS);
187  out.addVocab32(cmd);
188  out.addFloat64(step);
189  ret = true;
190  }
191  else
192  {
193  ret = false;
194  }
195  }
196  }
197  else if (cmd == VOCAB_LASER_SCAN_RATE)
198  {
199  if (sens_p)
200  {
201  double rate = 0;
202  if (sens_p->getScanRate(rate))
203  {
204  out.addVocab32(VOCAB_IS);
205  out.addVocab32(cmd);
206  out.addFloat64(rate);
207  ret = true;
208  }
209  else
210  {
211  ret = false;
212  }
213  }
214  }
215  else
216  {
217  yCError(RANGEFINDER2D_NWS_YARP, "Invalid command received in Rangefinder2D_nws_yarp");
218  }
219  }
220  else if (action == VOCAB_SET)
221  {
222  int cmd = in.get(2).asVocab32();
223  if (cmd == VOCAB_LASER_DISTANCE_RANGE)
224  {
225  if (sens_p)
226  {
227  double min = in.get(3).asInt32();
228  double max = in.get(4).asInt32();
229  sens_p->setDistanceRange(min, max);
230  ret = true;
231  }
232  }
233  else if (cmd == VOCAB_LASER_ANGULAR_RANGE)
234  {
235  if (sens_p)
236  {
237  double min = in.get(3).asInt32();
238  double max = in.get(4).asInt32();
239  sens_p->setScanLimits(min, max);
240  ret = true;
241  }
242  }
243  else if (cmd == VOCAB_LASER_SCAN_RATE)
244  {
245  if (sens_p)
246  {
247  double rate = in.get(3).asInt32();
248  sens_p->setScanRate(rate);
249  ret = true;
250  }
251  }
252  else if (cmd == VOCAB_LASER_ANGULAR_STEP)
253  {
254  if (sens_p)
255  {
256  double step = in.get(3).asFloat64();
257  sens_p->setHorizontalResolution(step);
258  ret = true;
259  }
260  }
261  else
262  {
263  yCError(RANGEFINDER2D_NWS_YARP, "Invalid command received in Rangefinder2D_nws_yarp");
264  }
265  }
266  else
267  {
268  yCError(RANGEFINDER2D_NWS_YARP, "Invalid action received in Rangefinder2D_nws_yarp");
269  }
270  }
271  else
272  {
273  yCError(RANGEFINDER2D_NWS_YARP, "Invalid interface vocab received in Rangefinder2D_nws_yarp");
274  }
275 
276  if (!ret)
277  {
278  out.clear();
280  }
281 
282  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
283  if (returnToSender != nullptr) {
284  out.write(*returnToSender);
285  }
286  return true;
287 }
288 
290 {
291  return true;
292 }
293 
295 {
296  Property params;
297  params.fromString(config.toString());
298 
299  if (!config.check("period"))
300  {
301  yCError(RANGEFINDER2D_NWS_YARP) << "missing 'period' parameter. Check you configuration file\n";
302  return false;
303  } else {
304  _period = config.find("period").asFloat64();
305  }
306 
307  if (!config.check("name"))
308  {
309  yCError(RANGEFINDER2D_NWS_YARP) << "Rangefinder2D_nws_yarp: missing 'name' parameter. Check you configuration file; it must be like:";
310  yCError(RANGEFINDER2D_NWS_YARP) << " name: full name of the port, like /robotName/deviceId/sensorType:o";
311  return false;
312  }
313  else
314  {
315  streamingPortName = config.find("name").asString();
316  rpcPortName = streamingPortName + "/rpc:i";
317  }
318 
319  if (config.check("frame_id"))
320  {
321  frame_id = config.find("frame_id").asString();
322  }
323 
324  if(!initialize_YARP(config) )
325  {
326  yCError(RANGEFINDER2D_NWS_YARP) << streamingPortName << "Error initializing YARP ports";
327  return false;
328  }
329 
330  if(config.check("subdevice"))
331  {
332  Property p;
333  p.fromString(config.toString(), false);
334  p.put("device", config.find("subdevice").asString());
335 
336  if(!m_driver.open(p) || !m_driver.isValid())
337  {
338  yCError(RANGEFINDER2D_NWS_YARP) << "failed to open subdevice.. check params";
339  return false;
340  }
341 
342  if(!attach(&m_driver))
343  {
344  yCError(RANGEFINDER2D_NWS_YARP) << "failed to open subdevice.. check params";
345  return false;
346  }
347  isDeviceOwned = true;
348  }
349  return true;
350 }
351 
352 bool Rangefinder2D_nws_yarp::initialize_YARP(yarp::os::Searchable &params)
353 {
354  if (!streamingPort.open(streamingPortName))
355  {
356  yCError(RANGEFINDER2D_NWS_YARP, "failed to open port %s", streamingPortName.c_str());
357  return false;
358  }
359  if (!rpcPort.open(rpcPortName))
360  {
361  yCError(RANGEFINDER2D_NWS_YARP, "failed to open port %s", rpcPortName.c_str());
362  return false;
363  }
364  rpcPort.setReader(*this);
365  return true;
366 }
367 
369 {
370  streamingPort.interrupt();
371  streamingPort.close();
372  rpcPort.interrupt();
373  rpcPort.close();
374 }
375 
377 {
378  if (sens_p!=nullptr)
379  {
380  bool ret = true;
382  yarp::sig::Vector ranges;
383  ret &= sens_p->getRawData(ranges);
384  ret &= sens_p->getDeviceStatus(status);
385 
386  if (ret)
387  {
388  if (iTimed) {
389  lastStateStamp = iTimed->getLastInputStamp();
390  } else {
391  lastStateStamp.update(yarp::os::Time::now());
392  }
393 
394  int ranges_size = ranges.size();
395  YARP_UNUSED(ranges_size);
396 
397  yarp::dev::LaserScan2D& b = streamingPort.prepare();
398  //b.clear();
399  b.scans=ranges;
400  b.angle_min= minAngle;
401  b.angle_max= maxAngle;
402  b.range_min= minDistance;
403  b.range_max= maxDistance;
404  b.status=status;
405  streamingPort.setEnvelope(lastStateStamp);
406  streamingPort.write();
407 
408  }
409  else
410  {
411  yCError(RANGEFINDER2D_NWS_YARP, "%s: Sensor returned error", streamingPortName.c_str());
412  }
413  }
414 }
415 
417 {
418  yCTrace(RANGEFINDER2D_NWS_YARP, "Rangefinder2D_nws_yarp::Close");
419  if (PeriodicThread::isRunning())
420  {
421  PeriodicThread::stop();
422  }
423 
424  detach();
425  return true;
426 }
define control board standard interfaces
constexpr yarp::conf::vocab32_t VOCAB_IS
Definition: GenericVocabs.h:14
constexpr yarp::conf::vocab32_t VOCAB_GET
Definition: GenericVocabs.h:13
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:16
constexpr yarp::conf::vocab32_t VOCAB_SET
Definition: GenericVocabs.h:12
constexpr yarp::conf::vocab32_t VOCAB_LASER_ANGULAR_RANGE
constexpr yarp::conf::vocab32_t VOCAB_LASER_SCAN_RATE
constexpr yarp::conf::vocab32_t VOCAB_ILASER2D
constexpr yarp::conf::vocab32_t VOCAB_LASER_DISTANCE_RANGE
constexpr yarp::conf::vocab32_t VOCAB_DEVICE_INFO
constexpr yarp::conf::vocab32_t VOCAB_LASER_ANGULAR_STEP
bool ret
constexpr double DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RANGEFINDER2D_NWS_YARP()
rangefinder2D_nws_yarp: A Network grabber for 2D Rangefinder devices. This device will stream data on...
void run() override
Loop function.
void threadRelease() override
Release method.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
void attach(yarp::dev::IRangefinder2D *s)
bool threadInit() override
Initialization method.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool close() override
Close the DeviceDriver.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:74
A generic interface for planar laser range finders.
yarp::sig::Vector scans
the scan data, measured in [m].
Definition: LaserScan2D.h:47
std::int32_t status
Definition: LaserScan2D.h:48
double angle_min
first angle of the scan [deg]
Definition: LaserScan2D.h:31
double angle_max
last angle of the scan [deg]
Definition: LaserScan2D.h:35
double range_min
the minimum distance of the scan [m]
Definition: LaserScan2D.h:39
double range_max
the maximum distance of the scan [m]
Definition: LaserScan2D.h:43
A container for a device driver.
Definition: PolyDriver.h:24
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:164
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:240
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition: Bottle.cpp:158
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:230
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
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 yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:228
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
size_t size() const
Definition: Vector.h:323
#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
#define YARP_UNUSED(var)
Definition: api.h:162