YARP
Yet Another Robot Platform
Rangefinder2DWrapper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #define _USE_MATH_DEFINES
20 
21 #include "Rangefinder2DWrapper.h"
23 #include <yarp/os/LogStream.h>
24 
25 #include <cmath>
26 #include <sstream>
27 
28 using namespace yarp::sig;
29 using namespace yarp::dev;
30 using namespace yarp::os;
31 using namespace std;
32 
33 YARP_LOG_COMPONENT(RANGEFINDER2DWRAPPER, "yarp.devices.Rangefinder2DWrapper")
34 
35 
36 
42  partName("Rangefinder2DWrapper"),
43  sens_p(nullptr),
44  iTimed(nullptr),
45  _period(DEFAULT_THREAD_PERIOD),
46  minAngle(0),
47  maxAngle(0),
48  minDistance(0),
49  maxDistance(0),
50  resolution(0),
51  isDeviceOwned(false),
52  // init ROS data
53  useROS(ROS_disabled),
54  frame_id(""),
55  rosNodeName(""),
56  rosTopicName(""),
57  rosNode(nullptr),
58  rosMsgCounter(0)
59 {}
60 
62 {
63  sens_p = nullptr;
64 }
65 
66 bool Rangefinder2DWrapper::checkROSParams(yarp::os::Searchable &config)
67 {
68  // check for ROS parameter group
69  if (!config.check("ROS"))
70  {
71  useROS = ROS_disabled;
72  yCInfo(RANGEFINDER2DWRAPPER) << "No ROS group found in config file ... skipping ROS initialization.";
73  return true;
74  }
75 
76  yCInfo(RANGEFINDER2DWRAPPER) << "ROS group was FOUND in config file.";
77 
78  Bottle &rosGroup = config.findGroup("ROS");
79  if (rosGroup.isNull())
80  {
81  yCError(RANGEFINDER2DWRAPPER) << partName << "ROS group params is not a valid group or empty";
82  useROS = ROS_config_error;
83  return false;
84  }
85 
86  // check for useROS parameter
87  if (!rosGroup.check("useROS"))
88  {
89  yCError(RANGEFINDER2DWRAPPER) << partName << " cannot find useROS parameter, mandatory when using ROS message. \n \
90  Allowed values are true, false, ROS_only";
91  useROS = ROS_config_error;
92  return false;
93  }
94  std::string ros_use_type = rosGroup.find("useROS").asString();
95  if (ros_use_type == "false")
96  {
97  yCInfo(RANGEFINDER2DWRAPPER) << partName << "useROS topic if set to 'false'";
98  useROS = ROS_disabled;
99  return true;
100  }
101  else if (ros_use_type == "true")
102  {
103  yCInfo(RANGEFINDER2DWRAPPER) << partName << "useROS topic if set to 'true'";
104  useROS = ROS_enabled;
105  }
106  else if (ros_use_type == "only")
107  {
108  yCInfo(RANGEFINDER2DWRAPPER) << partName << "useROS topic if set to 'only";
109  useROS = ROS_only;
110  }
111  else
112  {
113  yCInfo(RANGEFINDER2DWRAPPER) << partName << "useROS parameter is set to invalid value ('" << ros_use_type << "'), supported values are 'true', 'false', 'only'";
114  useROS = ROS_config_error;
115  return false;
116  }
117 
118  // check for ROS_nodeName parameter
119  if (!rosGroup.check("ROS_nodeName"))
120  {
121  yCError(RANGEFINDER2DWRAPPER) << partName << " cannot find ROS_nodeName parameter, mandatory when using ROS message";
122  useROS = ROS_config_error;
123  return false;
124  }
125  rosNodeName = rosGroup.find("ROS_nodeName").asString(); // TODO: check name is correct
126  yCInfo(RANGEFINDER2DWRAPPER) << partName << "rosNodeName is " << rosNodeName;
127 
128  // check for ROS_topicName parameter
129  if (!rosGroup.check("ROS_topicName"))
130  {
131  yCError(RANGEFINDER2DWRAPPER) << partName << " cannot find ROS_topicName parameter, mandatory when using ROS message";
132  useROS = ROS_config_error;
133  return false;
134  }
135  rosTopicName = rosGroup.find("ROS_topicName").asString();
136  yCInfo(RANGEFINDER2DWRAPPER) << partName << "rosTopicName is " << rosTopicName;
137 
138  // check for frame_id parameter
139  if (!rosGroup.check("frame_id"))
140  {
141  yCError(RANGEFINDER2DWRAPPER) << partName << " cannot find frame_id parameter, mandatory when using ROS message";
142  useROS = ROS_config_error;
143  return false;
144  }
145  frame_id = rosGroup.find("frame_id").asString();
146  yCInfo(RANGEFINDER2DWRAPPER) << partName << "frame_id is " << frame_id;
147 
148  return true;
149 }
150 
151 bool Rangefinder2DWrapper::initialize_ROS()
152 {
153  bool success = false;
154  switch (useROS)
155  {
156  case ROS_enabled:
157  case ROS_only:
158  {
159  rosNode = new yarp::os::Node(rosNodeName); // add a ROS node
160  if (rosNode == nullptr)
161  {
162  yCError(RANGEFINDER2DWRAPPER) << " opening " << rosNodeName << " Node, check your yarp-ROS network configuration\n";
163  success = false;
164  break;
165  }
166  if (!rosPublisherPort.topic(rosTopicName))
167  {
168  yCError(RANGEFINDER2DWRAPPER) << " opening " << rosTopicName << " Topic, check your yarp-ROS network configuration\n";
169  success = false;
170  break;
171  }
172  success = true;
173  } break;
174 
175  case ROS_disabled:
176  {
177  yCInfo(RANGEFINDER2DWRAPPER) << partName << ": no ROS initialization required";
178  success = true;
179  } break;
180 
181  case ROS_config_error:
182  {
183  yCError(RANGEFINDER2DWRAPPER) << partName << " ROS parameter are not correct, check your configuration file";
184  success = false;
185  } break;
186 
187  default:
188  {
189  yCError(RANGEFINDER2DWRAPPER) << partName << " something went wrong with ROS configuration, we should never be here!!!";
190  success = false;
191  } break;
192  }
193  return success;
194 }
195 
201 {
202  if (device2attach.size() != 1)
203  {
204  yCError(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper: cannot attach more than one device");
205  return false;
206  }
207 
208  yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly;
209 
210  if (Idevice2attach->isValid())
211  {
212  Idevice2attach->view(sens_p);
213  Idevice2attach->view(iTimed);
214  }
215 
216  if (nullptr == sens_p)
217  {
218  yCError(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper: subdevice passed to attach method is invalid");
219  return false;
220  }
221  attach(sens_p);
222 
223  if(!sens_p->getDistanceRange(minDistance, maxDistance))
224  {
225  yCError(RANGEFINDER2DWRAPPER) << "Laser device does not provide min & max distance range.";
226  return false;
227  }
228 
229  if(!sens_p->getScanLimits(minAngle, maxAngle))
230  {
231  yCError(RANGEFINDER2DWRAPPER) << "Laser device does not provide min & max angle scan range.";
232  return false;
233  }
234 
235  if (!sens_p->getHorizontalResolution(resolution))
236  {
237  yCError(RANGEFINDER2DWRAPPER) << "Laser device does not provide horizontal resolution ";
238  return false;
239  }
240 
241  PeriodicThread::setPeriod(_period);
242  return PeriodicThread::start();
243 }
244 
246 {
247  if (PeriodicThread::isRunning())
248  {
249  PeriodicThread::stop();
250  }
251  sens_p = nullptr;
252  return true;
253 }
254 
256 {
257  sens_p = s;
258 }
259 
261 {
262  if (PeriodicThread::isRunning())
263  {
264  PeriodicThread::stop();
265  }
266  sens_p = nullptr;
267 }
268 
269 bool Rangefinder2DWrapper::read(yarp::os::ConnectionReader& connection)
270 {
271  yarp::os::Bottle in;
272  yarp::os::Bottle out;
273  bool ok = in.read(connection);
274  if (!ok) return false;
275 
276  // parse in, prepare out
277  int action = in.get(0).asVocab();
278  int inter = in.get(1).asVocab();
279  bool ret = false;
280 
281  if (inter == VOCAB_ILASER2D)
282  {
283  if (action == VOCAB_GET)
284  {
285  int cmd = in.get(2).asVocab();
286  if (cmd == VOCAB_DEVICE_INFO)
287  {
288  if (sens_p)
289  {
290  std::string info;
291  if (sens_p->getDeviceInfo(info))
292  {
293  out.addVocab(VOCAB_IS);
294  out.addVocab(cmd);
295  out.addString(info);
296  ret = true;
297  }
298  else
299  {
300  ret = false;
301  }
302  }
303  }
304  else if (cmd == VOCAB_LASER_DISTANCE_RANGE)
305  {
306  if (sens_p)
307  {
308  double max = 0;
309  double min = 0;
310  if (sens_p->getDistanceRange(min, max))
311  {
312  out.addVocab(VOCAB_IS);
313  out.addVocab(cmd);
314  out.addFloat64(min);
315  out.addFloat64(max);
316  ret = true;
317  }
318  else
319  {
320  ret = false;
321  }
322  }
323  }
324  else if (cmd == VOCAB_LASER_ANGULAR_RANGE)
325  {
326  if (sens_p)
327  {
328  double max = 0;
329  double min = 0;
330  if (sens_p->getScanLimits(min, max))
331  {
332  out.addVocab(VOCAB_IS);
333  out.addVocab(cmd);
334  out.addFloat64(min);
335  out.addFloat64(max);
336  ret = true;
337  }
338  else
339  {
340  ret = false;
341  }
342  }
343  }
344  else if (cmd == VOCAB_LASER_ANGULAR_STEP)
345  {
346  if (sens_p)
347  {
348  double step = 0;
349  if (sens_p->getHorizontalResolution(step))
350  {
351  out.addVocab(VOCAB_IS);
352  out.addVocab(cmd);
353  out.addFloat64(step);
354  ret = true;
355  }
356  else
357  {
358  ret = false;
359  }
360  }
361  }
362  else if (cmd == VOCAB_LASER_SCAN_RATE)
363  {
364  if (sens_p)
365  {
366  double rate = 0;
367  if (sens_p->getScanRate(rate))
368  {
369  out.addVocab(VOCAB_IS);
370  out.addVocab(cmd);
371  out.addFloat64(rate);
372  ret = true;
373  }
374  else
375  {
376  ret = false;
377  }
378  }
379  }
380  else
381  {
382  yCError(RANGEFINDER2DWRAPPER, "Invalid command received in Rangefinder2DWrapper");
383  }
384  }
385  else if (action == VOCAB_SET)
386  {
387  int cmd = in.get(2).asVocab();
388  if (cmd == VOCAB_LASER_DISTANCE_RANGE)
389  {
390  if (sens_p)
391  {
392  double min = in.get(3).asInt32();
393  double max = in.get(4).asInt32();
394  sens_p->setDistanceRange(min, max);
395  ret = true;
396  }
397  }
398  else if (cmd == VOCAB_LASER_ANGULAR_RANGE)
399  {
400  if (sens_p)
401  {
402  double min = in.get(3).asInt32();
403  double max = in.get(4).asInt32();
404  sens_p->setScanLimits(min, max);
405  ret = true;
406  }
407  }
408  else if (cmd == VOCAB_LASER_SCAN_RATE)
409  {
410  if (sens_p)
411  {
412  double rate = in.get(3).asInt32();
413  sens_p->setScanRate(rate);
414  ret = true;
415  }
416  }
417  else if (cmd == VOCAB_LASER_ANGULAR_STEP)
418  {
419  if (sens_p)
420  {
421  double step = in.get(3).asFloat64();
422  sens_p->setHorizontalResolution(step);
423  ret = true;
424  }
425  }
426  else
427  {
428  yCError(RANGEFINDER2DWRAPPER, "Invalid command received in Rangefinder2DWrapper");
429  }
430  }
431  else
432  {
433  yCError(RANGEFINDER2DWRAPPER, "Invalid action received in Rangefinder2DWrapper");
434  }
435  }
436  else
437  {
438  yCError(RANGEFINDER2DWRAPPER, "Invalid interface vocab received in Rangefinder2DWrapper");
439  }
440 
441  if (!ret)
442  {
443  out.clear();
444  out.addVocab(VOCAB_FAILED);
445  }
446 
447  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
448  if (returnToSender != nullptr) {
449  out.write(*returnToSender);
450  }
451  return true;
452 }
453 
455 {
456  return true;
457 }
458 
459 void Rangefinder2DWrapper::setId(const std::string &id)
460 {
461  sensorId=id;
462 }
463 
465 {
466  return sensorId;
467 }
468 
469 
471 {
472  Property params;
473  params.fromString(config.toString());
474 
475  if (!config.check("period"))
476  {
477  yCError(RANGEFINDER2DWRAPPER) << "Rangefinder2DWrapper: missing 'period' parameter. Check you configuration file\n";
478  return false;
479  }
480  else
481  _period = config.find("period").asInt32() / 1000.0;
482 
483  if (!config.check("name"))
484  {
485  yCError(RANGEFINDER2DWRAPPER) << "Rangefinder2DWrapper: missing 'name' parameter. Check you configuration file; it must be like:";
486  yCError(RANGEFINDER2DWRAPPER) << " name: full name of the port, like /robotName/deviceId/sensorType:o";
487  return false;
488  }
489  else
490  {
491  streamingPortName = config.find("name").asString();
492  rpcPortName = streamingPortName + "/rpc:i";
493  setId("Rangefinder2DWrapper");
494  }
495 
496  checkROSParams(config);
497 
498  if(!initialize_YARP(config) )
499  {
500  yCError(RANGEFINDER2DWRAPPER) << sensorId << "Error initializing YARP ports";
501  return false;
502  }
503 
504 
505  // call ROS node/topic initialization, if needed
506  if (!initialize_ROS())
507  {
508  return false;
509  }
510 
511  if(config.check("subdevice"))
512  {
513  Property p;
514  PolyDriverList driverlist;
515  p.fromString(config.toString(), false);
516  p.put("device", config.find("subdevice").asString());
517 
518  if(!driver.open(p) || !driver.isValid())
519  {
520  yCError(RANGEFINDER2DWRAPPER) << "RangeFinder2DWrapper: failed to open subdevice.. check params";
521  return false;
522  }
523 
524  driverlist.push(&driver, "1");
525  if(!attachAll(driverlist))
526  {
527  yCError(RANGEFINDER2DWRAPPER) << "RangeFinder2DWrapper: failed to open subdevice.. check params";
528  return false;
529  }
530  isDeviceOwned = true;
531  }
532  return true;
533 }
534 
535 bool Rangefinder2DWrapper::initialize_YARP(yarp::os::Searchable &params)
536 {
537  if(useROS != ROS_only)
538  {
539  if (!streamingPort.open(streamingPortName))
540  {
541  yCError(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper: failed to open port %s", streamingPortName.c_str());
542  return false;
543  }
544  if (!rpcPort.open(rpcPortName))
545  {
546  yCError(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper: failed to open port %s", rpcPortName.c_str());
547  return false;
548  }
549  rpcPort.setReader(*this);
550  }
551  return true;
552 }
553 
555 {
556  streamingPort.interrupt();
557  streamingPort.close();
558  rpcPort.interrupt();
559  rpcPort.close();
560 }
561 
563 {
564  if (sens_p!=nullptr)
565  {
566  bool ret = true;
568  yarp::sig::Vector ranges;
569  ret &= sens_p->getRawData(ranges);
570  ret &= sens_p->getDeviceStatus(status);
571 
572  if (ret)
573  {
574  if(iTimed)
575  lastStateStamp = iTimed->getLastInputStamp();
576  else
577  lastStateStamp.update(yarp::os::Time::now());
578 
579  int ranges_size = ranges.size();
580 
581  yarp::dev::LaserScan2D& b = streamingPort.prepare();
582  //b.clear();
583  b.scans=ranges;
584  b.angle_min= minAngle;
585  b.angle_max= maxAngle;
586  b.range_min= minDistance;
587  b.range_max= maxDistance;
588  b.status=status;
589  streamingPort.setEnvelope(lastStateStamp);
590  streamingPort.write();
591 
592  // publish ROS topic if required
593  if (useROS != ROS_disabled)
594  {
595  yarp::rosmsg::sensor_msgs::LaserScan &rosData = rosPublisherPort.prepare();
596  rosData.header.seq = rosMsgCounter++;
597  rosData.header.stamp = lastStateStamp.getTime();
598  rosData.header.frame_id = frame_id;
599 
600  rosData.angle_min = minAngle * M_PI / 180.0;
601  rosData.angle_max = maxAngle * M_PI / 180.0;
602  rosData.angle_increment = resolution * M_PI / 180.0;
603  rosData.time_increment = 0; // all points in a single scan are considered took at the very same time
604  rosData.scan_time = getPeriod(); // time elapsed between two successive readings
605  rosData.range_min = minDistance;
606  rosData.range_max = maxDistance;
607  rosData.ranges.resize(ranges_size);
608  rosData.intensities.resize(ranges_size);
609 
610  for (int i = 0; i < ranges_size; i++)
611  {
612  // in yarp, NaN is used when a scan value is missing. For example when the angular range of the rangefinder is smaller than 360.
613  // is ros, NaN is not used. Hence this check replaces NaN with inf.
614  if (std::isnan(ranges[i]))
615  {
616  rosData.ranges[i] = std::numeric_limits<double>::infinity();
617  rosData.intensities[i] = 0.0;
618  }
619  else
620  {
621  rosData.ranges[i] = ranges[i];
622  rosData.intensities[i] = 0.0;
623  }
624  }
625  rosPublisherPort.write();
626  }
627  }
628  else
629  {
630  yCError(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper: %s: Sensor returned error", sensorId.c_str());
631  }
632  }
633 }
634 
636 {
637  yCTrace(RANGEFINDER2DWRAPPER, "Rangefinder2DWrapper::Close");
638  if (PeriodicThread::isRunning())
639  {
640  PeriodicThread::stop();
641  }
642  if(rosNode!=nullptr) {
643  rosNode->interrupt();
644  delete rosNode;
645  rosNode = nullptr;
646  }
647 
648  detachAll();
649  return true;
650 }
LogStream.h
ROS_only
@ ROS_only
Definition: yarpRosHelper.h:23
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
yarp::os::Value::asVocab
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:231
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
VOCAB_ILASER2D
constexpr yarp::conf::vocab32_t VOCAB_ILASER2D
Definition: IRangefinder2D.h:19
yarp::os::Bottle::clear
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:124
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::dev::LaserScan2D::angle_max
double angle_max
last angle of the scan [deg]
Definition: LaserScan2D.h:38
yarp::sig
Signal processing.
Definition: Image.h:25
yarp::dev::LaserScan2D::status
std::int32_t status
Definition: LaserScan2D.h:51
Rangefinder2DWrapper::detachAll
bool detachAll() override
Detach the object (you must have first called attach).
Definition: Rangefinder2DWrapper.cpp:245
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
M_PI
#define M_PI
Definition: fakeLocalizerDev.cpp:44
VOCAB_LASER_SCAN_RATE
constexpr yarp::conf::vocab32_t VOCAB_LASER_SCAN_RATE
Definition: IRangefinder2D.h:24
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
yarp::rosmsg::sensor_msgs::LaserScan::time_increment
yarp::conf::float32_t time_increment
Definition: LaserScan.h:65
yarp::dev::PolyDriverList::size
int size() const
Definition: PolyDriverList.cpp:39
yarp::dev::PolyDriver::isValid
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:199
Rangefinder2DWrapper::getId
std::string getId()
Definition: Rangefinder2DWrapper.cpp:464
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::rosmsg::std_msgs::Header::frame_id
std::string frame_id
Definition: Header.h:49
ROS_enabled
@ ROS_enabled
Definition: yarpRosHelper.h:22
VOCAB_GET
constexpr yarp::conf::vocab32_t VOCAB_GET
Definition: GenericVocabs.h:16
yarp::rosmsg::sensor_msgs::LaserScan::scan_time
yarp::conf::float32_t scan_time
Definition: LaserScan.h:66
yarp::dev::IRangefinder2D
A generic interface for planar laser range finders.
Definition: IRangefinder2D.h:38
Rangefinder2DWrapper::open
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Definition: Rangefinder2DWrapper.cpp:470
yarp::dev::LaserScan2D
Definition: LaserScan2D.h:28
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
yarp::dev::IRangefinder2D::Device_status
Device_status
Definition: IRangefinder2D.h:41
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardInterfaces.h
define control board standard interfaces
yarp::os::Bottle::addFloat64
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:161
yarp::os::Bottle::find
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:290
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
Rangefinder2DWrapper::attach
void attach(yarp::dev::IRangefinder2D *s)
Definition: Rangefinder2DWrapper.cpp:255
yarp::dev::PolyDriverList::push
void push(PolyDriver *p, const char *k)
Definition: PolyDriverList.cpp:44
yarp::sig::VectorOf< double >
yarp::os::Bottle::check
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:280
yarp::rosmsg::std_msgs::Header::seq
std::uint32_t seq
Definition: Header.h:47
RANGEFINDER2DWRAPPER
const yarp::os::LogComponent & RANGEFINDER2DWRAPPER()
Definition: Rangefinder2DWrapper.cpp:33
Rangefinder2DWrapper::~Rangefinder2DWrapper
~Rangefinder2DWrapper()
Definition: Rangefinder2DWrapper.cpp:61
VOCAB_SET
constexpr yarp::conf::vocab32_t VOCAB_SET
Definition: GenericVocabs.h:15
Rangefinder2DWrapper::detach
void detach()
Definition: Rangefinder2DWrapper.cpp:260
yarp::rosmsg::sensor_msgs::LaserScan::angle_max
yarp::conf::float32_t angle_max
Definition: LaserScan.h:63
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
yarp::os::Bottle::write
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:233
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
Rangefinder2DWrapper::setId
void setId(const std::string &id)
Definition: Rangefinder2DWrapper.cpp:459
yarp::rosmsg::sensor_msgs::LaserScan::header
yarp::rosmsg::std_msgs::Header header
Definition: LaserScan.h:61
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
Rangefinder2DWrapper::attachAll
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which sensor this thread has to read from.
Definition: Rangefinder2DWrapper.cpp:200
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
yarp::rosmsg::sensor_msgs::LaserScan::range_max
yarp::conf::float32_t range_max
Definition: LaserScan.h:68
VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:19
ROS_disabled
@ ROS_disabled
Definition: yarpRosHelper.h:21
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
rosNode
yarp::os::Node * rosNode
Definition: laserFromPointCloud.cpp:72
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
Rangefinder2DWrapper.h
yarp::os::Node
The Node class.
Definition: Node.h:27
yarp::dev::LaserScan2D::range_max
double range_max
the maximum distance of the scan [m]
Definition: LaserScan2D.h:46
yarp::os::ConnectionReader::getWriter
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
yarp::rosmsg::sensor_msgs::LaserScan::ranges
std::vector< yarp::conf::float32_t > ranges
Definition: LaserScan.h:69
VOCAB_LASER_DISTANCE_RANGE
constexpr yarp::conf::vocab32_t VOCAB_LASER_DISTANCE_RANGE
Definition: IRangefinder2D.h:21
VOCAB_LASER_ANGULAR_STEP
constexpr yarp::conf::vocab32_t VOCAB_LASER_ANGULAR_STEP
Definition: IRangefinder2D.h:23
yarp::os::Bottle::addString
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:173
yarp::rosmsg::sensor_msgs::LaserScan::angle_increment
yarp::conf::float32_t angle_increment
Definition: LaserScan.h:64
yarp::rosmsg::sensor_msgs::LaserScan::intensities
std::vector< yarp::conf::float32_t > intensities
Definition: LaserScan.h:70
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
yarp::os::Bottle::addVocab
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:167
yarp::rosmsg::sensor_msgs::LaserScan::range_min
yarp::conf::float32_t range_min
Definition: LaserScan.h:67
yarp::os::Bottle::isNull
bool isNull() const override
Checks if the object is invalid.
Definition: Bottle.cpp:373
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
Rangefinder2DWrapper::threadInit
bool threadInit() override
Initialization method.
Definition: Rangefinder2DWrapper.cpp:454
yarp::dev::LaserScan2D::angle_min
double angle_min
first angle of the scan [deg]
Definition: LaserScan2D.h:34
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
VOCAB_DEVICE_INFO
constexpr yarp::conf::vocab32_t VOCAB_DEVICE_INFO
Definition: IRangefinder2D.h:20
yarp::os::Value::asInt32
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
Rangefinder2DWrapper::close
bool close() override
Close the DeviceDriver.
Definition: Rangefinder2DWrapper.cpp:635
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD
Definition: AnalogWrapper.h:45
VOCAB_LASER_ANGULAR_RANGE
constexpr yarp::conf::vocab32_t VOCAB_LASER_ANGULAR_RANGE
Definition: IRangefinder2D.h:22
Rangefinder2DWrapper::threadRelease
void threadRelease() override
Release method.
Definition: Rangefinder2DWrapper.cpp:554
yarp::os::Bottle::read
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:243
yarp::os::Node::interrupt
void interrupt()
interrupt delegates the call to the Node port interrupt.
Definition: Node.cpp:600
yarp::rosmsg::sensor_msgs::LaserScan::angle_min
yarp::conf::float32_t angle_min
Definition: LaserScan.h:62
yarp::sig::VectorOf::size
size_t size() const
Definition: Vector.h:355
Rangefinder2DWrapper
Rangefinder2DWrapper: Documentation to be added
Definition: Rangefinder2DWrapper.h:68
yCTrace
#define yCTrace(component,...)
Definition: LogComponent.h:88
VOCAB_IS
constexpr yarp::conf::vocab32_t VOCAB_IS
Definition: GenericVocabs.h:17
yarp::rosmsg::sensor_msgs::LaserScan
Definition: LaserScan.h:59
ROS_config_error
@ ROS_config_error
Definition: yarpRosHelper.h:20
yarp::dev::LaserScan2D::scans
yarp::sig::Vector scans
the scan data, measured in [m].
Definition: LaserScan2D.h:50
yarp::os::Value::asFloat64
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
yarp::rosmsg::std_msgs::Header::stamp
yarp::rosmsg::TickTime stamp
Definition: Header.h:48
yarp::dev::LaserScan2D::range_min
double range_min
the minimum distance of the scan [m]
Definition: LaserScan2D.h:42
Rangefinder2DWrapper::run
void run() override
Loop function.
Definition: Rangefinder2DWrapper.cpp:562
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37