YARP
Yet Another Robot Platform
Map2DClient.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 
8 #include "Map2DClient.h"
9 #include <yarp/os/Log.h>
10 #include <yarp/os/LogComponent.h>
11 #include <yarp/os/LogStream.h>
12 #include <mutex>
13 #include <yarp/dev/INavigation2D.h>
14 #include <yarp/dev/GenericVocabs.h>
15 
16 using namespace yarp::dev;
17 using namespace yarp::dev::Nav2D;
18 using namespace yarp::os;
19 using namespace yarp::sig;
20 
21 namespace {
22 YARP_LOG_COMPONENT(MAP2DCLIENT, "yarp.device.map2DClient")
23 }
24 
25 //------------------------------------------------------------------------------------------------------------------------------
26 
28 {
29  m_local_name.clear();
30  m_map_server.clear();
31 
32  m_local_name = config.find("local").asString();
33  m_map_server = config.find("remote").asString();
34 
35  if (m_local_name == "")
36  {
37  yCError(MAP2DCLIENT, "open() error you have to provide valid local name");
38  return false;
39  }
40  if (m_map_server == "")
41  {
42  yCError(MAP2DCLIENT, "open() error you have to provide valid remote name");
43  return false;
44  }
45 
46  std::string local_rpc1 = m_local_name;
47  local_rpc1 += "/mapClient_rpc";
48 
49  std::string remote_rpc1 = m_map_server;
50  remote_rpc1 += "/rpc";
51 
52  if (!m_rpcPort_to_Map2DServer.open(local_rpc1))
53  {
54  yCError(MAP2DCLIENT, "open() error could not open rpc port %s, check network", local_rpc1.c_str());
55  return false;
56  }
57 
58  bool ok=false;
59  ok=Network::connect(local_rpc1, remote_rpc1);
60  if (!ok)
61  {
62  yCError(MAP2DCLIENT, "open() error could not connect to %s", remote_rpc1.c_str());
63  return false;
64  }
65 
66  return true;
67 }
68 
70 {
72  yarp::os::Bottle resp;
73 
76  yarp::os::Bottle& mapbot = b.addList();
77  MapGrid2D maptemp = map;
78  if (Property::copyPortable(maptemp, mapbot) == false)
79  {
80  yCError(MAP2DCLIENT) << "store_map() failed copyPortable()";
81  return false;
82  }
83  //yCDebug(MAP2DCLIENT) << b.toString();
84  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
85  if (ret)
86  {
87  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
88  {
89  yCError(MAP2DCLIENT) << "store_map() received error from server";
90  return false;
91  }
92  }
93  else
94  {
95  yCError(MAP2DCLIENT) << "store_map() error on writing on rpc port";
96  return false;
97  }
98  return true;
99 }
100 
101 bool Map2DClient::get_map(std::string map_name, MapGrid2D& map)
102 {
104  yarp::os::Bottle resp;
105 
108  b.addString(map_name);
109 
110  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
111  if (ret)
112  {
113  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
114  {
115  yCError(MAP2DCLIENT) << "get_map() received error from server";
116  return false;
117  }
118  else
119  {
120  Value& bt = resp.get(1);
121  if (Property::copyPortable(bt, map))
122  {
123  return true;
124  }
125  else
126  {
127  yCError(MAP2DCLIENT) << "get_map() failed copyPortable()";
128  return false;
129  }
130  }
131  }
132  else
133  {
134  yCError(MAP2DCLIENT) << "get_map() error on writing on rpc port";
135  return false;
136  }
137  return true;
138 }
139 
141 {
143  yarp::os::Bottle resp;
144 
147 
148  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
149  if (ret)
150  {
151  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
152  {
153  yCError(MAP2DCLIENT) << "clear() received error from server";
154  return false;
155  }
156  }
157  else
158  {
159  yCError(MAP2DCLIENT) << "clear() error on writing on rpc port";
160  return false;
161  }
162  return true;
163 }
164 
165 bool Map2DClient::get_map_names(std::vector<std::string>& map_names)
166 {
167  map_names.clear();
169  yarp::os::Bottle resp;
170 
173  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
174  if (ret)
175  {
176  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
177  {
178  yCError(MAP2DCLIENT) << "get_map_names() received error from server";
179  return false;
180  }
181  else
182  {
183  for (size_t i = 1; i < resp.size(); i++)
184  {
185  map_names.push_back(resp.get(i).asString());
186  }
187  return true;
188  }
189  }
190  else
191  {
192  yCError(MAP2DCLIENT) << "get_map_names() error on writing on rpc port";
193  return false;
194  }
195  return true;
196 }
197 
198 bool Map2DClient::remove_map(std::string map_name)
199 {
201  yarp::os::Bottle resp;
202 
205  b.addString(map_name);
206 
207  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
208  if (ret)
209  {
210  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
211  {
212  yCError(MAP2DCLIENT) << "remove_map() received error from server";
213  return false;
214  }
215  }
216  else
217  {
218  yCError(MAP2DCLIENT) << "remove_map() error on writing on rpc port";
219  return false;
220  }
221  return true;
222 }
223 
224 bool Map2DClient::storeLocation(std::string location_name, Map2DLocation loc)
225 {
227  yarp::os::Bottle resp;
228 
232  b.addString(location_name);
233  b.addString(loc.map_id);
234  b.addFloat64(loc.x);
235  b.addFloat64(loc.y);
236  b.addFloat64(loc.theta);
237 
238  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
239  if (ret)
240  {
241  if (resp.get(0).asVocab32() != VOCAB_OK)
242  {
243  yCError(MAP2DCLIENT) << "storeLocation() received error from locations server";
244  return false;
245  }
246  }
247  else
248  {
249  yCError(MAP2DCLIENT) << "storeLocation() error on writing on rpc port";
250  return false;
251  }
252  return true;
253 }
254 
255 bool Map2DClient::storeArea(std::string area_name, Map2DArea area)
256 {
258  yarp::os::Bottle resp;
259 
263  b.addString(area_name);
264  yarp::os::Bottle& areabot = b.addList();
265  Map2DArea areatemp = area;
266  if (Property::copyPortable(areatemp, areabot) == false)
267  {
268  yCError(MAP2DCLIENT) << "storeArea() failed copyPortable()";
269  return false;
270  }
271 
272  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
273  if (ret)
274  {
275  if (resp.get(0).asVocab32() != VOCAB_OK)
276  {
277  yCError(MAP2DCLIENT) << "storeArea() received error from locations server";
278  return false;
279  }
280  }
281  else
282  {
283  yCError(MAP2DCLIENT) << "storeArea() error on writing on rpc port";
284  return false;
285  }
286  return true;
287 }
288 
289 bool Map2DClient::storePath(std::string path_name, Map2DPath path)
290 {
292  yarp::os::Bottle resp;
293 
297  b.addString(path_name);
298  yarp::os::Bottle& areabot = b.addList();
299  Map2DPath pathtemp = path;
300  if (Property::copyPortable(pathtemp, areabot) == false)
301  {
302  yCError(MAP2DCLIENT) << "storePath() failed copyPortable()";
303  return false;
304  }
305 
306  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
307  if (ret)
308  {
309  if (resp.get(0).asVocab32() != VOCAB_OK)
310  {
311  yCError(MAP2DCLIENT) << "storePath() received error from locations server";
312  return false;
313  }
314  }
315  else
316  {
317  yCError(MAP2DCLIENT) << "storePath() error on writing on rpc port";
318  return false;
319  }
320  return true;
321 }
322 
323 bool Map2DClient::getLocationsList(std::vector<std::string>& locations)
324 {
326  yarp::os::Bottle resp;
327 
331 
332  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
333  if (ret)
334  {
335  if (resp.get(0).asVocab32() != VOCAB_OK)
336  {
337  yCError(MAP2DCLIENT) << "getLocationsList() received error from locations server";
338  return false;
339  }
340  else
341  {
342  Bottle* list = resp.get(1).asList();
343  if (list)
344  {
345  locations.clear();
346  for (size_t i = 0; i < list->size(); i++)
347  {
348  locations.push_back(list->get(i).asString());
349  }
350  return true;
351  }
352  else
353  {
354  yCError(MAP2DCLIENT) << "getLocationsList() error while reading from locations server";
355  return false;
356  }
357  }
358  }
359  else
360  {
361  yCError(MAP2DCLIENT) << "getLocationsList() error on writing on rpc port";
362  return false;
363  }
364  return true;
365 }
366 
367 bool Map2DClient::getAreasList(std::vector<std::string>& areas)
368 {
370  yarp::os::Bottle resp;
371 
375 
376  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
377  if (ret)
378  {
379  if (resp.get(0).asVocab32() != VOCAB_OK)
380  {
381  yCError(MAP2DCLIENT) << "getAreasList() received error from locations server";
382  return false;
383  }
384  else
385  {
386  Bottle* list = resp.get(1).asList();
387  if (list)
388  {
389  areas.clear();
390  for (size_t i = 0; i < list->size(); i++)
391  {
392  areas.push_back(list->get(i).asString());
393  }
394  return true;
395  }
396  else
397  {
398  yCError(MAP2DCLIENT) << "getAreasList() error while reading from locations server";
399  return false;
400  }
401  }
402  }
403  else
404  {
405  yCError(MAP2DCLIENT) << "getAreasList() error on writing on rpc port";
406  return false;
407  }
408  return true;
409 }
410 
411 bool Map2DClient::getPathsList(std::vector<std::string>& paths)
412 {
414  yarp::os::Bottle resp;
415 
419 
420  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
421  if (ret)
422  {
423  if (resp.get(0).asVocab32() != VOCAB_OK)
424  {
425  yCError(MAP2DCLIENT) << "getPathsList() received error from locations server";
426  return false;
427  }
428  else
429  {
430  Bottle* list = resp.get(1).asList();
431  if (list)
432  {
433  paths.clear();
434  for (size_t i = 0; i < list->size(); i++)
435  {
436  paths.push_back(list->get(i).asString());
437  }
438  return true;
439  }
440  else
441  {
442  yCError(MAP2DCLIENT) << "getPathsList() error while reading from locations server";
443  return false;
444  }
445  }
446  }
447  else
448  {
449  yCError(MAP2DCLIENT) << "getPathsList() error on writing on rpc port";
450  return false;
451  }
452  return true;
453 }
454 
455 bool Map2DClient::getLocation(std::string location_name, Map2DLocation& loc)
456 {
458  yarp::os::Bottle resp;
459 
463  b.addString(location_name);
464 
465  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
466  if (ret)
467  {
468  if (resp.get(0).asVocab32() != VOCAB_OK)
469  {
470  yCError(MAP2DCLIENT) << "getLocation() received error from locations server";
471  return false;
472  }
473  else
474  {
475  loc.map_id = resp.get(1).asString();
476  loc.x = resp.get(2).asFloat64();
477  loc.y = resp.get(3).asFloat64();
478  loc.theta = resp.get(4).asFloat64();
479  }
480  }
481  else
482  {
483  yCError(MAP2DCLIENT) << "getLocation() error on writing on rpc port";
484  return false;
485  }
486  return true;
487 }
488 
489 bool Map2DClient::getArea(std::string location_name, Map2DArea& area)
490 {
492  yarp::os::Bottle resp;
493 
497  b.addString(location_name);
498 
499  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
500  if (ret)
501  {
502  if (resp.get(0).asVocab32() != VOCAB_OK)
503  {
504  yCError(MAP2DCLIENT) << "getArea() received error from locations server";
505  return false;
506  }
507  else
508  {
509  Value& bt = resp.get(1);
510  if (Property::copyPortable(bt, area))
511  {
512  return true;
513  }
514  else
515  {
516  yCError(MAP2DCLIENT) << "getArea() failed copyPortable()";
517  return false;
518  }
519  }
520  }
521  else
522  {
523  yCError(MAP2DCLIENT) << "getArea() error on writing on rpc port";
524  return false;
525  }
526  return true;
527 }
528 
529 bool Map2DClient::getPath(std::string path_name, Map2DPath& path)
530 {
532  yarp::os::Bottle resp;
533 
537  b.addString(path_name);
538 
539  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
540  if (ret)
541  {
542  if (resp.get(0).asVocab32() != VOCAB_OK)
543  {
544  yCError(MAP2DCLIENT) << "getPath() received error from locations server";
545  return false;
546  }
547  else
548  {
549  Value& bt = resp.get(1);
550  if (Property::copyPortable(bt, path))
551  {
552  return true;
553  }
554  else
555  {
556  yCError(MAP2DCLIENT) << "getPath() failed copyPortable()";
557  return false;
558  }
559  }
560  }
561  else
562  {
563  yCError(MAP2DCLIENT) << "getPath() error on writing on rpc port";
564  return false;
565  }
566  return true;
567 }
568 
569 bool Map2DClient::deleteLocation(std::string location_name)
570 {
572  yarp::os::Bottle resp;
573 
577  b.addString(location_name);
578 
579  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
580  if (ret)
581  {
582  if (resp.get(0).asVocab32() != VOCAB_OK)
583  {
584  yCError(MAP2DCLIENT) << "deleteLocation() received error from locations server";
585  return false;
586  }
587  }
588  else
589  {
590  yCError(MAP2DCLIENT) << "deleteLocation() error on writing on rpc port";
591  return false;
592  }
593  return true;
594 }
595 
596 bool Map2DClient::renameLocation(std::string original_name, std::string new_name)
597 {
599  yarp::os::Bottle resp;
600 
604  b.addString(original_name);
605  b.addString(new_name);
606 
607  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
608  if (ret)
609  {
610  if (resp.get(0).asVocab32() != VOCAB_OK)
611  {
612  yCError(MAP2DCLIENT) << "renameLocation() received error from locations server";
613  return false;
614  }
615  }
616  else
617  {
618  yCError(MAP2DCLIENT) << "renameLocation() error on writing on rpc port";
619  return false;
620  }
621  return true;
622 }
623 
624 bool Map2DClient::deleteArea(std::string location_name)
625 {
627  yarp::os::Bottle resp;
628 
632  b.addString(location_name);
633 
634  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
635  if (ret)
636  {
637  if (resp.get(0).asVocab32() != VOCAB_OK)
638  {
639  yCError(MAP2DCLIENT) << "deleteArea() received error from locations server";
640  return false;
641  }
642  }
643  else
644  {
645  yCError(MAP2DCLIENT) << "deleteArea() error on writing on rpc port";
646  return false;
647  }
648  return true;
649 }
650 
651 bool Map2DClient::deletePath(std::string path_name)
652 {
654  yarp::os::Bottle resp;
655 
659  b.addString(path_name);
660 
661  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
662  if (ret)
663  {
664  if (resp.get(0).asVocab32() != VOCAB_OK)
665  {
666  yCError(MAP2DCLIENT) << "deletePath() received error from locations server";
667  return false;
668  }
669  }
670  else
671  {
672  yCError(MAP2DCLIENT) << "deletePath() error on writing on rpc port";
673  return false;
674  }
675  return true;
676 }
677 
678 bool Map2DClient::renameArea(std::string original_name, std::string new_name)
679 {
681  yarp::os::Bottle resp;
682 
686  b.addString(original_name);
687  b.addString(new_name);
688 
689  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
690  if (ret)
691  {
692  if (resp.get(0).asVocab32() != VOCAB_OK)
693  {
694  yCError(MAP2DCLIENT) << "renameArea() received error from locations server";
695  return false;
696  }
697  }
698  else
699  {
700  yCError(MAP2DCLIENT) << "renameArea() error on writing on rpc port";
701  return false;
702  }
703  return true;
704 }
705 
706 bool Map2DClient::renamePath(std::string original_name, std::string new_name)
707 {
709  yarp::os::Bottle resp;
710 
714  b.addString(original_name);
715  b.addString(new_name);
716 
717  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
718  if (ret)
719  {
720  if (resp.get(0).asVocab32() != VOCAB_OK)
721  {
722  yCError(MAP2DCLIENT) << "renamePath() received error from locations server";
723  return false;
724  }
725  }
726  else
727  {
728  yCError(MAP2DCLIENT) << "renamePath() error on writing on rpc port";
729  return false;
730  }
731  return true;
732 }
733 
735 {
737  yarp::os::Bottle resp;
738 
742 
743  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
744  if (ret)
745  {
746  if (resp.get(0).asVocab32() != VOCAB_OK)
747  {
748  yCError(MAP2DCLIENT) << "clearAllLocations() received error from locations server";
749  return false;
750  }
751  }
752  else
753  {
754  yCError(MAP2DCLIENT) << "clearAllLocations() error on writing on rpc port";
755  return false;
756  }
757  return true;
758 }
759 
761 {
763  yarp::os::Bottle resp;
764 
768 
769  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
770  if (ret)
771  {
772  if (resp.get(0).asVocab32() != VOCAB_OK)
773  {
774  yCError(MAP2DCLIENT) << "clearAllAreas() received error from locations server";
775  return false;
776  }
777  }
778  else
779  {
780  yCError(MAP2DCLIENT) << "clearAllAreas() error on writing on rpc port";
781  return false;
782  }
783  return true;
784 }
785 
787 {
789  yarp::os::Bottle resp;
790 
794 
795  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
796  if (ret)
797  {
798  if (resp.get(0).asVocab32() != VOCAB_OK)
799  {
800  yCError(MAP2DCLIENT) << "clearAllMapsTemporaryFlags() received error from locations server";
801  return false;
802  }
803  }
804  else
805  {
806  yCError(MAP2DCLIENT) << "clearAllAreas() error on writing on rpc port";
807  return false;
808  }
809  return true;
810 }
811 
812 bool Map2DClient::clearMapTemporaryFlags(std::string map_name)
813 {
815  yarp::os::Bottle resp;
816 
820  b.addString(map_name);
821 
822  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
823  if (ret)
824  {
825  if (resp.get(0).asVocab32() != VOCAB_OK)
826  {
827  yCError(MAP2DCLIENT) << "clearMapTemporaryFlags() received error from locations server";
828  return false;
829  }
830  }
831  else
832  {
833  yCError(MAP2DCLIENT) << "clearAllAreas() error on writing on rpc port";
834  return false;
835  }
836  return true;
837 }
838 
840 {
842  yarp::os::Bottle resp;
843 
847 
848  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
849  if (ret)
850  {
851  if (resp.get(0).asVocab32() != VOCAB_OK)
852  {
853  yCError(MAP2DCLIENT) << "clearAllPaths() received error from locations server";
854  return false;
855  }
856  }
857  else
858  {
859  yCError(MAP2DCLIENT) << "clearAllPaths() error on writing on rpc port";
860  return false;
861  }
862  return true;
863 }
864 
866 {
867  return true;
868 }
869 
870 bool Map2DClient::saveMapsCollection(std::string maps_collection)
871 {
873  yarp::os::Bottle resp;
874 
878  b.addString(maps_collection);
879 
880  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
881  if (ret)
882  {
883  if (resp.get(0).asVocab32() != VOCAB_OK)
884  {
885  yCError(MAP2DCLIENT) << "saveMapsCollection() received error from locations server";
886  return false;
887  }
888  }
889  else
890  {
891  yCError(MAP2DCLIENT) << "saveMapsCollection() error on writing on rpc port";
892  return false;
893  }
894  return true;
895 }
896 
897 bool Map2DClient::loadMapsCollection(std::string maps_collection)
898 {
900  yarp::os::Bottle resp;
901 
905  b.addString(maps_collection);
906 
907  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
908  if (ret)
909  {
910  if (resp.get(0).asVocab32() != VOCAB_OK)
911  {
912  yCError(MAP2DCLIENT) << "loadMapsCollection() received error from locations server";
913  return false;
914  }
915  }
916  else
917  {
918  yCError(MAP2DCLIENT) << "loadMapsCollection() error on writing on rpc port";
919  return false;
920  }
921  return true;
922 }
923 
924 bool Map2DClient::saveLocationsAndExtras(std::string locations_collection)
925 {
927  yarp::os::Bottle resp;
928 
932  b.addString(locations_collection);
933 
934  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
935  if (ret)
936  {
937  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
938  {
939  yCError(MAP2DCLIENT) << "saveLocationsAndExtras() received error from locations server";
940  return false;
941  }
942  }
943  else
944  {
945  yCError(MAP2DCLIENT) << "saveLocationsAndExtras() error on writing on rpc port";
946  return false;
947  }
948  return true;
949 }
950 
951 bool Map2DClient::loadLocationsAndExtras(std::string locations_collection)
952 {
954  yarp::os::Bottle resp;
955 
959  b.addString(locations_collection);
960 
961  bool ret = m_rpcPort_to_Map2DServer.write(b, resp);
962  if (ret)
963  {
964  if (resp.get(0).asVocab32() != VOCAB_IMAP_OK)
965  {
966  yCError(MAP2DCLIENT) << "loadLocationsAndExtras() received error from locations server";
967  return false;
968  }
969  }
970  else
971  {
972  yCError(MAP2DCLIENT) << "loadLocationsAndExtras() error on writing on rpc port";
973  return false;
974  }
975  return true;
976 }
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:15
constexpr yarp::conf::vocab32_t VOCAB_NAV_DELETE_X
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LIST_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_AREA
constexpr yarp::conf::vocab32_t VOCAB_NAV_STORE_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_RENAME_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_TEMPORARY_FLAGS
constexpr yarp::conf::vocab32_t VOCAB_NAV_CLEARALL_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_PATH
constexpr yarp::conf::vocab32_t VOCAB_IMAP_LOAD_X
Definition: IMap2D.h:248
constexpr yarp::conf::vocab32_t VOCAB_IMAP_OK
Definition: IMap2D.h:252
constexpr yarp::conf::vocab32_t VOCAB_IMAP_SAVE_X
Definition: IMap2D.h:249
constexpr yarp::conf::vocab32_t VOCAB_IMAP
Definition: IMap2D.h:242
constexpr yarp::conf::vocab32_t VOCAB_IMAP_GET_MAP
Definition: IMap2D.h:244
constexpr yarp::conf::vocab32_t VOCAB_IMAP_SET_MAP
Definition: IMap2D.h:243
constexpr yarp::conf::vocab32_t VOCAB_IMAP_LOCATIONS_COLLECTION
Definition: IMap2D.h:251
constexpr yarp::conf::vocab32_t VOCAB_IMAP_MAPS_COLLECTION
Definition: IMap2D.h:250
constexpr yarp::conf::vocab32_t VOCAB_IMAP_CLEAR_ALL_MAPS
Definition: IMap2D.h:246
constexpr yarp::conf::vocab32_t VOCAB_IMAP_REMOVE
Definition: IMap2D.h:247
constexpr yarp::conf::vocab32_t VOCAB_IMAP_GET_NAMES
Definition: IMap2D.h:245
bool ret
bool getAreasList(std::vector< std::string > &locations) override
Get a list of all stored areas.
bool storeArea(std::string location_name, yarp::dev::Nav2D::Map2DArea area) override
Store an area.
bool loadLocationsAndExtras(std::string locations_collection_file) override
Load a collection of locations/areas/paths etc.
bool deleteArea(std::string location_name) override
Delete an area.
bool renameLocation(std::string original_name, std::string new_name) override
Searches for a location and renames it.
bool loadMapsCollection(std::string maps_collection_file) override
Load a collection of maps.
bool getPathsList(std::vector< std::string > &paths) override
Get a list of all stored paths.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: Map2DClient.cpp:27
bool store_map(const yarp::dev::Nav2D::MapGrid2D &map) override
Stores a map into the map server.
Definition: Map2DClient.cpp:69
bool saveMapsCollection(std::string maps_collection_file) override
Save a collection of maps.
bool clearAllPaths() override
Delete all stored paths.
bool renameArea(std::string original_name, std::string new_name) override
Searches for an area and renames it.
bool saveLocationsAndExtras(std::string locations_collection_file) override
Save a collection of locations/area/paths etc.
bool getLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation &loc) override
Retrieves a location specified by the user in the world reference frame.
bool renamePath(std::string original_name, std::string new_name) override
Searches for a path and renames it.
bool clearMapTemporaryFlags(std::string map_name) override
Clear all temporary flags from a specific map.
bool getLocationsList(std::vector< std::string > &locations) override
Get a list of all stored locations.
bool storePath(std::string path_name, yarp::dev::Nav2D::Map2DPath path) override
Store a path.
bool deletePath(std::string path_name) override
Delete a path.
bool getPath(std::string path_name, yarp::dev::Nav2D::Map2DPath &path) override
Retrieves a path.
bool get_map_names(std::vector< std::string > &map_names) override
Gets a list containing the names of all registered maps.
bool deleteLocation(std::string location_name) override
Delete a location.
bool remove_map(std::string map_name) override
Removes a map from the map server.
bool getArea(std::string location_name, yarp::dev::Nav2D::Map2DArea &area) override
Retrieves an area.
bool get_map(std::string map_name, yarp::dev::Nav2D::MapGrid2D &map) override
Gets a map from the map server.
bool close() override
Close the DeviceDriver.
bool clearAllMaps() override
Removes all the registered maps from the server.
bool clearAllAreas() override
Delete all stored areas.
bool clearAllLocations() override
Delete all stored locations.
bool storeLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation loc) override
Store a location specified by the user in the world reference frame.
bool clearAllMapsTemporaryFlags() override
Clear all temporary flags from all stored maps.
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 clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
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.
A single value (typically within a Bottle).
Definition: Value.h:45
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 Bottle * asList() const
Get list value.
Definition: Value.cpp:240
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
#define yCError(component,...)
Definition: LogComponent.h:154
#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