YARP
Yet Another Robot Platform
Rangefinder2DClient.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/Log.h>
11#include <yarp/os/LogStream.h>
13#include <yarp/math/Math.h>
15
16#include <limits>
17#include <cmath>
18
21using namespace yarp::dev;
22using namespace yarp::os;
23using namespace yarp::sig;
24
25#ifndef DEG2RAD
26#define DEG2RAD M_PI/180.0
27#endif
28
29namespace {
30YARP_LOG_COMPONENT(RANGEFINDER2DCLIENT, "yarp.device.Rangefinder2DClient")
31}
32
34{
35 mutex.lock();
36 count=0;
37 deltaT=0;
38 deltaTMax=0;
39 deltaTMin=1e22;
40 now=SystemClock::nowSystem();
41 prev=now;
42 mutex.unlock();
43}
44
46{
47 state = IRangefinder2D::DEVICE_GENERAL_ERROR;
48 resetStat();
49}
50
52{
53 now=SystemClock::nowSystem();
54 mutex.lock();
55
56 if (count>0)
57 {
58 double tmpDT=now-prev;
59 deltaT+=tmpDT;
60 if (tmpDT > deltaTMax) {
61 deltaTMax = tmpDT;
62 }
63 if (tmpDT < deltaTMin) {
64 deltaTMin = tmpDT;
65 }
66
67 //compare network time
68 if (tmpDT*1000<LASER_TIMEOUT)
69 {
70 state = b.status;
71 }
72 else
73 {
74 state = IRangefinder2D::DEVICE_TIMEOUT;
75 }
76 }
77
78 prev=now;
79 count++;
80
81 lastScan=b;
82 Stamp newStamp;
83 getEnvelope(newStamp);
84
85 //initialialization (first received data)
86 if (lastStamp.isValid()==false)
87 {
88 lastStamp = newStamp;
89 }
90
91 //now compare timestamps
92 if ((1000*(newStamp.getTime()-lastStamp.getTime()))<LASER_TIMEOUT)
93 {
94 state = b.status;
95 }
96 else
97 {
98 state = IRangefinder2D::DEVICE_TIMEOUT;
99 }
100 lastStamp = newStamp;
101
102 mutex.unlock();
103}
104
106{
107 mutex.lock();
108 int ret=state;
109 if (ret != IRangefinder2D::DEVICE_GENERAL_ERROR)
110 {
111 data=lastScan;
112 stmp = lastStamp;
113 }
114 mutex.unlock();
115
116 return ret;
117}
118
120{
121 mutex.lock();
122 auto status = (yarp::dev::IRangefinder2D::Device_status) lastScan.status;
123 mutex.unlock();
124 return status;
125}
126
128{
129 mutex.lock();
130 int ret=count;
131 mutex.unlock();
132 return ret;
133}
134
135// time is in ms
136void Rangefinder2DInputPortProcessor::getEstFrequency(int &ite, double &av, double &min, double &max)
137{
138 mutex.lock();
139 ite=count;
140 min=deltaTMin*1000;
141 max=deltaTMax*1000;
142 if (count<1)
143 {
144 av=0;
145 }
146 else
147 {
148 av=deltaT/count;
149 }
150 av=av*1000;
151 mutex.unlock();
152}
153
155{
156 local.clear();
157 remote.clear();
158
159 local = config.find("local").asString();
160 remote = config.find("remote").asString();
161
162 m_carrier = config.check("carrier", yarp::os::Value("tcp"), "the carrier used for the connection with the server").asString();
163
164 if (local=="")
165 {
166 yCError(RANGEFINDER2DCLIENT, "open() error you have to provide valid local name");
167 return false;
168 }
169 if (remote=="")
170 {
171 yCError(RANGEFINDER2DCLIENT, "open() error you have to provide valid remote name");
172 return false;
173 }
174
175 std::string local_rpc = local;
176 local_rpc += "/rpc:o";
177 std::string remote_rpc = remote;
178 remote_rpc += "/rpc:i";
179
180 if (!inputPort.open(local))
181 {
182 yCError(RANGEFINDER2DCLIENT, "open() error could not open port %s, check network\n",local.c_str());
183 return false;
184 }
186
187 if (!rpcPort.open(local_rpc))
188 {
189 yCError(RANGEFINDER2DCLIENT, "open() error could not open rpc port %s, check network\n", local_rpc.c_str());
190 return false;
191 }
192
193 bool ok=Network::connect(remote.c_str(), local.c_str(), m_carrier);
194 if (!ok)
195 {
196 yCError(RANGEFINDER2DCLIENT, "open() error could not connect to %s\n", remote.c_str());
197 return false;
198 }
199
200 ok=Network::connect(local_rpc, remote_rpc);
201 if (!ok)
202 {
203 yCError(RANGEFINDER2DCLIENT, "open() error could not connect to %s\n", remote_rpc.c_str());
204 return false;
205 }
206
207 //getScanLimits is used here to update the cached values of scan_angle_min, scan_angle_max
208 double tmp_min;
209 double tmp_max;
210 this->getScanLimits(tmp_min, tmp_max);
211
212 //get the position of the device, if it is available
216 auto* drv = new yarp::dev::PolyDriver;
217 Property TransformClientOptions;
218 TransformClientOptions.put("device", "transformClient");
219 TransformClientOptions.put("local", "/rangefinder2DTransformClient");
220 TransformClientOptions.put("remote", "/transformServer");
221 TransformClientOptions.put("period", "10");
222
223 bool b_canOpenTransformClient = false;
224 if (config.check("laser_frame_name") &&
225 config.check("robot_frame_name"))
226 {
227 laser_frame_name = config.find("laser_frame_name").toString();
228 robot_frame_name = config.find("robot_frame_name").toString();
229 b_canOpenTransformClient = drv->open(TransformClientOptions);
230 }
231
232 if (b_canOpenTransformClient)
233 {
234 yarp::dev::IFrameTransform* iTrf = nullptr;
235 drv->view(iTrf);
236 if (!iTrf)
237 {
238 yCError(RANGEFINDER2DCLIENT) << "A Problem occurred while trying to view the IFrameTransform interface";
239 drv->close();
240 delete drv;
241 return false;
242 }
243
247 device_position_x = mat[0][3];
248 device_position_y = mat[1][3];
250 if (fabs(v[0]) < 1e-6 && fabs(v[1]) < 1e-6)
251 {
252 yCError(RANGEFINDER2DCLIENT) << "Laser device is not planar";
253 }
254 yCInfo(RANGEFINDER2DCLIENT) << "Position information obtained fromtransform server";
255 drv->close();
256 }
257 else
258 {
259 if (config.check("device_position_x") &&
260 config.check("device_position_y") &&
261 config.check("device_position_theta"))
262 {
263 yCInfo(RANGEFINDER2DCLIENT) << "Position information obtained from configuration parameters";
264 device_position_x = config.find("device_position_x").asFloat64();
265 device_position_y = config.find("device_position_y").asFloat64();
266 device_position_theta = config.find("device_position_theta").asFloat64();
267 }
268 else
269 {
270 yCDebug(RANGEFINDER2DCLIENT) << "No position information provided for this device";
271 }
272 }
273
274 delete drv;
275 return true;
276}
277
279{
280 rpcPort.close();
282 return true;
283}
284
286{
288 inputPort.getLast(scan, lastTs);
289
290 data = scan.scans;
291
292 if (timestamp != nullptr)
293 {
294 *timestamp = lastTs.getTime();
295 }
296 return true;
297}
298
299bool Rangefinder2DClient::getLaserMeasurement(std::vector<LaserMeasurementData> &data, double* timestamp)
300{
302 inputPort.getLast(scan, lastTs);
303 size_t size = scan.scans.size();
304 data.resize(size);
305 if (scan_angle_max < scan_angle_min) { yCError(RANGEFINDER2DCLIENT) << "getLaserMeasurement failed"; return false; }
306 double laser_angle_of_view = scan_angle_max - scan_angle_min;
307 for (size_t i = 0; i < size; i++)
308 {
309 double angle = (i / double(size)*laser_angle_of_view + device_position_theta + scan_angle_min)* DEG2RAD;
310 double value = scan.scans[i];
311#if 1 //cartesian version is preferable, even if more computationally expensive, since it takes in account device_position
312 data[i].set_cartesian(value * cos(angle) + device_position_x, value * sin(angle) + device_position_y);
313#else
314 data[i].set_polar(value,angle);
315#endif
316 }
317 if (timestamp!=nullptr)
318 {
319 *timestamp = lastTs.getTime();
320 }
321 return true;
322}
323
324bool Rangefinder2DClient::getDistanceRange(double& min, double& max)
325{
326 Bottle cmd, response;
330 bool ok = rpcPort.write(cmd, response);
331 if (CHECK_FAIL(ok, response) != false)
332 {
333 min = response.get(2).asFloat64();
334 max = response.get(3).asFloat64();
335 return true;
336 }
337 return false;
338}
339
340bool Rangefinder2DClient::setDistanceRange(double min, double max)
341{
342 Bottle cmd, response;
346 cmd.addFloat64(min);
347 cmd.addFloat64(max);
348 bool ok = rpcPort.write(cmd, response);
349 if (ok)
350 {
351 scan_angle_min = min;
352 scan_angle_max = max;
353 }
354 return (CHECK_FAIL(ok, response));
355}
356
357bool Rangefinder2DClient::getScanLimits(double& min, double& max)
358{
359 Bottle cmd, response;
363 bool ok = rpcPort.write(cmd, response);
364 if (CHECK_FAIL(ok, response) != false)
365 {
366 min = scan_angle_min = response.get(2).asFloat64();
367 max = scan_angle_max = response.get(3).asFloat64();
368 return true;
369 }
370 return false;
371}
372
373bool Rangefinder2DClient::setScanLimits(double min, double max)
374{
375 Bottle cmd, response;
379 cmd.addFloat64(min);
380 cmd.addFloat64(max);
381 bool ok = rpcPort.write(cmd, response);
382 return (CHECK_FAIL(ok, response));
383}
384
386{
387 Bottle cmd, response;
391 bool ok = rpcPort.write(cmd, response);
392 if (CHECK_FAIL(ok, response) != false)
393 {
394 step = response.get(2).asFloat64();
395 return true;
396 }
397 return false;
398}
399
401{
402 Bottle cmd, response;
406 cmd.addFloat64(step);
407 bool ok = rpcPort.write(cmd, response);
408 return (CHECK_FAIL(ok, response));
409}
410
412{
413 Bottle cmd, response;
417 bool ok = rpcPort.write(cmd, response);
418 if (CHECK_FAIL(ok, response) != false)
419 {
420 rate = response.get(2).asFloat64();
421 return true;
422 }
423 return false;
424}
425
427{
428 Bottle cmd, response;
432 cmd.addFloat64(rate);
433 bool ok = rpcPort.write(cmd, response);
434 return (CHECK_FAIL(ok, response));
435}
436
438{
439 status = inputPort.getStatus();
440 return true;
441}
442
443bool Rangefinder2DClient::getDeviceInfo(std::string &device_info)
444{
445 Bottle cmd, response;
449 bool ok = rpcPort.write(cmd, response);
450 if (CHECK_FAIL(ok, response)!=false)
451 {
452 device_info = response.get(2).asString();
453 return true;
454 }
455 return false;
456}
constexpr yarp::conf::vocab32_t VOCAB_GET
Definition: GenericVocabs.h:13
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
#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)
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
bool close() override
Close the DeviceDriver.
yarp::os::Stamp lastTs
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 getRawData(yarp::sig::Vector &data, double *timestamp=nullptr) override
Get the device measurements.
bool getLaserMeasurement(std::vector< yarp::dev::LaserMeasurementData > &data, double *timestamp=nullptr) override
Get the device measurements.
bool getDeviceStatus(Device_status &status) override
get the device status
Rangefinder2DInputPortProcessor inputPort
bool getDeviceInfo(std::string &device_info) override
get the device hardware charactestics
bool getScanLimits(double &min, double &max) override
get the scan angular range.
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.
yarp::sig::Vector scans
the scan data, measured in [m].
Definition: LaserScan2D.h:46
std::int32_t status
Definition: LaserScan2D.h:47
A container for a device driver.
Definition: PolyDriver.h:23
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:64
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:164
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
bool getEnvelope(PortReader &envelope) override
void close() override
Stop port activity.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void useCallback(TypedReaderCallback< T > &callback) override
Set an object whose onRead method will be called when data is available.
bool write(const PortWriter &writer, const PortWriter *callback=nullptr) const override
Write an object to the port.
Definition: Port.cpp:436
void close() override
Stop port activity.
Definition: Port.cpp:363
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:79
A class for storing options and configuration information.
Definition: Property.h:33
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:63
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:21
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
bool isValid() const
Check if this Stamp is valid.
Definition: Stamp.cpp:39
A single value (typically within a Bottle).
Definition: Value.h:43
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
std::string toString() const override
Return a standard text representation of the content of the object.
Definition: Value.cpp:356
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
A class for a Matrix.
Definition: Matrix.h:39
size_t size() const
Definition: Vector.h:321
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCDebug(component,...)
Definition: LogComponent.h:128
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
For streams capable of holding different kinds of content, check what they actually have.
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:808
An interface to the operating system, including Port based communication.