YARP
Yet Another Robot Platform
LaserFromRosTopic.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 "LaserFromRosTopic.h"
22 
23 #include <yarp/os/Time.h>
24 #include <yarp/os/Log.h>
25 #include <yarp/os/LogStream.h>
26 #include <yarp/os/ResourceFinder.h>
27 #include <yarp/math/Math.h>
28 
29 #include <cmath>
30 #include <cstring>
31 #include <cstdlib>
32 #include <iostream>
33 #include <limits>
34 #include <mutex>
35 
36 using namespace std;
37 using namespace yarp::os;
38 using namespace yarp::dev;
39 
40 #ifndef DEG2RAD
41 #define DEG2RAD M_PI/180.0
42 #endif
43 
44 #ifndef RAD2DEG
45 #define RAD2DEG 180/M_PI
46 #endif
47 
48 YARP_LOG_COMPONENT(LASER_FROM_ROS_TOPIC, "yarp.devices.laserFromRosTopic")
49 
50 /*
51 
52 yarpdev --device transformServer --ROS::enable_ros_publisher 0 --ROS::enable_ros_subscriber 1
53 
54 yarpdev --device Rangefinder2DWrapper --subdevice laserFromRosTopic \
55 --SENSOR::input_topics_name "(/base_scan)" \
56 --TRANSFORM_CLIENT::local /LaserFromRosTopic/tfClient \
57 --TRANSFORM_CLIENT::remote /transformServer \
58 --TRANSFORMS::src_frames "(/frame1)" \
59 --TRANSFORMS::dst_frame /output_frame \
60 --period 10 \
61 --SENSOR::min_angle 0 \
62 --SENSOR::max_angle 360 \
63 --SENSOR::resolution 0.5 \
64 --name /outlaser:o
65 
66 yarpdev --device Rangefinder2DWrapper --subdevice laserFromRosTopic \
67 --SENSOR::min_angle 0 \
68 --SENSOR::max_angle 360 \
69 --SENSOR::resolution 0.5 \
70 --SENSOR::input_topics_name "(/topic1 /topic2)" \
71 --TRANSFORM_CLIENT::local /LaserFromRosTopic/tfClient \
72 --TRANSFORM_CLIENT::remote /transformServer \
73 --TRANSFORMS::src_frames "(/frame1 /frame2)" \
74 --TRANSFORMS::dst_frame /output_frame \
75 --period 10 \
76 --name /outlaser:o
77 */
78 
79 double constrainAngle(double x)
80 {
81  x = fmod(x, 360);
82  if (x < 0)
83  x += 360;
84  return x;
85 }
86 
88 {
89  m_contains_data=false;
90 }
91 
93 {
94  m_port_mutex.lock();
95  m_lastScan.angle_max = b.angle_max;
96  m_lastScan.angle_min = b.angle_min;
97  m_lastScan.range_max = b.range_max;
98  m_lastScan.range_min = b.range_min;
99  size_t ros_size = b.ranges.size();
100  if (ros_size != m_lastScan.scans.size())
101  {
102  m_lastScan.scans.resize (ros_size);
103  }
104  for (size_t i = 0; i < ros_size; i++)
105  {
106  m_lastScan.scans[i] = b.ranges[i];
107  }
108  getEnvelope(m_lastStamp);
109  m_contains_data=true;
110  m_port_mutex.unlock();
111 }
112 
114 {
115  //this blocks untils the first data is received;
116  size_t counter =0;
117  while (m_contains_data==false)
118  {
120  if (counter++ > 100) {yDebug() << "Waiting for incoming data..."; counter=0;}
121  }
122 
123  m_port_mutex.lock();
124  data = m_lastScan;
125  stmp = m_lastStamp;
126  m_port_mutex.unlock();
127 }
128 
129 //-------------------------------------------------------------------------------------
130 
132 {
133  Property subConfig;
134  m_info = "LaserFromRosTopic device";
135 
136 #ifdef LASER_DEBUG
137  yCDebug(LASER_FROM_ROS_TOPIC) << "%s\n", config.toString().c_str());
138 #endif
139 
140  if (this->parseConfiguration(config) == false)
141  {
142  yCError(LASER_FROM_ROS_TOPIC) << "Error parsing parameters";
143  return false;
144  }
145 
146  yarp::os::Searchable& general_config = config.findGroup("SENSOR");
147 
148  if (general_config.check("input_topics_name")) //this parameter is optional
149  {
150  yarp::os::Bottle* portlist = general_config.find("input_topics_name").asList();
151  if (portlist)
152  {
153  for (size_t i = 0; i < portlist->size(); i++)
154  m_port_names.push_back(portlist->get(i).asString());
155  }
156  else
157  {
158  m_port_names.push_back("/laserFromExternalPort:i");
159  }
160 
161  for (size_t i = 0; i < m_port_names.size(); i++)
162  {
163  InputPortProcessor proc;
164  m_input_ports.push_back(proc);
165  }
166  m_last_stamp.resize(m_port_names.size());
167  m_last_scan_data.resize(m_port_names.size());
168  }
169 
170  if (general_config.check("base_type")) //this parameter is optional
171  {
172  string bt = general_config.find("base_type").asString();
173  if (bt=="infinity") { m_base_type = base_enum::BASE_IS_INF; }
174  else if (bt=="nan") { m_base_type = base_enum::BASE_IS_NAN; }
175  else if (bt=="zero") {m_base_type = base_enum::BASE_IS_ZERO;}
176  else { yCError(LASER_FROM_ROS_TOPIC) << "Invalid value of param base_type"; return false;
177  }
178  }
179 
180  //set the base value
181  m_empty_laser_data = m_laser_data;
182  if (m_base_type == base_enum::BASE_IS_INF)
183  {
184  for (size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::numeric_limits<double>::infinity();
185  }
186  else if (m_base_type == base_enum::BASE_IS_NAN)
187  {
188  for (size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::nanf("");
189  }
190  else if (m_base_type == base_enum::BASE_IS_ZERO)
191  {
192  for (size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = 0;
193  }
194  else
195  {
196  yCError(LASER_FROM_ROS_TOPIC) << "Invalid m_base_type";
197  return false;
198  }
199 
200  if (general_config.check("override")) //this parameter is optional
201  {
202  if (m_input_ports.size() != 1)
203  {
204  yCError(LASER_FROM_ROS_TOPIC) << "option override cannot be used when multiple ports are involved";
205  return false;
206  }
207  else
208  {
209  m_option_override_limits = true;
210  }
211  }
212 
213  //open the tc client
214  if (config.check("TRANSFORMS") && config.check("TRANSFORM_CLIENT"))
215  {
216  yarp::os::Searchable& transforms_config = config.findGroup("TRANSFORMS");
217  yarp::os::Bottle* src_frames_list = transforms_config.find("src_frames").asList();
218  if (src_frames_list)
219  {
220  if (src_frames_list->size() != m_input_ports.size())
221  {
222  yCError(LASER_FROM_ROS_TOPIC) << "src_frames invalid number";
223  return false;
224  }
225  for (size_t i = 0; i < src_frames_list->size(); i++)
226  {
227  m_src_frame_id.push_back(src_frames_list->get(i).asString());
228  }
229  }
230  else
231  {
232  yCError(LASER_FROM_ROS_TOPIC) << "src_frames invalid value or param not found";
233  return false;
234  }
235  m_dst_frame_id = transforms_config.find("dst_frame").asString();
236  if (m_dst_frame_id=="")
237  {
238  yCError(LASER_FROM_ROS_TOPIC) << "dst_frame param not found";
239  return false;
240  }
241 
242 
243  std::string client_cfg_string = config.findGroup("TRANSFORM_CLIENT").toString();
244  if (client_cfg_string=="")
245  {
246  yCError(LASER_FROM_ROS_TOPIC) << "TRANSFORM_CLIENT param not found";
247  return false;
248  }
249 
250  Property tcprop;
251  tcprop.fromString(client_cfg_string);
252  tcprop.put("device", "transformClient");
253 
254  m_tc_driver.open(tcprop);
255  if (!m_tc_driver.isValid())
256  {
257  yCError(LASER_FROM_ROS_TOPIC) << "Error opening PolyDriver check parameters";
258  return false;
259  }
260  m_tc_driver.view(m_iTc);
261  if (!m_iTc)
262  {
263  yCError(LASER_FROM_ROS_TOPIC) << "Error opening iFrameTransform interface. Device not available";
264  return false;
265  }
267  }
268 
269  m_ros_node = new yarp::os::Node("/laserFromRosTopicNode");
270  for (size_t i = 0; i < m_input_ports.size(); i++)
271  {
272  //m_input_ports[i].useCallback(); ///@@@<-SEGFAULT
273  if (m_input_ports[i].topic(m_port_names[i]) == false)
274  {
275  yCError(LASER_FROM_ROS_TOPIC) << "Error opening port:" << m_port_names[i];
276  return false;
277  }
278  m_input_ports[i].useCallback();
279  }
280  PeriodicThread::start();
281 
282  yInfo("LaserFromRosTopic: Sensor ready");
283  return true;
284 }
285 
287 {
288  PeriodicThread::stop();
289 
290  for (auto it=m_input_ports.begin(); it!= m_input_ports.end(); it++)
291  {
292  it->close();
293  }
294  if (m_ros_node) { delete m_ros_node; m_ros_node = nullptr; }
295 
296  yCInfo(LASER_FROM_ROS_TOPIC) << "LaserFromRosTopic closed";
297  return true;
298 }
299 
300 
301 
302 bool LaserFromRosTopic::setDistanceRange(double min, double max)
303 {
304  std::lock_guard<std::mutex> guard(m_mutex);
305  m_min_distance = min;
306  m_max_distance = max;
307  return true;
308 }
309 
310 bool LaserFromRosTopic::setScanLimits(double min, double max)
311 {
312  std::lock_guard<std::mutex> guard(m_mutex);
313  yCWarning(LASER_FROM_ROS_TOPIC) << "setScanLimits not yet implemented";
314  return true;
315 }
316 
317 
318 
320 {
321  std::lock_guard<std::mutex> guard(m_mutex);
322  yCWarning(LASER_FROM_ROS_TOPIC, "setHorizontalResolution not yet implemented");
323  return true;
324 }
325 
327 {
328  std::lock_guard<std::mutex> guard(m_mutex);
329  yCWarning(LASER_FROM_ROS_TOPIC, "setScanRate not yet implemented");
330  return false;
331 }
332 
333 
334 
336 {
337 #ifdef LASER_DEBUG
338  yCDebug(LASER_FROM_ROS_TOPIC) <<"LaserFromRosTopic:: thread initialising...\n");
339  yCDebug(LASER_FROM_ROS_TOPIC) <<"... done!\n");
340 #endif
341 
342  return true;
343 }
344 
346 {
347  yarp::sig::Vector temp(3);
348  temp = yarp::math::dcm2rpy(m);
349  double t_off_rad = temp[2];
350  double x_off = m[0][3];
351  double y_off = m[1][3];
352 
353 #ifdef DO_NOTHING_DEBUG
354  double x_off = 0;
355  double y_off = 0;
356  double t_off_deg = 0;
357  double t_off_rad = 0;
358 #endif
359 
361  double resolution = (scan_data.angle_max - scan_data.angle_min)/ scan_data.scans.size(); // deg/elem
362  for (size_t i = 0; i < scan_data.scans.size(); i++)
363  {
364  double distance = scan_data.scans[i];
365  if (distance == std::numeric_limits<double>::infinity())
366  {
367  distance = 100;
368  }
369  if (std::isnan(distance))
370  {
371  //skip nan
372  }
373  else
374  {
375  //if we received a valid value, process it and put it in the right slot
376  double angle_input_deg = (i * resolution) + scan_data.angle_min;
377  double angle_input_rad = (angle_input_deg) * DEG2RAD;
378 
379  //calculate vertical and horizontal components of input angle
380  double Ay = (sin(angle_input_rad + t_off_rad) * distance);
381  double Ax = (cos(angle_input_rad + t_off_rad) * distance);
382 
383  //calculate vertical and horizontal components of new angle with offset.
384  double By = Ay + y_off;
385  double Bx = Ax + x_off;
386 
387  double angle_output_rad = atan2(By, Bx); //the output is (-pi +pi)
388  double angle_output_deg = angle_output_rad * RAD2DEG; //the output is (-180 +180)
389  angle_output_deg = constrainAngle(angle_output_deg); //the output is (0 360(
390 
391  //check if angle is inside the min max limits of the target vector, otherwise skip it
392  if (angle_output_deg > m_max_angle) { continue; }
393  if (angle_output_deg < m_min_angle) { continue; }
394 
395  //compute the new slot
396  int new_i = lrint ((angle_output_deg - m_min_angle) / m_resolution);
397  if (new_i == static_cast<int>(m_laser_data.size())) {new_i=0;}
398 
399  yAssert (new_i >= 0);
400  yAssert (new_i < static_cast<int>(m_laser_data.size()));
401 
402  //compute the distance
403  double newdistance = std::sqrt((Bx * Bx) + (By * By));
404 
405  //assignment on empty (nan) slots or in valid slots if distance is shorter
406  if (std::isnan(m_laser_data[new_i]))
407  {
408  m_laser_data[new_i] = newdistance;
409  }
410  else if (newdistance < m_laser_data[new_i])
411  {
412  m_laser_data[new_i] = newdistance;
413  }
414  }
415  }
416 }
417 
419 {
420 #ifdef DEBUG_TIMING
421  double t1 = yarp::os::Time::now();
422 #endif
423  std::lock_guard<std::mutex> guard(m_mutex);
424  m_laser_data = m_empty_laser_data;
425 
426  size_t nports= m_input_ports.size();
427  if (nports == 1) //one single port, optimes version
428  {
429  m_input_ports[0].getLast(m_last_scan_data[0], m_last_stamp[0]);
430  size_t received_scans = m_last_scan_data[0].scans.size();
431 
432  if (m_option_override_limits)
433  {
434  //this overrides user setting with parameters received from the port
435  m_sensorsNum = received_scans;
436  m_max_angle = m_last_scan_data[0].angle_max;
437  m_min_angle = m_last_scan_data[0].angle_min;
438  m_max_distance = m_last_scan_data[0].range_max;
439  m_min_distance = m_last_scan_data[0].range_min;
440  m_resolution = received_scans / (m_max_angle - m_min_angle);
441  if (m_laser_data.size() != m_sensorsNum) m_laser_data.resize(m_sensorsNum);
442  }
443 
444  if (m_iTc==nullptr)
445  {
446  for (size_t elem = 0; elem < m_sensorsNum; elem++)
447  {
448  m_laser_data[elem] = m_last_scan_data[0].scans[elem]; //m
449  }
450  }
451  else
452  {
453  yarp::sig::Matrix m(4, 4); m.eye();
454  bool frame_exists = m_iTc->getTransform(m_src_frame_id[0], m_dst_frame_id, m);
455  if (frame_exists == false)
456  {
457  yCWarning(LASER_FROM_ROS_TOPIC) << "Unable to found m matrix" << "and" << m_dst_frame_id;
458  }
459  calculate(m_last_scan_data[0], m);
460  }
461  }
462  else //multiple ports
463  {
464  for (size_t i = 0; i < nports; i++)
465  {
466  yarp::sig::Matrix m(4, 4); m.eye();
467  bool frame_exists = m_iTc->getTransform(m_src_frame_id[i], m_dst_frame_id, m);
468  if (frame_exists == false)
469  {
470  yCWarning(LASER_FROM_ROS_TOPIC) << "Unable to found m matrix between" << "and" << m_dst_frame_id;
471  }
472  m_input_ports[i].getLast(m_last_scan_data[i], m_last_stamp[i]);
473  calculate(m_last_scan_data[i], m);
474  }
475  }
476 
477  applyLimitsOnLaserData();
478 
479  return;
480 }
481 
483 {
484 #ifdef LASER_DEBUG
485  yCDebug(LASER_FROM_ROS_TOPIC) <<"Thread releasing...");
486  yCDebug(LASER_FROM_ROS_TOPIC) <<"... done.");
487 #endif
488 
489  return;
490 }
LogStream.h
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
LaserFromRosTopic::setScanRate
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
Definition: LaserFromRosTopic.cpp:326
yarp::os::Bottle::toString
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:214
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
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::os::Bottle::size
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:254
yarp::dev::LaserScan2D::angle_max
double angle_max
last angle of the scan [deg]
Definition: LaserScan2D.h:38
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
InputPortProcessor
Definition: AnalogSensorClient.h:30
yarp::math::dcm2rpy
yarp::sig::Vector dcm2rpy(const yarp::sig::Matrix &R)
Converts a dcm (direction cosine matrix) rotation matrix to roll-pitch-yaw angles (defined in Math....
Definition: math.cpp:780
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_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
RAD2DEG
#define RAD2DEG
Definition: LaserFromRosTopic.cpp:45
yarp::dev::LaserScan2D
Definition: LaserScan2D.h:28
InputPortProcessor::onRead
void onRead(yarp::sig::Vector &v) override
Definition: AnalogSensorClient.cpp:52
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
InputPortProcessor::InputPortProcessor
InputPortProcessor()
Definition: AnalogSensorClient.cpp:46
yarp::sig::VectorOf< double >
Log.h
yarp::rosmsg::sensor_msgs::LaserScan::angle_max
yarp::conf::float32_t angle_max
Definition: LaserScan.h:63
LASER_FROM_ROS_TOPIC
const yarp::os::LogComponent & LASER_FROM_ROS_TOPIC()
Definition: LaserFromRosTopic.cpp:48
LaserFromRosTopic::setDistanceRange
bool setDistanceRange(double min, double max) override
set the device detection range.
Definition: LaserFromRosTopic.cpp:302
LaserFromRosTopic::close
bool close() override
Close the DeviceDriver.
Definition: LaserFromRosTopic.cpp:286
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
InputPortProcessor::getLast
int getLast(yarp::sig::Vector &data, yarp::os::Stamp &stmp)
Definition: AnalogSensorClient.cpp:104
LaserFromRosTopic::run
void run() override
Loop function.
Definition: LaserFromRosTopic.cpp:418
Math.h
LaserFromRosTopic::threadRelease
void threadRelease() override
Release method.
Definition: LaserFromRosTopic.cpp:482
BASE_IS_ZERO
@ BASE_IS_ZERO
Definition: laserFromExternalPort.h:46
yarp::sig::Matrix::eye
const Matrix & eye()
Build an identity matrix, don't resize.
Definition: Matrix.cpp:429
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
LaserFromRosTopic::setHorizontalResolution
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
Definition: LaserFromRosTopic.cpp:319
yarp::rosmsg::sensor_msgs::LaserScan::range_max
yarp::conf::float32_t range_max
Definition: LaserScan.h:68
LaserFromRosTopic::open
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: LaserFromRosTopic.cpp:131
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
BASE_IS_NAN
@ BASE_IS_NAN
Definition: laserFromExternalPort.h:44
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
yarp::os::Node
The Node class.
Definition: Node.h:27
DEG2RAD
#define DEG2RAD
Definition: LaserFromRosTopic.cpp:41
BASE_IS_INF
@ BASE_IS_INF
Definition: laserFromExternalPort.h:45
yarp::rosmsg::sensor_msgs::LaserScan::ranges
std::vector< yarp::conf::float32_t > ranges
Definition: LaserScan.h:69
yarp::rosmsg::sensor_msgs::LaserScan::range_min
yarp::conf::float32_t range_min
Definition: LaserScan.h:67
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
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
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
yInfo
#define yInfo(...)
Definition: Log.h:260
yDebug
#define yDebug(...)
Definition: Log.h:237
yarp::os::Value::asList
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:243
yarp::rosmsg::sensor_msgs::LaserScan::angle_min
yarp::conf::float32_t angle_min
Definition: LaserScan.h:62
Time.h
yarp::sig::VectorOf::size
size_t size() const
Definition: Vector.h:355
LaserFromRosTopic::threadInit
bool threadInit() override
Initialization method.
Definition: LaserFromRosTopic.cpp:335
LaserFromRosTopic.h
yarp::rosmsg::sensor_msgs::LaserScan
Definition: LaserScan.h:59
yarp::dev::LaserScan2D::scans
yarp::sig::Vector scans
the scan data, measured in [m].
Definition: LaserScan2D.h:50
yAssert
#define yAssert(x)
Definition: Log.h:297
LaserFromRosTopic::setScanLimits
bool setScanLimits(double min, double max) override
set the scan angular range.
Definition: LaserFromRosTopic.cpp:310
yarp::os::Time::delay
void delay(double seconds)
Wait for a certain number of seconds.
Definition: Time.cpp:114
constrainAngle
double constrainAngle(double x)
Definition: LaserFromRosTopic.cpp:79
ResourceFinder.h
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
LaserFromRosTopic::calculate
void calculate(yarp::dev::LaserScan2D scan, yarp::sig::Matrix m)
Definition: LaserFromRosTopic.cpp:345
yarp::sig::Matrix
A class for a Matrix.
Definition: Matrix.h:46