YARP
Yet Another Robot Platform
Map2DServer.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 <sstream>
7 #include <limits>
8 #include "Map2DServer.h"
9 #include <yarp/dev/IMap2D.h>
10 #include <yarp/dev/INavigation2D.h>
11 #include <yarp/dev/GenericVocabs.h>
12 #include <yarp/math/Math.h>
13 #include <yarp/os/Log.h>
14 #include <yarp/os/LogComponent.h>
15 #include <yarp/os/LogStream.h>
16 #include <mutex>
17 #include <cstdlib>
18 #include <fstream>
19 #include <yarp/os/Publisher.h>
20 #include <yarp/os/Subscriber.h>
21 #include <yarp/os/Node.h>
23 #include <yarp/rosmsg/TickTime.h>
24 
25 using namespace yarp::sig;
26 using namespace yarp::dev;
27 using namespace yarp::dev::Nav2D;
28 using namespace yarp::os;
29 
30 namespace {
31 YARP_LOG_COMPONENT(MAP2DSERVER, "yarp.device.map2DServer")
32 }
33 
39 {
40  m_enable_publish_ros_map = false;
41  m_enable_subscribe_ros_map = false;
42  m_rosNode = nullptr;
43 }
44 
45 Map2DServer::~Map2DServer() = default;
46 
47 void Map2DServer::parse_vocab_command(yarp::os::Bottle& in, yarp::os::Bottle& out)
48 {
49  int code = in.get(0).asVocab32();
50 // bool ret = false;
51  if (code == VOCAB_IMAP)
52  {
53  int cmd = in.get(1).asVocab32();
54  if (cmd == VOCAB_IMAP_SET_MAP)
55  {
56  MapGrid2D the_map;
57  Value& b = in.get(2);
58  if (Property::copyPortable(b, the_map))
59  {
60  std::string map_name = the_map.getMapName();
61  auto it = m_maps_storage.find(map_name);
62  if (it == m_maps_storage.end())
63  {
64  //add a new map
65  m_maps_storage[map_name] = the_map;
66  out.clear();
68  }
69  else
70  {
71  //the map already exists
72  m_maps_storage[map_name] = the_map;
73  out.clear();
75  }
76  }
77  else
78  {
79  out.clear();
81  yCError(MAP2DSERVER) << "Error in copyPortable";
82  }
83  }
84  else if (cmd == VOCAB_IMAP_GET_MAP)
85  {
86  std::string name = in.get(2).asString();
87  auto it = m_maps_storage.find(name);
88  if (it != m_maps_storage.end())
89  {
90  out.clear();
92  yarp::os::Bottle& mapbot = out.addList();
93  Property::copyPortable(it->second, mapbot);
94  }
95  else
96  {
97  out.clear();
99  yCError(MAP2DSERVER) << "Map" << name << "not found";
100  }
101  }
102  else if (cmd == VOCAB_IMAP_GET_NAMES)
103  {
104  out.clear();
106 
107  for (auto& it : m_maps_storage)
108  {
109  out.addString(it.first);
110  }
111  }
112  else if (cmd == VOCAB_IMAP_REMOVE)
113  {
114  std::string name = in.get(2).asString();
115  size_t rem = m_maps_storage.erase(name);
116  if (rem == 0)
117  {
118  yCError(MAP2DSERVER) << "Map not found";
119  out.clear();
121  }
122  else
123  {
124  out.clear();
126  }
127  }
128  else if (cmd == VOCAB_IMAP_CLEAR_ALL_MAPS)
129  {
130  m_maps_storage.clear();
131  out.clear();
133  }
134  else if (cmd == VOCAB_IMAP_SAVE_X)
135  {
137  {
138  std::string mapfile = in.get(3).asString();
139  if (saveMaps(mapfile))
140  {
141  out.clear();
143  }
144  else
145  {
146  yCError(MAP2DSERVER, "Unable to save collection");
147  out.clear();
149  }
150  }
151  else if (in.get(2).asVocab32() == VOCAB_IMAP_LOCATIONS_COLLECTION)
152  {
153  std::string locfile = in.get(3).asString();
154  if (save_locations_and_areas(locfile))
155  {
156  out.clear();
158  }
159  else
160  {
161  yCError(MAP2DSERVER, "Unable to save collection");
162  out.clear();
164  }
165  }
166  else
167  {
168  yCError(MAP2DSERVER, "Parser error");
169  out.clear();
171  }
172  }
173  else if (cmd == VOCAB_IMAP_LOAD_X)
174  {
176  {
177  std::string mapfile = in.get(3).asString();
178  if (loadMaps(mapfile))
179  {
180  out.clear();
182  }
183  else
184  {
185  yCError(MAP2DSERVER, "Unable to load collection");
186  out.clear();
188  }
189  }
191  {
192  std::string locfile = in.get(3).asString();
193  if (load_locations_and_areas(locfile))
194  {
195  out.clear();
197  }
198  else
199  {
200  yCError(MAP2DSERVER, "Unable to load collection");
201  out.clear();
203  }
204  }
205  else
206  {
207  yCError(MAP2DSERVER, "Parser error");
208  out.clear();
210  }
211  }
212  else
213  {
214  yCError(MAP2DSERVER, "Invalid vocab received in Map2DServer");
215  out.clear();
217  }
218  }
219  else if (code == VOCAB_INAVIGATION)
220  {
221  int cmd = in.get(1).asVocab32();
222  if (cmd == VOCAB_NAV_GET_LIST_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
223  {
224  std::string info;
225 
226  out.addVocab32(VOCAB_OK);
227  Bottle& l = out.addList();
228 
229  std::map<std::string, Map2DLocation>::iterator it;
230  for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
231  {
232  l.addString(it->first);
233  }
234  yCInfo(MAP2DSERVER) << "The following locations are currently stored in the server:" << l.toString();
235 // ret = true;
236  }
237  else if (cmd == VOCAB_NAV_GET_LIST_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
238  {
239  std::string info;
240 
241  out.addVocab32(VOCAB_OK);
242  Bottle& l = out.addList();
243 
244  std::map<std::string, Map2DArea>::iterator it;
245  for (it = m_areas_storage.begin(); it != m_areas_storage.end(); ++it)
246  {
247  l.addString(it->first);
248  }
249  yCInfo(MAP2DSERVER) << "The following areas are currently stored in the server:" << l.toString();
250 // ret = true;
251  }
252  else if (cmd == VOCAB_NAV_GET_LIST_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
253  {
254  std::string info;
255 
256  out.addVocab32(VOCAB_OK);
257  Bottle& l = out.addList();
258 
259  std::map<std::string, Map2DPath>::iterator it;
260  for (it = m_paths_storage.begin(); it != m_paths_storage.end(); ++it)
261  {
262  l.addString(it->first);
263  }
264  yCInfo(MAP2DSERVER) << "The following paths are currently stored in the server: " << l.toString();
265  // ret = true;
266  }
267  else if (cmd == VOCAB_NAV_CLEARALL_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
268  {
269  m_locations_storage.clear();
270  yCInfo(MAP2DSERVER) << "All locations deleted";
271  out.addVocab32(VOCAB_OK);
272 // ret = true;
273  }
274  else if (cmd == VOCAB_NAV_CLEARALL_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
275  {
276  m_areas_storage.clear();
277  yCInfo(MAP2DSERVER) << "All areas deleted";
278  out.addVocab32(VOCAB_OK);
279  // ret = true;
280  }
281  else if (cmd == VOCAB_NAV_CLEARALL_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
282  {
283  m_paths_storage.clear();
284  yCInfo(MAP2DSERVER) << "All paths deleted";
285  out.addVocab32(VOCAB_OK);
286  // ret = true;
287  }
288  else if (cmd == VOCAB_NAV_CLEARALL_X && in.get(2).asVocab32() == VOCAB_NAV_TEMPORARY_FLAGS)
289  {
290  for (auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
291  {
292  it->second.clearMapTemporaryFlags();
293  }
294  yCInfo(MAP2DSERVER) << "Temporary flags deleted from all maps";
295  out.addVocab32(VOCAB_OK);
296  // ret = true;
297  }
298  else if (cmd == VOCAB_NAV_DELETE_X && in.get(2).asVocab32() == VOCAB_NAV_TEMPORARY_FLAGS)
299  {
300  std::string name = in.get(3).asString();
301 
302  auto it = m_maps_storage.find(name);
303  if (it != m_maps_storage.end())
304  {
305  yCInfo(MAP2DSERVER) << "Temporary flags cleaned" << name;
306  it->second.clearMapTemporaryFlags();
307  out.addVocab32(VOCAB_OK);
308  }
309  else
310  {
311  yCError(MAP2DSERVER, "User requested an invalid map name");
312  out.addVocab32(VOCAB_ERR);
313  }
314  // ret = true;
315  }
316  else if (cmd == VOCAB_NAV_DELETE_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
317  {
318  std::string name = in.get(3).asString();
319 
320  std::map<std::string, Map2DLocation>::iterator it;
321  it = m_locations_storage.find(name);
322  if (it != m_locations_storage.end())
323  {
324  yCInfo(MAP2DSERVER) << "Deleted location" << name;
325  m_locations_storage.erase(it);
326  out.addVocab32(VOCAB_OK);
327  }
328  else
329  {
330  yCError(MAP2DSERVER, "User requested an invalid location name");
331  out.addVocab32(VOCAB_ERR);
332  }
333 // ret = true;
334  }
335  else if (cmd == VOCAB_NAV_DELETE_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
336  {
337  std::string name = in.get(3).asString();
338 
339  std::map<std::string, Map2DPath>::iterator it;
340  it = m_paths_storage.find(name);
341  if (it != m_paths_storage.end())
342  {
343  yCInfo(MAP2DSERVER) << "Deleted path" << name;
344  m_paths_storage.erase(it);
345  out.addVocab32(VOCAB_OK);
346  }
347  else
348  {
349  yCError(MAP2DSERVER, "User requested an invalid location name");
350  out.addVocab32(VOCAB_ERR);
351  }
352 
353  // ret = true;
354  }
355  else if (cmd == VOCAB_NAV_RENAME_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
356  {
357  std::string orig_name = in.get(3).asString();
358  std::string new_name = in.get(4).asString();
359 
360  std::map<std::string, Map2DLocation>::iterator orig_it;
361  orig_it = m_locations_storage.find(orig_name);
362  std::map<std::string, Map2DLocation>::iterator new_it;
363  new_it = m_locations_storage.find(new_name);
364 
365  if (orig_it != m_locations_storage.end() &&
366  new_it == m_locations_storage.end())
367  {
368  yCInfo(MAP2DSERVER) << "Location:" << orig_name << "renamed to:" << new_name;
369  auto loc = orig_it->second;
370  m_locations_storage.erase(orig_it);
371  m_locations_storage.insert(std::pair<std::string, Map2DLocation>(new_name, loc));
372  out.addVocab32(VOCAB_OK);
373  }
374  else
375  {
376  yCError(MAP2DSERVER, "User requested an invalid rename operation");
377  out.addVocab32(VOCAB_ERR);
378  }
379  // ret = true;
380  }
381  else if (cmd == VOCAB_NAV_RENAME_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
382  {
383  std::string orig_name = in.get(3).asString();
384  std::string new_name = in.get(4).asString();
385 
386  std::map<std::string, Map2DArea>::iterator orig_it;
387  orig_it = m_areas_storage.find(orig_name);
388  std::map<std::string, Map2DArea>::iterator new_it;
389  new_it = m_areas_storage.find(new_name);
390 
391  if (orig_it != m_areas_storage.end() &&
392  new_it == m_areas_storage.end())
393  {
394  yCInfo(MAP2DSERVER) << "Area:" << orig_name << "renamed to:" << new_name;
395  auto area = orig_it->second;
396  m_areas_storage.erase(orig_it);
397  m_areas_storage.insert(std::pair<std::string, Map2DArea>(new_name,area));
398  out.addVocab32(VOCAB_OK);
399  }
400  else
401  {
402  yCError(MAP2DSERVER, "User requested an invalid rename operation");
403  out.addVocab32(VOCAB_ERR);
404  }
405 // ret = true;
406  }
407  else if (cmd == VOCAB_NAV_RENAME_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
408  {
409  std::string orig_name = in.get(3).asString();
410  std::string new_name = in.get(4).asString();
411 
412  std::map<std::string, Map2DPath>::iterator orig_it;
413  orig_it = m_paths_storage.find(orig_name);
414  std::map<std::string, Map2DPath>::iterator new_it;
415  new_it = m_paths_storage.find(new_name);
416 
417  if (orig_it != m_paths_storage.end() &&
418  new_it == m_paths_storage.end())
419  {
420  yCInfo(MAP2DSERVER) << "Path:" << orig_name << "renamed to:" << new_name;
421  auto area = orig_it->second;
422  m_paths_storage.erase(orig_it);
423  m_paths_storage.insert(std::pair<std::string, Map2DPath>(new_name, area));
424  out.addVocab32(VOCAB_OK);
425  }
426  else
427  {
428  yCError(MAP2DSERVER, "User requested an invalid rename operation");
429  out.addVocab32(VOCAB_ERR);
430  }
431  // ret = true;
432  }
433  else if (cmd == VOCAB_NAV_DELETE_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
434  {
435  std::string name = in.get(3).asString();
436 
437  std::map<std::string, Map2DArea>::iterator it;
438  it = m_areas_storage.find(name);
439  if (it != m_areas_storage.end())
440  {
441  yCInfo(MAP2DSERVER) << "Deleted area" << name;
442  m_areas_storage.erase(it);
443  out.addVocab32(VOCAB_OK);
444  }
445  else
446  {
447  yCError(MAP2DSERVER, "User requested an invalid area name");
448  out.addVocab32(VOCAB_ERR);
449  }
450 
451  // ret = true;
452  }
453  else if (cmd == VOCAB_NAV_GET_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
454  {
455  std::string name = in.get(3).asString();
456 
457  std::map<std::string, Map2DLocation>::iterator it;
458  it = m_locations_storage.find(name);
459  if (it != m_locations_storage.end())
460  {
461  out.addVocab32(VOCAB_OK);
462  Map2DLocation loc = it->second;
463  yCInfo(MAP2DSERVER) << "Retrieved location" << name << "at" << loc.toString();
464  out.addString(loc.map_id);
465  out.addFloat64(loc.x);
466  out.addFloat64(loc.y);
467  out.addFloat64(loc.theta);
468  }
469  else
470  {
471  out.addVocab32(VOCAB_ERR);
472  yCError(MAP2DSERVER, "User requested an invalid location name");
473  }
474  //ret = true;
475  }
476  else if (cmd == VOCAB_NAV_GET_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
477  {
478  std::string area_name = in.get(3).asString();
479 
480  std::map<std::string, Map2DArea>::iterator it;
481  it = m_areas_storage.find(area_name);
482  if (it != m_areas_storage.end())
483  {
484  Map2DArea area = it->second;
485  yarp::os::Bottle areabot;
486  Map2DArea areatemp = area;
487  if (Property::copyPortable(areatemp, areabot) == false)
488  {
489  yCError(MAP2DSERVER) << "VOCAB_NAV_GET_X VOCAB_NAV_AREA failed copyPortable()";
490  out.addVocab32(VOCAB_ERR);
491  }
492  else
493  {
494  yCInfo(MAP2DSERVER) << "Retrieved area" << area_name << "at" << area.toString();
495  out.addVocab32(VOCAB_OK);
496 
497  yarp::os::Bottle& areabot = out.addList();
498  Property::copyPortable(areatemp, areabot);
499  }
500  }
501  else
502  {
503  out.addVocab32(VOCAB_ERR);
504  yCError(MAP2DSERVER, "User requested an invalid area name");
505  }
506  //ret = true;
507  }
508  else if (cmd == VOCAB_NAV_GET_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
509  {
510  std::string path_name = in.get(3).asString();
511 
512  std::map<std::string, Map2DPath>::iterator it;
513  it = m_paths_storage.find(path_name);
514  if (it != m_paths_storage.end())
515  {
516  Map2DPath path = it->second;
517  yarp::os::Bottle pathbot;
518  Map2DPath pathtemp = path;
519  if (Property::copyPortable(pathtemp, pathbot) == false)
520  {
521  yCError(MAP2DSERVER) << "VOCAB_NAV_GET_X VOCAB_NAV_PATH failed copyPortable()";
522  out.addVocab32(VOCAB_ERR);
523  }
524  else
525  {
526  yCInfo(MAP2DSERVER) << "Retrieved path" << path_name << "at" << path.toString();
527  out.addVocab32(VOCAB_OK);
528 
529  yarp::os::Bottle& pathbot = out.addList();
530  Property::copyPortable(pathtemp, pathbot);
531  }
532  }
533  else
534  {
535  out.addVocab32(VOCAB_ERR);
536  yCError(MAP2DSERVER, "User requested an invalid path name");
537  }
538  //ret = true;
539  }
540  else if (cmd == VOCAB_NAV_STORE_X && in.get(2).asVocab32() == VOCAB_NAV_LOCATION)
541  {
542  Map2DLocation location;
543  std::string name = in.get(3).asString();
544 
545  location.map_id = in.get(4).asString();
546  location.x = in.get(5).asFloat64();
547  location.y = in.get(6).asFloat64();
548  location.theta = in.get(7).asFloat64();
549 
550  m_locations_storage.insert(std::pair<std::string, Map2DLocation>(name, location));
551  yCInfo(MAP2DSERVER) << "Added location" << name << "at" << location.toString();
552  out.addVocab32(VOCAB_OK);
553  //ret = true;
554  }
555  else if (cmd == VOCAB_NAV_STORE_X && in.get(2).asVocab32() == VOCAB_NAV_AREA)
556  {
557  Map2DArea area;
558  std::string area_name = in.get(3).asString();
559 
560  Value& b = in.get(4);
561  if (Property::copyPortable(b, area))
562  {
563  m_areas_storage.insert(std::pair<std::string, Map2DArea>(area_name, area));
564  yCInfo(MAP2DSERVER) << "Added area" << area_name << "at" << area.toString();
565  out.addVocab32(VOCAB_OK);
566  }
567  else
568  {
569  yCError(MAP2DSERVER) << "VOCAB_NAV_STORE_X VOCAB_NAV_AREA failed copyPortable()";
570  out.addVocab32(VOCAB_ERR);
571  }
572  //ret = true;
573  }
574  else if (cmd == VOCAB_NAV_STORE_X && in.get(2).asVocab32() == VOCAB_NAV_PATH)
575  {
576  Map2DPath path;
577  std::string path_name = in.get(3).asString();
578 
579  Value& b = in.get(4);
580  if (Property::copyPortable(b, path))
581  {
582  m_paths_storage.insert(std::pair<std::string, Map2DPath>(path_name, path));
583  yCInfo(MAP2DSERVER) << "Added path" << path_name << "at" << path.toString();
584  out.addVocab32(VOCAB_OK);
585  }
586  else
587  {
588  yCError(MAP2DSERVER) << "VOCAB_NAV_STORE_X VOCAB_NAV_PATH failed copyPortable()";
589  out.addVocab32(VOCAB_ERR);
590  }
591  //ret = true;
592  }
593  else
594  {
595  yCError(MAP2DSERVER) << "Invalid vocab received:" << in.toString();
596  out.clear();
597  out.addVocab32(VOCAB_ERR);
598  }
599  }
600  else
601  {
602  yCError(MAP2DSERVER) << "Invalid vocab received:" << in.toString();
603  out.clear();
605  }
606 }
607 
608 void Map2DServer::parse_string_command(yarp::os::Bottle& in, yarp::os::Bottle& out)
609 {
610  if (in.get(0).asString() == "save_locations&areas" && in.get(1).isString())
611  {
612  if(save_locations_and_areas(in.get(1).asString()))
613  {
614  out.addString(in.get(1).asString() + " successfully saved");
615  }
616  else
617  {
618  out.addString("save_locations&areas failed");
619  }
620  }
621  else if (in.get(0).asString() == "load_locations&areas" && in.get(1).isString())
622  {
623  if(load_locations_and_areas(in.get(1).asString()))
624  {
625  out.addString(in.get(1).asString() + " successfully loaded");
626  }
627  else
628  {
629  out.addString("load_locations&areas failed");
630  }
631  }
632  else if(in.get(0).asString() == "list_locations")
633  {
634  std::map<std::string, Map2DLocation>::iterator it;
635  for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
636  {
637  out.addString(it->first);
638  }
639  }
640  else if (in.get(0).asString() == "list_areas")
641  {
642  std::map<std::string, Map2DArea>::iterator it;
643  for (it = m_areas_storage.begin(); it != m_areas_storage.end(); ++it)
644  {
645  out.addString(it->first);
646  }
647  }
648  else if (in.get(0).asString() == "list_paths")
649  {
650  std::map<std::string, Map2DPath>::iterator it;
651  for (it = m_paths_storage.begin(); it != m_paths_storage.end(); ++it)
652  {
653  out.addString(it->first);
654  }
655  }
656  else if (in.get(0).asString() == "save_maps" && in.get(1).isString())
657  {
658  if(saveMaps(in.get(1).asString()))
659  {
660  out.addString(in.get(1).asString() + " successfully saved");
661  }
662  else
663  {
664  out.addString("save_maps failed");
665  }
666  }
667  else if (in.get(0).asString() == "load_maps" && in.get(1).isString())
668  {
669  if(loadMaps(in.get(1).asString()))
670  {
671  out.addString(in.get(1).asString() + " successfully loaded");
672  }
673  else
674  {
675  out.addString("load_maps failed");
676  }
677  }
678  else if (in.get(0).asString() == "save_map" && in.get(1).isString() && in.get(2).isString())
679  {
680  std::string map_name = in.get(1).asString();
681  std::string map_file = in.get(2).asString() + ".map";
682  auto p = m_maps_storage.find(map_name);
683  if (p == m_maps_storage.end())
684  {
685  out.addString("save_map failed: map " + map_name + " not found");
686  }
687  else
688  {
689  bool b = p->second.saveToFile(map_file);
690  if (b)
691  {
692  out.addString(map_file + " successfully saved");
693  }
694  else
695  {
696  out.addString("save_map failed: unable to save " + map_name + " to "+ map_file);
697  }
698  }
699  }
700  else if (in.get(0).asString() == "load_map" && in.get(1).isString())
701  {
702  MapGrid2D map;
703  bool r = map.loadFromFile(in.get(1).asString());
704  if(r)
705  {
706  std::string map_name= map.getMapName();
707  auto p = m_maps_storage.find(map_name);
708  if (p == m_maps_storage.end())
709  {
710  m_maps_storage[map_name] = map;
711  out.addString(in.get(1).asString() + " successfully loaded.");
712  }
713  else
714  {
715  out.addString(in.get(1).asString() + " already exists, skipping.");
716  }
717  }
718  else
719  {
720  out.addString("load_map failed. Unable to load " + in.get(1).asString());
721  }
722  }
723  else if(in.get(0).asString() == "list_maps")
724  {
725  std::map<std::string, MapGrid2D>::iterator it;
726  for (it = m_maps_storage.begin(); it != m_maps_storage.end(); ++it)
727  {
728  out.addString(it->first);
729  }
730  }
731  else if(in.get(0).asString() == "clear_all_locations")
732  {
733  m_locations_storage.clear();
734  out.addString("all locations cleared");
735  }
736  else if (in.get(0).asString() == "clear_all_areas")
737  {
738  m_areas_storage.clear();
739  out.addString("all areas cleared");
740  }
741  else if (in.get(0).asString() == "clear_all_paths")
742  {
743  m_paths_storage.clear();
744  out.addString("all paths cleared");
745  }
746  else if(in.get(0).asString() == "clear_all_maps")
747  {
748  m_maps_storage.clear();
749  out.addString("all maps cleared");
750  }
751  else if (in.get(0).asString() == "enable_maps_compression")
752  {
753  bool b = true;
754  for (auto it=m_maps_storage.begin(); it!= m_maps_storage.end(); it++)
755  {b &= it->second.enable_map_compression_over_network(in.get(1).asBool());}
756  if (b) {out.addString("compression mode of all maps set to:"+ in.get(1).asString());}
757  else {out.addString("failed to set compression mode");}
758  }
759  else if(in.get(0).asString() == "help")
760  {
761  out.addVocab32("many");
762  out.addString("'save_locations&areas <full path filename>' to save locations and areas on a file");
763  out.addString("'load_locations&areas <full path filename>' to load locations and areas from a file");
764  out.addString("'list_locations' to view a list of all stored locations");
765  out.addString("'list_areas' to view a list of all stored areas");
766  out.addString("'list_paths' to view a list of all stored paths");
767  out.addString("'clear_all_locations' to clear all stored locations");
768  out.addString("'clear_all_areas' to clear all stored areas");
769  out.addString("'clear_all_paths' to clear all stored paths");
770  out.addString("'save_maps <full path>' to save a map collection to a folder");
771  out.addString("'load_maps <full path>' to load a map collection from a folder");
772  out.addString("'save_map <map_name> <full path>' to save a single map");
773  out.addString("'load_map <full path>' to load a single map");
774  out.addString("'list_maps' to view a list of all stored maps");
775  out.addString("'clear_all_maps' to clear all stored maps");
776  out.addString("'enable_maps_compression <0/1>' to set the map transmission mode");
777  }
778  else
779  {
780  out.addString("request not understood, call 'help' to see a list of available commands");
781  }
782 
783  //updateVizMarkers();
784 }
785 
786 bool Map2DServer::read(yarp::os::ConnectionReader& connection)
787 {
788  std::lock_guard<std::mutex> lock(m_mutex);
789  yarp::os::Bottle in;
790  yarp::os::Bottle out;
791  bool ok = in.read(connection);
792  if (!ok) {
793  return false;
794  }
795 
796  //parse string command
797  if(in.get(0).isString())
798  {
799  parse_string_command(in, out);
800  }
801  // parse vocab command
802  else if(in.get(0).isVocab32())
803  {
804  parse_vocab_command(in, out);
805  }
806 
807  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
808  if (returnToSender != nullptr)
809  {
810  out.write(*returnToSender);
811  }
812  else
813  {
814  yCError(MAP2DSERVER) << "Invalid return to sender";
815  }
816  return true;
817 }
818 
819 bool Map2DServer::saveMaps(std::string mapsfile)
820 {
821  if (m_maps_storage.size() == 0)
822  {
823  yCError(MAP2DSERVER) << "Map storage is empty";
824  return false;
825  }
826  std::ofstream file;
827  file.open(mapsfile.c_str());
828  if (!file.is_open())
829  {
830  yCError(MAP2DSERVER) << "Sorry unable to open" << mapsfile;
831  return false;
832  }
833  bool ret = true;
834  for (auto& it : m_maps_storage)
835  {
836  std::string map_filename = it.first + ".map";
837  file << "mapfile: ";
838  file << map_filename;
839  file << '\n';
840  ret &= it.second.saveToFile(map_filename);
841  }
842  file.close();
843  return ret;
844 }
845 
846 bool Map2DServer::loadMaps(std::string mapsfile)
847 {
848  bool ret = true;
849  std::ifstream file;
850  file.open(mapsfile.c_str());
851  if (!file.is_open())
852  {
853  yCError(MAP2DSERVER) << "loadMaps() Unable to open:" << mapsfile;
854  return false;
855  }
856  while (!file.eof())
857  {
858  std::string dummy;
859  std::string buffer;
860  std::getline(file, buffer);
861  std::istringstream iss(buffer);
862  iss >> dummy;
863  if (dummy == "") {
864  break;
865  }
866  if (dummy == "mapfile:")
867  {
868  std::string mapfilename;
869  iss >> mapfilename;
870  std::string option;
871  iss >> option;
872  std::string mapfilenameWithPath = m_rf_mapCollection.findFile(mapfilename);
873  MapGrid2D map;
874  bool r = map.loadFromFile(mapfilenameWithPath);
875  if (r)
876  {
877  std::string map_name= map.getMapName();
878  auto p = m_maps_storage.find(map_name);
879  if (p == m_maps_storage.end())
880  {
881  if (option == "crop") {
882  map.crop(-1, -1, -1, -1);
883  }
884  m_maps_storage[map_name] = map;
885  }
886  else
887  {
888  yCError(MAP2DSERVER) << "A map with the same name '" << map_name << "'was found, skipping...";
889  ret = false;
890  }
891  }
892  else
893  {
894  yCError(MAP2DSERVER) << "Problems opening map file" << mapfilenameWithPath;
895  ret = false;
896  }
897  }
898  else
899  {
900  yCError(MAP2DSERVER) << "Invalid syntax, missing mapfile tag";
901  ret = false;
902  }
903  }
904  file.close();
905  return ret;
906 }
907 
909 {
910  yCWarning(MAP2DSERVER) << "The 'map2DServer' device is deprecated in favour of 'map2D_nws_yarp'.";
911  yCWarning(MAP2DSERVER) << "The old device is no longer supported, and it will be deprecated in YARP 3.6 and removed in YARP 4.";
912  yCWarning(MAP2DSERVER) << "Please update your scripts.";
913 
914  Property params;
915  params.fromString(config.toString());
916 
917  std::string collection_file_name="maps_collection.ini";
918  std::string locations_file_name="locations.ini";
919  if (config.check("mapCollectionFile"))
920  {
921  collection_file_name= config.find("mapCollectionFile").asString();
922  }
923 
924  if (config.check("mapCollectionContext"))
925  {
926  std::string collection_context_name= config.find("mapCollectionContext").asString();
927  m_rf_mapCollection.setDefaultContext(collection_context_name.c_str());
928  std::string collection_file_with_path = m_rf_mapCollection.findFile(collection_file_name);
929  std::string locations_file_with_path = m_rf_mapCollection.findFile(locations_file_name);
930 
931  if (locations_file_with_path=="")
932  {
933  yCWarning(MAP2DSERVER) << "Unable to find file:" << locations_file_with_path << "within the specified context:" << collection_context_name;
934  }
935  else
936  {
937  bool ret = load_locations_and_areas(locations_file_with_path);
938  if (ret) { yCInfo(MAP2DSERVER) << "Location file" << locations_file_with_path << "successfully loaded."; }
939  else { yCError(MAP2DSERVER) << "Problems opening file" << locations_file_with_path; }
940  }
941 
942  if (collection_file_with_path=="")
943  {
944  yCWarning(MAP2DSERVER) << "Unable to find file:" << collection_file_name << "within the specified context:" << collection_context_name;
945  }
946  else
947  {
948  if (loadMaps(collection_file_with_path))
949  {
950  yCInfo(MAP2DSERVER) << "Map collection file:" << collection_file_with_path << "successfully loaded.";
951  if (m_maps_storage.size() > 0)
952  {
953  yCInfo(MAP2DSERVER) << "Available maps are:";
954  for (auto& it : m_maps_storage)
955  {
956  yCInfo(MAP2DSERVER) << it.first;
957  }
958  }
959  else
960  {
961  yCInfo(MAP2DSERVER) << "No maps available";
962  }
963  if (m_locations_storage.size() > 0)
964  {
965  yCInfo(MAP2DSERVER) << "Available Locations are:";
966  for (auto& it : m_locations_storage)
967  {
968  yCInfo(MAP2DSERVER) << it.first;
969  }
970  }
971  else
972  {
973  yCInfo(MAP2DSERVER) << "No locations available";
974  }
975 
976  if (m_areas_storage.size() > 0)
977  {
978  yCInfo(MAP2DSERVER) << "Available areas are:";
979  for (auto& it : m_areas_storage)
980  {
981  yCInfo(MAP2DSERVER) << it.first;
982  }
983  }
984  else
985  {
986  yCInfo(MAP2DSERVER) << "No areas available";
987  }
988  }
989  else
990  {
991  yCError(MAP2DSERVER) << "Unable to load map collection file:" << collection_file_with_path;
992  return false;
993  }
994  }
995  }
996 
997  if (!config.check("name"))
998  {
999  m_rpcPortName = "/mapServer/rpc";
1000  }
1001  else
1002  {
1003  m_rpcPortName = config.find("name").asString();
1004  }
1005 
1006  //open rpc port
1007  if (!m_rpcPort.open(m_rpcPortName))
1008  {
1009  yCError(MAP2DSERVER, "Failed to open port %s", m_rpcPortName.c_str());
1010  return false;
1011  }
1012  m_rpcPort.setReader(*this);
1013 
1014  //ROS configuration
1015  if (config.check("ROS"))
1016  {
1017  yCInfo(MAP2DSERVER, "Configuring ROS params");
1018  Bottle ROS_config = config.findGroup("ROS");
1019  if (ROS_config.check("enable_ros_publisher") == false)
1020  {
1021  yCError(MAP2DSERVER) << "Missing 'enable_ros_publisher' in ROS group";
1022  return false;
1023  }
1024  if (ROS_config.find("enable_ros_publisher").asInt32() == 1 || ROS_config.find("enable_ros_publisher").asString() == "true")
1025  {
1026  m_enable_publish_ros_map = true;
1027  yCInfo(MAP2DSERVER) << "Enabled ROS publisher";
1028  }
1029  if (ROS_config.check("enable_ros_subscriber") == false)
1030  {
1031  yCError(MAP2DSERVER) << "Missing 'enable_ros_subscriber' in ROS group";
1032  return false;
1033  }
1034  if (ROS_config.find("enable_ros_subscriber").asInt32() == 1 || ROS_config.find("enable_ros_subscriber").asString() == "true")
1035  {
1036  m_enable_subscribe_ros_map = true;
1037  yCInfo(MAP2DSERVER) << "Enabled ROS subscriber";
1038  }
1039 
1040  if (m_enable_subscribe_ros_map || m_enable_publish_ros_map)
1041  {
1042  if (m_rosNode == nullptr)
1043  {
1044  m_rosNode = new yarp::os::Node(ROSNODENAME);
1045  }
1046  if (m_enable_publish_ros_map && !m_rosPublisherPort_map.topic(ROSTOPICNAME_MAP))
1047  {
1048  yCError(MAP2DSERVER) << "Unable to publish to" << ROSTOPICNAME_MAP << "topic, check your YARP-ROS network configuration";
1049  return false;
1050  }
1051  if (m_enable_publish_ros_map && !m_rosPublisherPort_metamap.topic(ROSTOPICNAME_MAPMETADATA))
1052  {
1053  yCError(MAP2DSERVER) << "Unable to publish to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration";
1054  return false;
1055  }
1056 
1057  if (m_enable_subscribe_ros_map && !m_rosSubscriberPort_map.topic(ROSTOPICNAME_MAP))
1058  {
1059  yCError(MAP2DSERVER) << "Unable to subscribe to " << ROSTOPICNAME_MAP << " topic, check your YARP-ROS network configuration";
1060  return false;
1061  }
1062  if (m_enable_subscribe_ros_map && !m_rosSubscriberPort_metamap.topic(ROSTOPICNAME_MAPMETADATA))
1063  {
1064  yCError(MAP2DSERVER) << "Unable to subscribe to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration";
1065  return false;
1066  }
1067  m_rosSubscriberPort_map.setStrict();
1068  m_rosSubscriberPort_metamap.setStrict();
1069 
1070  }
1071  // m_rosPublisherPort_markers.topic("/locationServerMarkers");
1072  }
1073  else
1074  {
1075  //no ROS options
1076  }
1077  //yarp::os::Time::delay(5);
1078  yarp::rosmsg::nav_msgs::OccupancyGrid* map_ros = nullptr;
1079  yarp::rosmsg::nav_msgs::MapMetaData* metamap_ros = nullptr;
1080 
1081  map_ros = m_rosSubscriberPort_map.read(true);
1082  metamap_ros = m_rosSubscriberPort_metamap.read(true);
1083  if (map_ros!=nullptr && metamap_ros!=nullptr)
1084  {
1085  yCInfo(MAP2DSERVER) << "Received map for ROS";
1086  std::string map_name = "ros_map";
1087  MapGrid2D map;
1088  map.setSize_in_cells(map_ros->info.width,map_ros->info.height);
1089  map.setResolution( map_ros->info.resolution);
1090  map.setMapName(map_name);
1092  map_ros->info.origin.orientation.y,
1093  map_ros->info.origin.orientation.z,
1094  map_ros->info.origin.orientation.w);
1097  double orig_angle = vec[2];
1098  map.setOrigin(map_ros->info.origin.position.x,map_ros->info.origin.position.y,orig_angle);
1099  for (size_t y = 0; y < map_ros->info.height; y++) {
1100  for (size_t x=0; x< map_ros->info.width; x++)
1101  {
1102  XYCell cell(x,map_ros->info.height-1-y);
1103  double occ = map_ros->data[x+y*map_ros->info.width];
1104  map.setOccupancyData(cell,occ);
1105 
1106  if (occ >= 0 && occ <= 70) {
1107  map.setMapFlag(cell, MapGrid2D::MAP_CELL_FREE);
1108  } else if (occ >= 71 && occ <= 100) {
1109  map.setMapFlag(cell, MapGrid2D::MAP_CELL_WALL);
1110  } else {
1111  map.setMapFlag(cell, MapGrid2D::MAP_CELL_UNKNOWN);
1112  }
1113  }
1114  }
1115  auto p = m_maps_storage.find(map_name);
1116  if (p == m_maps_storage.end())
1117  {
1118  yCInfo(MAP2DSERVER) << "Added map "<< map_name <<" to mapServer";
1119  m_maps_storage[map_name] = map;
1120  }
1121  }
1122  return true;
1123 }
1124 
1126 {
1127  yCTrace(MAP2DSERVER, "Close");
1128  if (m_enable_publish_ros_map)
1129  {
1130  m_rosPublisherPort_map.interrupt();
1131  m_rosPublisherPort_metamap.interrupt();
1132  m_rosPublisherPort_map.close();
1133  m_rosPublisherPort_metamap.close();
1134  }
1135  if (m_enable_subscribe_ros_map)
1136  {
1137  m_rosSubscriberPort_map.interrupt();
1138  m_rosSubscriberPort_metamap.interrupt();
1139  m_rosSubscriberPort_map.close();
1140  m_rosSubscriberPort_metamap.close();
1141  }
1142  return true;
1143 }
1144 
1145 bool Map2DServer::priv_load_locations_and_areas_v1(std::ifstream& file)
1146 {
1147  std::string buffer;
1148  std::getline(file, buffer);
1149  if (buffer != "Locations:")
1150  {
1151  yCError(MAP2DSERVER) << "Unable to parse Locations section!";
1152  return false;
1153  }
1154 
1155  while (1)
1156  {
1157  std::getline(file, buffer);
1158  if (buffer == "Areas:") {
1159  break;
1160  }
1161  if (file.eof())
1162  {
1163  yCError(MAP2DSERVER) << "Unexpected End Of File";
1164  return false;
1165  }
1166  Bottle b;
1167  b.fromString(buffer);
1168  size_t bot_size = b.size();
1169  if (bot_size != 5)
1170  {
1171  yCError(MAP2DSERVER) << "Unable to parse contents of Areas section!";
1172  return false;
1173  }
1174  Map2DLocation location;
1175  std::string name = b.get(0).asString();
1176  location.map_id = b.get(1).asString();
1177  location.x = b.get(2).asFloat64();
1178  location.y = b.get(3).asFloat64();
1179  location.theta = b.get(4).asFloat64();
1180  m_locations_storage[name] = location;
1181  }
1182 
1183  if (buffer != "Areas:")
1184  {
1185  yCError(MAP2DSERVER) << "Unable to parse Areas section!";
1186  return false;
1187  }
1188 
1189  while (1)
1190  {
1191  Map2DArea area;
1192  std::getline(file, buffer);
1193  if (file.eof()) {
1194  break;
1195  }
1196 
1197  Bottle b;
1198  b.fromString(buffer);
1199  size_t bot_size = b.size();
1200  std::string name = b.get(0).asString();
1201  area.map_id = b.get(1).asString();
1202  size_t area_size = b.get(2).asInt32();
1203  if (area_size <= 0 || bot_size != area_size * 2 + 3)
1204  {
1205  yCError(MAP2DSERVER) << "Unable to parse contents of Areas section!";
1206  return false;
1207  }
1208  for (size_t ai = 3; ai < bot_size; ai += 2)
1209  {
1210  double xpos = b.get(ai).asFloat64();
1211  double ypos = b.get(ai + 1).asFloat64();
1212  area.points.push_back(yarp::math::Vec2D<double>(xpos, ypos));
1213  }
1214  m_areas_storage[name] = area;
1215  }
1216  return true;
1217 }
1218 
1219 bool Map2DServer::priv_load_locations_and_areas_v2(std::ifstream& file)
1220 {
1221  std::string buffer;
1222  std::getline(file, buffer);
1223  if (buffer != "Locations:")
1224  {
1225  yCError(MAP2DSERVER) << "Unable to parse Locations section!";
1226  return false;
1227  }
1228 
1229  while (1)
1230  {
1231  std::getline(file, buffer);
1232  if (buffer == "Areas:") {
1233  break;
1234  }
1235  if (file.eof())
1236  {
1237  yCError(MAP2DSERVER) << "Unexpected End Of File";
1238  return false;
1239  }
1240  Bottle b;
1241  b.fromString(buffer);
1242  size_t bot_size = b.size();
1243  if (bot_size != 5)
1244  {
1245  yCError(MAP2DSERVER) << "Unable to parse contents of Areas section!";
1246  return false;
1247  }
1248  Map2DLocation location;
1249  std::string name = b.get(0).asString();
1250  location.map_id = b.get(1).asString();
1251  location.x = b.get(2).asFloat64();
1252  location.y = b.get(3).asFloat64();
1253  location.theta = b.get(4).asFloat64();
1254  m_locations_storage[name] = location;
1255  }
1256 
1257  if (buffer != "Areas:")
1258  {
1259  yCError(MAP2DSERVER) << "Unable to parse Areas section!";
1260  return false;
1261  }
1262 
1263  while (1)
1264  {
1265  Map2DArea area;
1266  std::getline(file, buffer);
1267  if (buffer == "Paths:") {
1268  break;
1269  }
1270  if (file.eof()) {
1271  break;
1272  }
1273 
1274  Bottle b;
1275  b.fromString(buffer);
1276  size_t bot_size = b.size();
1277  std::string name = b.get(0).asString();
1278  area.map_id = b.get(1).asString();
1279  size_t area_size = b.get(2).asInt32();
1280  if (area_size <= 0 || bot_size != area_size * 2 + 3)
1281  {
1282  yCError(MAP2DSERVER) << "Unable to parse contents of Areas section!";
1283  return false;
1284  }
1285  for (size_t ai = 3; ai < bot_size; ai += 2)
1286  {
1287  double xpos = b.get(ai).asFloat64();
1288  double ypos = b.get(ai + 1).asFloat64();
1289  area.points.push_back(yarp::math::Vec2D<double>(xpos, ypos));
1290  }
1291  m_areas_storage[name] = area;
1292  }
1293 
1294  if (buffer != "Paths:")
1295  {
1296  yCError(MAP2DSERVER) << "Unable to parse Paths section!";
1297  return false;
1298  }
1299 
1300  while (1)
1301  {
1302  Map2DPath path;
1303  std::getline(file, buffer);
1304  if (file.eof()) {
1305  break;
1306  }
1307 
1308  Bottle b;
1309  b.fromString(buffer);
1310  size_t bot_size = b.size();
1311  YARP_UNUSED(bot_size);
1312  std::string name = b.get(0).asString();
1313  size_t i=1;
1314  do
1315  {
1316  if (b.get(i).isList())
1317  {
1318  Bottle* ll = b.get(i).asList();
1319  if (ll && ll->size() == 4)
1320  {
1321  Map2DLocation loc;
1322  loc.map_id = ll->get(0).asString();
1323  loc.x = ll->get(1).asFloat64();
1324  loc.y = ll->get(2).asFloat64();
1325  loc.theta= ll->get(3).asFloat64();
1326  path.push_back(loc);
1327  }
1328  else
1329  {
1330  yCError(MAP2DSERVER) << "Unable to parse contents of Paths section!";
1331  return false;
1332  }
1333  }
1334  else
1335  {
1336  break;
1337  }
1338  i++;
1339  }
1340  while (1);
1341  m_paths_storage[name] = path;
1342  }
1343 
1344  return true;
1345 }
1346 
1347 bool Map2DServer::load_locations_and_areas(std::string locations_file)
1348 {
1349  std::ifstream file;
1350  file.open (locations_file.c_str());
1351 
1352  if(!file.is_open())
1353  {
1354  yCError(MAP2DSERVER) << "Unable to open" << locations_file << "locations file.";
1355  return false;
1356  }
1357 
1358  std::string buffer;
1359 
1360  std::getline(file, buffer);
1361  if (buffer != "Version:")
1362  {
1363  yCError(MAP2DSERVER) << "Unable to parse Version section!";
1364  file.close();
1365  return false;
1366  }
1367  std::getline(file, buffer);
1368  int version = atoi(buffer.c_str());
1369 
1370  if (version == 1)
1371  {
1372  if (!priv_load_locations_and_areas_v1(file))
1373  {
1374  yCError(MAP2DSERVER) << "Call to load_locations_and_areas_v1 failed";
1375  file.close();
1376  return false;
1377  }
1378  }
1379  else if (version == 2)
1380  {
1381  if (!priv_load_locations_and_areas_v2(file))
1382  {
1383  yCError(MAP2DSERVER) << "Call to load_locations_and_areas_v2 failed";
1384  file.close();
1385  return false;
1386  }
1387  }
1388  else
1389  {
1390  yCError(MAP2DSERVER) << "Only versions 1,2 supported!";
1391  file.close();
1392  return false;
1393  }
1394 
1395  //on success
1396  file.close();
1397  yCDebug(MAP2DSERVER) << "Locations file" << locations_file << "loaded, "
1398  << m_locations_storage.size() << "locations and "
1399  << m_areas_storage.size() << " areas and "
1400  << m_paths_storage.size() << " paths available";
1401  return true;
1402 }
1403 
1404 bool Map2DServer::save_locations_and_areas(std::string locations_file)
1405 {
1406  std::ofstream file;
1407  file.open (locations_file.c_str());
1408 
1409  if(!file.is_open())
1410  {
1411  yCError(MAP2DSERVER) << "Unable to open" << locations_file << "locations file.";
1412  return false;
1413  }
1414 
1415  std::string s;
1416  Map2DLocation loc;
1417  Map2DArea area;
1418  s = " ";
1419 
1420  file << "Version:\n";
1421  file << "2\n";
1422 
1423  {
1424  file << "Locations:\n";
1425  std::map<std::string, Map2DLocation>::iterator it;
1426  for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
1427  {
1428  loc = it->second;
1429  file << it->first << s << loc.map_id << s << loc.x << s << loc.y << s << loc.theta << "\n";
1430  }
1431  }
1432 
1433  {
1434  file << "Areas:\n";
1435  std::map<std::string, Map2DArea>::iterator it2;
1436  for (it2 = m_areas_storage.begin(); it2 != m_areas_storage.end(); ++it2)
1437  {
1438  area = it2->second;
1439  file << it2->first << s << area.map_id << s << area.points.size() << s;
1440  for (size_t i = 0; i < area.points.size(); i++)
1441  {
1442  file << area.points[i].x << s;
1443  file << area.points[i].y << s;
1444  }
1445  file << "\n";
1446  }
1447  }
1448 
1449  {
1450  file << "Paths:\n";
1451  std::map<std::string, Map2DPath>::iterator it3;
1452  for (it3 = m_paths_storage.begin(); it3 != m_paths_storage.end(); ++it3)
1453  {
1454  file << it3->first << " "; // the name of the path
1455  for (size_t i=0; i<it3->second.size(); i++)
1456  {
1457  loc = it3->second[i];
1458  file << "( " <<loc.map_id << s << loc.x << s << loc.y << s << loc.theta << ") ";
1459  }
1460  file << "\n";
1461  }
1462  }
1463 
1464  file.close();
1465  yCDebug(MAP2DSERVER) << "Locations file" << locations_file << "saved.";
1466  return true;
1467 }
1468 
1469 bool Map2DServer::updateVizMarkers()
1470 {
1471  yarp::rosmsg::TickDuration dur; dur.sec = 0xFFFFFFFF;
1472  double yarpTimeStamp = yarp::os::Time::now();
1473  uint64_t time;
1474  uint64_t nsec_part;
1475  uint64_t sec_part;
1477  time = (uint64_t)(yarpTimeStamp * 1000000000UL);
1478  nsec_part = (time % 1000000000UL);
1479  sec_part = (time / 1000000000UL);
1480  if (sec_part > std::numeric_limits<unsigned int>::max())
1481  {
1482  yCWarning(MAP2DSERVER) << "Timestamp exceeded the 64 bit representation, resetting it to 0";
1483  sec_part = 0;
1484  }
1485 
1488  yarp::sig::Vector rpy(3);
1490 
1491  yarp::rosmsg::visualization_msgs::MarkerArray& markers = m_rosPublisherPort_markers.prepare();
1492  markers.markers.clear();
1493 
1494  std::map<std::string, Map2DLocation>::iterator it;
1495  int count = 1;
1496  for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it, ++count)
1497  {
1498  rpy[0] = 0; //x
1499  rpy[1] = 0; //y
1500  rpy[2] = it->second.theta / 180 * 3.14159265359; //z
1502  q.fromRotationMatrix(m);
1503 
1504  marker.header.frame_id = "map";
1505  tt.sec = (yarp::os::NetUint32) sec_part;;
1506  tt.nsec = (yarp::os::NetUint32) nsec_part;;
1507  marker.header.stamp = tt;
1508  marker.ns = "my_namespace";
1509  marker.id = count;
1512  marker.pose.position.x = it->second.x;
1513  marker.pose.position.y = it->second.y;
1514  marker.pose.position.z = 0;
1515  marker.pose.orientation.x = q.x();
1516  marker.pose.orientation.y = q.y();
1517  marker.pose.orientation.z = q.z();
1518  marker.pose.orientation.w = q.w();
1519  marker.scale.x = 1;
1520  marker.scale.y = 0.1;
1521  marker.scale.z = 0.1;
1522  marker.color.a = 1.0;
1523  marker.color.r = 0.0;
1524  marker.color.g = 1.0;
1525  marker.color.b = 0.0;
1526  marker.lifetime = dur;
1527  marker.text = it->first;
1528  markers.markers.push_back(marker);
1529  }
1530 
1531  m_rosPublisherPort_markers.write();
1532  return true;
1533 }
#define ROSNODENAME
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:15
constexpr yarp::conf::vocab32_t VOCAB_ERR
Definition: GenericVocabs.h:17
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_ERROR
Definition: IMap2D.h:253
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
#define ROSTOPICNAME_MAP
Definition: Map2D_nws_ros.h:86
#define ROSTOPICNAME_MAPMETADATA
Definition: Map2D_nws_ros.h:87
bool close() override
Close the DeviceDriver.
Map2DServer()
Map2DServer.
Definition: Map2DServer.cpp:38
bool loadMaps(std::string filename)
bool saveMaps(std::string filename)
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool load_locations_and_areas(std::string locations_file)
bool save_locations_and_areas(std::string locations_file)
std::string toString() const
Returns text representation of the area.
Definition: Map2DArea.cpp:133
std::vector< yarp::math::Vec2D< double > > points
Definition: Map2DArea.h:111
void push_back(yarp::dev::Nav2D::Map2DLocation loc)
Inserts a new location into the path @loc the location to be inserted.
Definition: Map2DPath.cpp:127
std::string toString() const
Returns text representation of the path.
Definition: Map2DPath.cpp:42
bool setResolution(double resolution)
Sets the resolution of the map, i.e.
Definition: MapGrid2D.cpp:1058
bool setOrigin(double x, double y, double theta)
Sets the origin of the map reference frame (according to ROS convention)
Definition: MapGrid2D.cpp:1024
std::string getMapName() const
Retrieves the map name.
Definition: MapGrid2D.cpp:1085
bool setSize_in_cells(size_t x, size_t y)
Sets the size of the map in cells.
Definition: MapGrid2D.cpp:1108
bool setMapName(std::string map_name)
Sets the map name.
Definition: MapGrid2D.cpp:1074
bool setMapFlag(XYCell cell, map_flags flag)
Set the flag of a specific cell of the map.
Definition: MapGrid2D.cpp:1136
bool crop(int left, int top, int right, int bottom)
Modifies the map, cropping pixels at the boundaries.
Definition: MapGrid2D.cpp:707
bool setOccupancyData(XYCell cell, double occupancy)
Set the occupancy data of a specific cell of the map.
Definition: MapGrid2D.cpp:1158
bool loadFromFile(std::string map_filename)
Loads a yarp map file from disk.
Definition: MapGrid2D.cpp:556
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
Definition: Quaternion.cpp:162
double x() const
Definition: Quaternion.cpp:81
yarp::sig::Matrix toRotationMatrix4x4() const
Converts a quaternion to a rotation matrix.
Definition: Quaternion.cpp:222
double z() const
Definition: Quaternion.cpp:91
double w() const
Definition: Quaternion.cpp:76
double y() const
Definition: Quaternion.cpp:86
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
void fromString(const std::string &text)
Initializes bottle from a string.
Definition: Bottle.cpp:204
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
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:240
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 check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:230
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:211
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:287
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
The Node class.
Definition: Node.h:24
A class for storing options and configuration information.
Definition: Property.h:34
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
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 bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list 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 bool isString() const
Checks if value is a string.
Definition: Value.cpp:156
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:228
virtual bool asBool() const
Get boolean value.
Definition: Value.cpp:186
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual bool isList() const
Checks if value is a list.
Definition: Value.cpp:162
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:240
virtual bool isVocab32() const
Checks if value is a vocabulary identifier.
Definition: Value.cpp:174
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
std::uint32_t nsec
Definition: TickTime.h:30
std::uint32_t sec
Definition: TickTime.h:29
yarp::conf::float64_t y
Definition: Point.h:33
yarp::conf::float64_t x
Definition: Point.h:32
yarp::conf::float64_t z
Definition: Point.h:34
yarp::rosmsg::geometry_msgs::Point position
Definition: Pose.h:33
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Pose.h:34
yarp::conf::float64_t y
Definition: Vector3.h:38
yarp::conf::float64_t z
Definition: Vector3.h:39
yarp::conf::float64_t x
Definition: Vector3.h:37
yarp::rosmsg::geometry_msgs::Pose origin
Definition: MapMetaData.h:46
yarp::conf::float32_t resolution
Definition: MapMetaData.h:43
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: MapMetaData.h:130
std::vector< std::int8_t > data
Definition: OccupancyGrid.h:43
yarp::rosmsg::nav_msgs::MapMetaData info
Definition: OccupancyGrid.h:42
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::conf::float32_t b
Definition: ColorRGBA.h:34
yarp::conf::float32_t a
Definition: ColorRGBA.h:35
yarp::conf::float32_t g
Definition: ColorRGBA.h:33
yarp::conf::float32_t r
Definition: ColorRGBA.h:32
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
std::vector< yarp::rosmsg::visualization_msgs::Marker > markers
Definition: MarkerArray.h:30
yarp::rosmsg::std_msgs::ColorRGBA color
Definition: Marker.h:101
static const std::uint8_t ARROW
Definition: Marker.h:78
yarp::rosmsg::TickDuration lifetime
Definition: Marker.h:102
yarp::rosmsg::geometry_msgs::Vector3 scale
Definition: Marker.h:100
static const std::uint8_t ADD
Definition: Marker.h:90
yarp::rosmsg::geometry_msgs::Pose pose
Definition: Marker.h:99
yarp::rosmsg::std_msgs::Header header
Definition: Marker.h:94
A class for a Matrix.
Definition: Matrix.h:43
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
An interface for the device drivers.
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
Definition: math.cpp:847
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
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
An interface to the operating system, including Port based communication.
std::uint32_t NetUint32
Definition of the NetUint32 type.
Definition: NetUint32.h:30
Signal processing.
Definition: Image.h:22
std::string toString() const
Returns text representation of the location.
Definition: Map2DLocation.h:74
#define YARP_UNUSED(var)
Definition: api.h:162