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