YARP
Yet Another Robot Platform
Localization2DClient.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 #include "Localization2DClient.h"
8 #include <yarp/os/Log.h>
9 #include <yarp/os/LogComponent.h>
10 #include <yarp/os/LogStream.h>
11 #include <mutex>
12 
15 using namespace yarp::dev;
16 using namespace yarp::dev::Nav2D;
17 using namespace yarp::os;
18 using namespace yarp::sig;
19 
20 namespace {
21 YARP_LOG_COMPONENT(LOCALIZATION2DCLIENT, "yarp.device.localization2DClient")
22 }
23 
24 //------------------------------------------------------------------------------------------------------------------------------
25 
27 {
28  m_local_name.clear();
29  m_remote_name.clear();
30 
31  m_local_name = config.find("local").asString();
32  m_remote_name = config.find("remote").asString();
33 
34  if (m_local_name == "")
35  {
36  yCError(LOCALIZATION2DCLIENT, "open() error you have to provide a valid 'local' param");
37  return false;
38  }
39 
40  if (m_remote_name == "")
41  {
42  yCError(LOCALIZATION2DCLIENT, "open() error you have to provide valid 'remote' param");
43  return false;
44  }
45 
46  std::string
47  local_rpc,
48  remote_rpc,
49  remote_streaming_name,
50  local_streaming_name;
51 
52  local_rpc = m_local_name + "/localization/rpc";
53  remote_rpc = m_remote_name + "/rpc";
54  remote_streaming_name = m_remote_name + "/stream:o";
55  local_streaming_name = m_local_name + "/stream:i";
56 
57  if (!m_rpc_port_localization_server.open(local_rpc))
58  {
59  yCError(LOCALIZATION2DCLIENT, "open() error could not open rpc port %s, check network", local_rpc.c_str());
60  return false;
61  }
62 
63  /*
64  //currently unused
65  bool ok=Network::connect(remote_streaming_name.c_str(), local_streaming_name.c_str(), "tcp");
66  if (!ok)
67  {
68  yCError(LOCALIZATION2DCLIENT, "open() error could not connect to %s", remote_streaming_name.c_str());
69  return false;
70  }*/
71 
72  bool ok = true;
73 
74  ok = Network::connect(local_rpc, remote_rpc);
75  if (!ok)
76  {
77  yCError(LOCALIZATION2DCLIENT, "open() error could not connect to %s", remote_rpc.c_str());
78  return false;
79  }
80 
81  return true;
82 }
83 
85 {
87  yarp::os::Bottle resp;
88 
91  b.addString(loc.map_id);
92  b.addFloat64(loc.x);
93  b.addFloat64(loc.y);
94  b.addFloat64(loc.theta);
95 
96  bool ret = m_rpc_port_localization_server.write(b, resp);
97  if (ret)
98  {
99  if (resp.get(0).asVocab32() != VOCAB_OK)
100  {
101  yCError(LOCALIZATION2DCLIENT) << "setInitialPose() received error from localization server";
102  return false;
103  }
104  }
105  else
106  {
107  yCError(LOCALIZATION2DCLIENT) << "setInitialPose() error on writing on rpc port";
108  return false;
109  }
110  return true;
111 }
112 
114 {
115  if (cov.rows() != 3 || cov.cols() != 3)
116  {
117  yCError(LOCALIZATION2DCLIENT) << "Covariance matrix is expected to have size (3,3)";
118  return false;
119  }
121  yarp::os::Bottle resp;
122 
125  b.addString(loc.map_id);
126  b.addFloat64(loc.x);
127  b.addFloat64(loc.y);
128  b.addFloat64(loc.theta);
129  yarp::os::Bottle& mc = b.addList();
130  for (size_t i = 0; i < 3; i++) {for (size_t j = 0; j < 3; j++) { mc.addFloat64(cov[i][j]); }}
131 
132  bool ret = m_rpc_port_localization_server.write(b, resp);
133  if (ret)
134  {
135  if (resp.get(0).asVocab32() != VOCAB_OK)
136  {
137  yCError(LOCALIZATION2DCLIENT) << "setInitialPose() received error from localization server";
138  return false;
139  }
140  }
141  else
142  {
143  yCError(LOCALIZATION2DCLIENT) << "setInitialPose() error on writing on rpc port";
144  return false;
145  }
146  return true;
147 }
148 
150 {
152  yarp::os::Bottle resp;
153 
156 
157  bool ret = m_rpc_port_localization_server.write(b, resp);
158  if (ret)
159  {
160  if (resp.get(0).asVocab32() != VOCAB_OK || resp.size() != 10)
161  {
162  yCError(LOCALIZATION2DCLIENT) << "getEstimatedOdometry() received error from localization server";
163  return false;
164  }
165  else
166  {
167  odom.odom_x = resp.get(1).asFloat64();
168  odom.odom_y = resp.get(2).asFloat64();
169  odom.odom_theta = resp.get(3).asFloat64();
170  odom.base_vel_x = resp.get(4).asFloat64();
171  odom.base_vel_y = resp.get(5).asFloat64();
172  odom.base_vel_theta = resp.get(6).asFloat64();
173  odom.odom_vel_x = resp.get(7).asFloat64();
174  odom.odom_vel_y = resp.get(8).asFloat64();
175  odom.odom_vel_theta = resp.get(9).asFloat64();
176  return true;
177  }
178  }
179  else
180  {
181  yCError(LOCALIZATION2DCLIENT) << "getEstimatedOdometry() error on writing on rpc port";
182  return false;
183  }
184  return true;
185 }
186 
188 {
190  yarp::os::Bottle resp;
191 
194 
195  bool ret = m_rpc_port_localization_server.write(b, resp);
196  if (ret)
197  {
198  if (resp.get(0).asVocab32() != VOCAB_OK || resp.size() != 5)
199  {
200  yCError(LOCALIZATION2DCLIENT) << "getCurrentPosition() received error from localization server";
201  return false;
202  }
203  else
204  {
205  loc.map_id = resp.get(1).asString();
206  loc.x = resp.get(2).asFloat64();
207  loc.y = resp.get(3).asFloat64();
208  loc.theta = resp.get(4).asFloat64();
209  return true;
210  }
211  }
212  else
213  {
214  yCError(LOCALIZATION2DCLIENT) << "getCurrentPosition() error on writing on rpc port";
215  return false;
216  }
217  return true;
218 }
219 
221 {
223  yarp::os::Bottle resp;
224 
227 
228  bool ret = m_rpc_port_localization_server.write(b, resp);
229  if (ret)
230  {
231  if (resp.get(0).asVocab32() != VOCAB_OK || resp.size() != 6)
232  {
233  yCError(LOCALIZATION2DCLIENT) << "getCurrentPosition() received error from localization server";
234  return false;
235  }
236  else
237  {
238  if (cov.rows() != 3 || cov.cols() != 3)
239  {
240  yCDebug(LOCALIZATION2DCLIENT) << "Performance warning: covariance matrix is not (3,3), resizing...";
241  cov.resize(3, 3);
242  }
243  loc.map_id = resp.get(1).asString();
244  loc.x = resp.get(2).asFloat64();
245  loc.y = resp.get(3).asFloat64();
246  loc.theta = resp.get(4).asFloat64();
247  Bottle* mc = resp.get(5).asList();
248  if (mc == nullptr) {
249  return false;
250  }
251  for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { cov[i][j] = mc->get(i*3+j).asFloat64(); } }
252  return true;
253  }
254  }
255  else
256  {
257  yCError(LOCALIZATION2DCLIENT) << "getCurrentPosition() error on writing on rpc port";
258  return false;
259  }
260  return true;
261 }
262 
263 bool Localization2DClient::getEstimatedPoses(std::vector<Map2DLocation>& poses)
264 {
266  yarp::os::Bottle resp;
267 
270 
271  bool ret = m_rpc_port_localization_server.write(b, resp);
272  if (ret)
273  {
274  if (resp.get(0).asVocab32() != VOCAB_OK)
275  {
276  yCError(LOCALIZATION2DCLIENT) << "getEstimatedPoses() received error from localization server";
277  return false;
278  }
279  else
280  {
281  int nposes = resp.get(1).asInt32();
282  poses.clear();
283  for (int i = 0; i < nposes; i++)
284  {
285  Map2DLocation loc;
286  Bottle* b = resp.get(2 + i).asList();
287  if (b)
288  {
289  loc.map_id = b->get(0).asString();
290  loc.x = b->get(1).asFloat64();
291  loc.y = b->get(2).asFloat64();
292  loc.theta = b->get(3).asFloat64();
293  }
294  else
295  {
296  poses.clear();
297  yCError(LOCALIZATION2DCLIENT) << "getEstimatedPoses() parsing error";
298  return false;
299  }
300  poses.push_back(loc);
301  }
302  return true;
303  }
304  }
305  else
306  {
307  yCError(LOCALIZATION2DCLIENT) << "getEstimatedPoses() error on writing on rpc port";
308  return false;
309  }
310  return true;
311 }
312 
314 {
316  yarp::os::Bottle resp;
317 
320 
321  bool ret = m_rpc_port_localization_server.write(b, resp);
322  if (ret)
323  {
324  if (resp.get(0).asVocab32() != VOCAB_OK || resp.size() != 2)
325  {
326  yCError(LOCALIZATION2DCLIENT) << "getLocalizationStatus() received error from localization server";
327  return false;
328  }
329  else
330  {
332  return true;
333  }
334  }
335  else
336  {
337  yCError(LOCALIZATION2DCLIENT) << "getLocalizationStatus() error on writing on rpc port";
338  return false;
339  }
340  return true;
341 }
342 
344 {
346  yarp::os::Bottle resp;
347 
350 
351  bool ret = m_rpc_port_localization_server.write(b, resp);
352  if (ret)
353  {
354  if (resp.get(0).asVocab32() != VOCAB_OK)
355  {
356  yCError(LOCALIZATION2DCLIENT) << "startLocalizationService() received error from navigation server";
357  return false;
358  }
359  }
360  else
361  {
362  yCError(LOCALIZATION2DCLIENT) << "startLocalizationService() error on writing on rpc port";
363  return false;
364  }
365  return true;
366 }
367 
369 {
371  yarp::os::Bottle resp;
372 
375 
376  bool ret = m_rpc_port_localization_server.write(b, resp);
377  if (ret)
378  {
379  if (resp.get(0).asVocab32() != VOCAB_OK)
380  {
381  yCError(LOCALIZATION2DCLIENT) << "stopLocalizationService() received error from navigation server";
382  return false;
383  }
384  }
385  else
386  {
387  yCError(LOCALIZATION2DCLIENT) << "stopLocalizationService() error on writing on rpc port";
388  return false;
389  }
390  return true;
391 }
392 
394 {
395  m_rpc_port_localization_server.close();
396  return true;
397 }
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:15
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_POSES
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_STOP
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_STATUS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_ESTIMATED_ODOM
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_START
bool ret
bool getEstimatedOdometry(yarp::dev::OdometryData &odom) override
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
bool startLocalizationService() override
Starts the localization service.
bool getLocalizationStatus(yarp::dev::Nav2D::LocalizationStatusEnum &status) override
Gets the current status of the localization task.
bool close() override
Close the DeviceDriver.
bool getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc) override
Gets the current position of the robot w.r.t world reference frame.
bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation &loc) override
Sets the initial pose for the localization algorithm which estimates the current position of the robo...
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool stopLocalizationService() override
Stops the localization service.
bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses) override
Gets a set of pose estimates computed by the localization algorithm.
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:42
double odom_vel_y
velocity of the robot [m/s] expressed in the world reference frame
Definition: OdometryData.h:58
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
Definition: OdometryData.h:50
double odom_vel_theta
angular velocity of the robot [deg/s] expressed in the world reference frame
Definition: OdometryData.h:62
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:46
double odom_x
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:30
double odom_y
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:34
double odom_theta
orientation the robot [deg], expressed in the world reference frame
Definition: OdometryData.h:38
double odom_vel_x
velocity of the robot [m/s] expressed in the world reference frame
Definition: OdometryData.h:54
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
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition: Bottle.cpp:182
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:251
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 addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
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 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 Bottle * asList() const
Get list value.
Definition: Value.cpp:240
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
A class for a Matrix.
Definition: Matrix.h:43
void resize(size_t r, size_t c)
Resize the matrix, if matrix is not empty preserve old content.
Definition: Matrix.cpp:265
size_t cols() const
Return number of columns.
Definition: Matrix.h:98
size_t rows() const
Return number of rows.
Definition: Matrix.h:92
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
An interface for the device drivers.
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:22