YARP
Yet Another Robot Platform
Rangefinder2DClient.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 "Rangefinder2DClient.h"
22 
23 #include <yarp/os/Log.h>
24 #include <yarp/os/LogStream.h>
26 #include <yarp/math/Math.h>
28 
29 #include <limits>
30 #include <cmath>
31 
34 using namespace yarp::dev;
35 using namespace yarp::os;
36 using namespace yarp::sig;
37 
38 #ifndef DEG2RAD
39 #define DEG2RAD M_PI/180.0
40 #endif
41 
42 namespace {
43 YARP_LOG_COMPONENT(RANGEFINDER2DCLIENT, "yarp.device.Rangefinder2DClient")
44 }
45 
47 {
48  mutex.lock();
49  count=0;
50  deltaT=0;
51  deltaTMax=0;
52  deltaTMin=1e22;
53  now=SystemClock::nowSystem();
54  prev=now;
55  mutex.unlock();
56 }
57 
59 {
61  resetStat();
62 }
63 
65 {
66  now=SystemClock::nowSystem();
67  mutex.lock();
68 
69  if (count>0)
70  {
71  double tmpDT=now-prev;
72  deltaT+=tmpDT;
73  if (tmpDT>deltaTMax)
74  deltaTMax=tmpDT;
75  if (tmpDT<deltaTMin)
76  deltaTMin=tmpDT;
77 
78  //compare network time
79  if (tmpDT*1000<LASER_TIMEOUT)
80  {
81  state = b.status;
82  }
83  else
84  {
86  }
87  }
88 
89  prev=now;
90  count++;
91 
92  lastScan=b;
93  Stamp newStamp;
94  getEnvelope(newStamp);
95 
96  //initialialization (first received data)
97  if (lastStamp.isValid()==false)
98  {
99  lastStamp = newStamp;
100  }
101 
102  //now compare timestamps
103  if ((1000*(newStamp.getTime()-lastStamp.getTime()))<LASER_TIMEOUT)
104  {
105  state = b.status;
106  }
107  else
108  {
110  }
111  lastStamp = newStamp;
112 
113  mutex.unlock();
114 }
115 
117 {
118  mutex.lock();
119  int ret=state;
121  {
122  data=lastScan;
123  stmp = lastStamp;
124  }
125  mutex.unlock();
126 
127  return ret;
128 }
129 
131 {
132  mutex.lock();
133  ranges= lastScan.scans;
134  mutex.unlock();
135  return true;
136 }
137 
139 {
140  mutex.lock();
141  auto status = (yarp::dev::IRangefinder2D::Device_status) lastScan.status;
142  mutex.unlock();
143  return status;
144 }
145 
147 {
148  mutex.lock();
149  int ret=count;
150  mutex.unlock();
151  return ret;
152 }
153 
154 // time is in ms
155 void Rangefinder2DInputPortProcessor::getEstFrequency(int &ite, double &av, double &min, double &max)
156 {
157  mutex.lock();
158  ite=count;
159  min=deltaTMin*1000;
160  max=deltaTMax*1000;
161  if (count<1)
162  {
163  av=0;
164  }
165  else
166  {
167  av=deltaT/count;
168  }
169  av=av*1000;
170  mutex.unlock();
171 }
172 
174 {
175  local.clear();
176  remote.clear();
177 
178  local = config.find("local").asString();
179  remote = config.find("remote").asString();
180 
181  if (local=="")
182  {
183  yCError(RANGEFINDER2DCLIENT, "open() error you have to provide valid local name");
184  return false;
185  }
186  if (remote=="")
187  {
188  yCError(RANGEFINDER2DCLIENT, "open() error you have to provide valid remote name");
189  return false;
190  }
191 
192  std::string local_rpc = local;
193  local_rpc += "/rpc:o";
194  std::string remote_rpc = remote;
195  remote_rpc += "/rpc:i";
196 
197  if (!inputPort.open(local))
198  {
199  yCError(RANGEFINDER2DCLIENT, "open() error could not open port %s, check network\n",local.c_str());
200  return false;
201  }
202  inputPort.useCallback();
203 
204  if (!rpcPort.open(local_rpc))
205  {
206  yCError(RANGEFINDER2DCLIENT, "open() error could not open rpc port %s, check network\n", local_rpc.c_str());
207  return false;
208  }
209 
210  bool ok=Network::connect(remote.c_str(), local.c_str(), "udp");
211  if (!ok)
212  {
213  yCError(RANGEFINDER2DCLIENT, "open() error could not connect to %s\n", remote.c_str());
214  return false;
215  }
216 
217  ok=Network::connect(local_rpc, remote_rpc);
218  if (!ok)
219  {
220  yCError(RANGEFINDER2DCLIENT, "open() error could not connect to %s\n", remote_rpc.c_str());
221  return false;
222  }
223 
224  //getScanLimits is used here to update the cached values of scan_angle_min, scan_angle_max
225  double tmp_min;
226  double tmp_max;
227  this->getScanLimits(tmp_min, tmp_max);
228 
229  //get the position of the device, if it is available
230  device_position_x = 0;
231  device_position_y = 0;
232  device_position_theta = 0;
233  auto* drv = new yarp::dev::PolyDriver;
234  Property TransformClientOptions;
235  TransformClientOptions.put("device", "transformClient");
236  TransformClientOptions.put("local", "/rangefinder2DTransformClient");
237  TransformClientOptions.put("remote", "/transformServer");
238  TransformClientOptions.put("period", "10");
239 
240  bool b_canOpenTransformClient = false;
241  if (config.check("laser_frame_name") &&
242  config.check("robot_frame_name"))
243  {
244  laser_frame_name = config.find("laser_frame_name").toString();
245  robot_frame_name = config.find("robot_frame_name").toString();
246  b_canOpenTransformClient = drv->open(TransformClientOptions);
247  }
248 
249  if (b_canOpenTransformClient)
250  {
251  yarp::dev::IFrameTransform* iTrf = nullptr;
252  drv->view(iTrf);
253  if (!iTrf)
254  {
255  yCError(RANGEFINDER2DCLIENT) << "A Problem occurred while trying to view the IFrameTransform interface";
256  drv->close();
257  delete drv;
258  return false;
259  }
260 
261  yarp::sig::Matrix mat;
262  iTrf->getTransform(laser_frame_name, robot_frame_name, mat);
264  device_position_x = mat[0][3];
265  device_position_y = mat[1][3];
266  device_position_theta = v[2];
267  if (fabs(v[0]) < 1e-6 && fabs(v[1]) < 1e-6)
268  {
269  yCError(RANGEFINDER2DCLIENT) << "Laser device is not planar";
270  }
271  yCInfo(RANGEFINDER2DCLIENT) << "Position information obtained fromtransform server";
272  drv->close();
273  }
274  else
275  {
276  if (config.check("device_position_x") &&
277  config.check("device_position_y") &&
278  config.check("device_position_theta"))
279  {
280  yCInfo(RANGEFINDER2DCLIENT) << "Position information obtained from configuration parameters";
281  device_position_x = config.find("device_position_x").asFloat64();
282  device_position_y = config.find("device_position_y").asFloat64();
283  device_position_theta = config.find("device_position_theta").asFloat64();
284  }
285  else
286  {
287  yCDebug(RANGEFINDER2DCLIENT) << "No position information provided for this device";
288  }
289  }
290 
291  delete drv;
292  return true;
293 }
294 
296 {
297  rpcPort.close();
298  inputPort.close();
299  return true;
300 }
301 
303 {
304  inputPort.getData(data);
305  return true;
306 }
307 
308 bool Rangefinder2DClient::getLaserMeasurement(std::vector<LaserMeasurementData> &data)
309 {
310  yarp::sig::Vector ranges;
311  inputPort.getData(ranges);
312  size_t size = ranges.size();
313  data.resize(size);
314  if (scan_angle_max < scan_angle_min) { yCError(RANGEFINDER2DCLIENT) << "getLaserMeasurement failed"; return false; }
315  double laser_angle_of_view = scan_angle_max - scan_angle_min;
316  for (size_t i = 0; i < size; i++)
317  {
318  double angle = (i / double(size)*laser_angle_of_view + device_position_theta + scan_angle_min)* DEG2RAD;
319  double value = ranges[i];
320 #if 1 //cartesian version is preferable, even if more computationally expensive, since it takes in account device_position
321  data[i].set_cartesian(value * cos(angle) + device_position_x, value * sin(angle) + device_position_y);
322 #else
323  data[i].set_polar(value,angle);
324 #endif
325  }
326  return true;
327 }
328 
329 bool Rangefinder2DClient::getDistanceRange(double& min, double& max)
330 {
331  Bottle cmd, response;
332  cmd.addVocab(VOCAB_GET);
335  bool ok = rpcPort.write(cmd, response);
336  if (CHECK_FAIL(ok, response) != false)
337  {
338  min = response.get(2).asFloat64();
339  max = response.get(3).asFloat64();
340  return true;
341  }
342  return false;
343 }
344 
345 bool Rangefinder2DClient::setDistanceRange(double min, double max)
346 {
347  Bottle cmd, response;
348  cmd.addVocab(VOCAB_SET);
351  cmd.addFloat64(min);
352  cmd.addFloat64(max);
353  bool ok = rpcPort.write(cmd, response);
354  if (ok)
355  {
356  scan_angle_min = min;
357  scan_angle_max = max;
358  }
359  return (CHECK_FAIL(ok, response));
360 }
361 
362 bool Rangefinder2DClient::getScanLimits(double& min, double& max)
363 {
364  Bottle cmd, response;
365  cmd.addVocab(VOCAB_GET);
368  bool ok = rpcPort.write(cmd, response);
369  if (CHECK_FAIL(ok, response) != false)
370  {
371  min = scan_angle_min = response.get(2).asFloat64();
372  max = scan_angle_max = response.get(3).asFloat64();
373  return true;
374  }
375  return false;
376 }
377 
378 bool Rangefinder2DClient::setScanLimits(double min, double max)
379 {
380  Bottle cmd, response;
381  cmd.addVocab(VOCAB_SET);
384  cmd.addFloat64(min);
385  cmd.addFloat64(max);
386  bool ok = rpcPort.write(cmd, response);
387  return (CHECK_FAIL(ok, response));
388 }
389 
391 {
392  Bottle cmd, response;
393  cmd.addVocab(VOCAB_GET);
396  bool ok = rpcPort.write(cmd, response);
397  if (CHECK_FAIL(ok, response) != false)
398  {
399  step = response.get(2).asFloat64();
400  return true;
401  }
402  return false;
403 }
404 
406 {
407  Bottle cmd, response;
408  cmd.addVocab(VOCAB_SET);
411  cmd.addFloat64(step);
412  bool ok = rpcPort.write(cmd, response);
413  return (CHECK_FAIL(ok, response));
414 }
415 
417 {
418  Bottle cmd, response;
419  cmd.addVocab(VOCAB_GET);
422  bool ok = rpcPort.write(cmd, response);
423  if (CHECK_FAIL(ok, response) != false)
424  {
425  rate = response.get(2).asFloat64();
426  return true;
427  }
428  return false;
429 }
430 
432 {
433  Bottle cmd, response;
434  cmd.addVocab(VOCAB_SET);
437  cmd.addFloat64(rate);
438  bool ok = rpcPort.write(cmd, response);
439  return (CHECK_FAIL(ok, response));
440 }
441 
443 {
444  status = inputPort.getStatus();
445  return true;
446 }
447 
448 bool Rangefinder2DClient::getDeviceInfo(std::string &device_info)
449 {
450  Bottle cmd, response;
451  cmd.addVocab(VOCAB_GET);
454  bool ok = rpcPort.write(cmd, response);
455  if (CHECK_FAIL(ok, response)!=false)
456  {
457  device_info = response.get(2).asString();
458  return true;
459  }
460  return false;
461 }
462 
464 {
465  return lastTs;
466 }
constexpr yarp::conf::vocab32_t VOCAB_GET
Definition: GenericVocabs.h:16
constexpr yarp::conf::vocab32_t VOCAB_SET
Definition: GenericVocabs.h:15
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
#define DEG2RAD
const int LASER_TIMEOUT
bool setDistanceRange(double min, double max) override
set the device detection range.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getHorizontalResolution(double &step) override
get the angular step between two measurments.
bool getScanRate(double &rate) override
get the scan rate (scans per seconds)
yarp::os::Stamp getLastInputStamp() override
Get the time stamp for the last read data.
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
bool close() override
Close the DeviceDriver.
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
bool setScanLimits(double min, double max) override
set the scan angular range.
bool getDistanceRange(double &min, double &max) override
get the device detection range
bool getLaserMeasurement(std::vector< yarp::dev::LaserMeasurementData > &data) override
Get the device measurements.
bool getDeviceStatus(Device_status &status) override
get the device status
bool getRawData(yarp::sig::Vector &data) override
Get the device measurements.
bool getDeviceInfo(std::string &device_info) override
get the device hardware charactestics
bool getScanLimits(double &min, double &max) override
get the scan angular range.
bool getData(yarp::sig::Vector &data)
void getEstFrequency(int &ite, double &av, double &min, double &max)
int getLast(yarp::dev::LaserScan2D &data, yarp::os::Stamp &stmp)
void onRead(yarp::dev::LaserScan2D &v) override
yarp::dev::IRangefinder2D::Device_status getStatus()
Transform Interface.
virtual bool getTransform(const std::string &target_frame_id, const std::string &source_frame_id, yarp::sig::Matrix &transform)=0
Get the transform between two frames.
std::int32_t status
Definition: LaserScan2D.h:51
A container for a device driver.
Definition: PolyDriver.h:27
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
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
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:167
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
A class for storing options and configuration information.
Definition: Property.h:37
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
A base class for nested structures that can be searched.
Definition: Searchable.h:69
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.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:37
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
std::string toString() const override
Return a standard text representation of the content of the object.
Definition: Value.cpp:359
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
A class for a Matrix.
Definition: Matrix.h:46
size_t size() const
Definition: Vector.h:355
#define yCInfo(component,...)
Definition: LogComponent.h:135
#define yCError(component,...)
Definition: LogComponent.h:157
#define yCDebug(component,...)
Definition: LogComponent.h:112
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
An interface for the device drivers.
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
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:25