YARP
Yet Another Robot Platform
map2DStorage.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 "map2DStorage.h"
9#include <yarp/dev/IMap2D.h>
12#include <yarp/math/Math.h>
13#include <yarp/os/Log.h>
15#include <yarp/os/LogStream.h>
16#include <mutex>
17#include <cstdlib>
18#include <fstream>
19
20using namespace yarp::sig;
21using namespace yarp::dev;
22using namespace yarp::dev::Nav2D;
23using namespace yarp::os;
24
25namespace {
26YARP_LOG_COMPONENT(MAP2DSTORAGE, "yarp.device.map2DStorage")
27}
28
34{
35}
36
38
39bool Map2DStorage::saveMapsCollection(std::string mapsfile)
40{
41 //check if the storage is not empty
42 if (m_maps_storage.size() == 0)
43 {
44 yCError(MAP2DSTORAGE) << "Map storage is empty";
45 return false;
46 }
47
48 //open the map collection file
49 std::ofstream file;
50 file.open(mapsfile.c_str());
51 if (!file.is_open())
52 {
53 yCError(MAP2DSTORAGE) << "Sorry unable to open" << mapsfile;
54 return false;
55 }
56
57 bool ret = true;
58 //for each map...
59 for (auto& it : m_maps_storage)
60 {
61 //add an entry to the map collection file
62 std::string map_filename = it.first + ".map";
63 file << "mapfile: ";
64 file << map_filename;
65 file << '\n';
66
67 //save each individual map to a file
68 ret &= it.second.saveToFile(map_filename);
69 }
70
71 file.close();
72 return ret;
73}
74
75bool Map2DStorage::loadMapsCollection(std::string mapsfile)
76{
77 bool ret = true;
78 std::ifstream file;
79 file.open(mapsfile.c_str());
80 if (!file.is_open())
81 {
82 yCError(MAP2DSTORAGE) << "loadMaps() Unable to open:" << mapsfile;
83 return false;
84 }
85 while (!file.eof())
86 {
87 std::string dummy;
88 std::string buffer;
89 std::getline(file, buffer);
90 std::istringstream iss(buffer);
91 iss >> dummy;
92 if (dummy == "") {
93 break;
94 }
95 if (dummy == "mapfile:")
96 {
97 std::string mapfilename;
98 iss >> mapfilename;
99 std::string option;
100 iss >> option;
101 std::string mapfilenameWithPath = m_rf_mapCollection.findFile(mapfilename);
102
103 //open the individual map file
104 MapGrid2D map;
105 bool r = map.loadFromFile(mapfilenameWithPath);
106 if (r)
107 {
108 std::string map_name= map.getMapName();
109 auto p = m_maps_storage.find(map_name);
110 if (p == m_maps_storage.end())
111 {
112 if (option == "crop") {
113 map.crop(-1, -1, -1, -1);
114 }
115 m_maps_storage[map_name] = map;
116 }
117 else
118 {
119 yCError(MAP2DSTORAGE) << "A map with the same name '" << map_name << "'was found, skipping...";
120 ret = false;
121 }
122 }
123 else
124 {
125 yCError(MAP2DSTORAGE) << "Problems opening map file" << mapfilenameWithPath;
126 ret = false;
127 }
128 }
129 else
130 {
131 yCError(MAP2DSTORAGE) << "Invalid syntax, missing mapfile tag";
132 ret = false;
133 }
134 }
135 file.close();
136 return ret;
137}
138
140{
141 Property params;
142 params.fromString(config.toString());
143
144 std::string collection_file_name="maps_collection.ini";
145 std::string locations_file_name="locations.ini";
146 if (config.check("mapCollectionFile"))
147 {
148 collection_file_name= config.find("mapCollectionFile").asString();
149 }
150
151 if (config.check("mapCollectionContext"))
152 {
153 std::string collection_context_name= config.find("mapCollectionContext").asString();
154 m_rf_mapCollection.setDefaultContext(collection_context_name.c_str());
155 std::string collection_file_with_path = m_rf_mapCollection.findFile(collection_file_name);
156 std::string locations_file_with_path = m_rf_mapCollection.findFile(locations_file_name);
157
158 if (collection_file_with_path=="")
159 {
160 yCInfo(MAP2DSTORAGE) << "No locations loaded";
161 }
162 else
163 {
164 bool ret = loadLocationsAndExtras(locations_file_with_path);
165 if (ret) { yCInfo(MAP2DSTORAGE) << "Location file" << locations_file_with_path << "successfully loaded."; }
166 else { yCError(MAP2DSTORAGE) << "Problems opening file" << locations_file_with_path; }
167 }
168
169 if (collection_file_with_path=="")
170 {
171 yCError(MAP2DSTORAGE) << "Unable to find file" << collection_file_name << "within the specified context:" << collection_context_name;
172 return false;
173 }
174 if (loadMapsCollection(collection_file_with_path))
175 {
176 yCInfo(MAP2DSTORAGE) << "Map collection file:" << collection_file_with_path << "successfully loaded.";
177 if (m_maps_storage.size() > 0)
178 {
179 yCInfo(MAP2DSTORAGE) << "Available maps are:";
180 for (auto& it : m_maps_storage)
181 {
182 yCInfo(MAP2DSTORAGE) << it.first;
183 }
184 }
185 else
186 {
187 yCInfo(MAP2DSTORAGE) << "No maps available";
188 }
189 if (m_locations_storage.size() > 0)
190 {
191 yCInfo(MAP2DSTORAGE) << "Available Locations are:";
192 for (auto& it : m_locations_storage)
193 {
194 yCInfo(MAP2DSTORAGE) << it.first;
195 }
196 }
197 else
198 {
199 yCInfo(MAP2DSTORAGE) << "No locations available";
200 }
201
202 if (m_areas_storage.size() > 0)
203 {
204 yCInfo(MAP2DSTORAGE) << "Available areas are:";
205 for (auto& it : m_areas_storage)
206 {
207 yCInfo(MAP2DSTORAGE) << it.first;
208 }
209 }
210 else
211 {
212 yCInfo(MAP2DSTORAGE) << "No areas available";
213 }
214 }
215 else
216 {
217 yCError(MAP2DSTORAGE) << "Unable to load map collection file:" << collection_file_with_path;
218 return false;
219 }
220 }
221
222 if (!config.check("name"))
223 {
224 m_rpcPortName = "/map2DStorage/rpc";
225 }
226 else
227 {
228 m_rpcPortName = config.find("name").asString();
229 }
230
231 //open rpc port
232 if (!m_rpcPort.open(m_rpcPortName))
233 {
234 yCError(MAP2DSTORAGE, "Failed to open port %s", m_rpcPortName.c_str());
235 return false;
236 }
237 m_rpcPort.setReader(*this);
238
239 return true;
240}
241
243{
244 yCTrace(MAP2DSTORAGE, "Close");
245 return true;
246}
247
248bool Map2DStorage::priv_load_locations_and_areas_v1(std::ifstream& file)
249{
250 std::string buffer;
251 std::getline(file, buffer);
252 if (buffer != "Locations:")
253 {
254 yCError(MAP2DSTORAGE) << "Unable to parse Locations section!";
255 return false;
256 }
257
258 while (1)
259 {
260 std::getline(file, buffer);
261 if (buffer == "Areas:") {
262 break;
263 }
264 if (file.eof())
265 {
266 yCError(MAP2DSTORAGE) << "Unexpected End Of File";
267 return false;
268 }
269 Bottle b;
271 size_t bot_size = b.size();
272 if (bot_size != 5)
273 {
274 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
275 return false;
276 }
277 Map2DLocation location;
278 std::string name = b.get(0).asString();
279 location.map_id = b.get(1).asString();
280 location.x = b.get(2).asFloat64();
281 location.y = b.get(3).asFloat64();
282 location.theta = b.get(4).asFloat64();
283 m_locations_storage[name] = location;
284 }
285
286 if (buffer != "Areas:")
287 {
288 yCError(MAP2DSTORAGE) << "Unable to parse Areas section!";
289 return false;
290 }
291
292 while (1)
293 {
294 Map2DArea area;
295 std::getline(file, buffer);
296 if (file.eof()) {
297 break;
298 }
299
300 Bottle b;
302 size_t bot_size = b.size();
303 std::string name = b.get(0).asString();
304 area.map_id = b.get(1).asString();
305 size_t area_size = b.get(2).asInt32();
306 if (area_size <= 0 || bot_size != area_size * 2 + 3)
307 {
308 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
309 return false;
310 }
311 for (size_t ai = 3; ai < bot_size; ai += 2)
312 {
313 double xpos = b.get(ai).asFloat64();
314 double ypos = b.get(ai + 1).asFloat64();
315 area.points.push_back(yarp::math::Vec2D<double>(xpos, ypos));
316 }
317 m_areas_storage[name] = area;
318 }
319 return true;
320}
321
322bool Map2DStorage::priv_load_locations_and_areas_v2(std::ifstream& file)
323{
324 std::string buffer;
325 std::getline(file, buffer);
326 if (buffer != "Locations:")
327 {
328 yCError(MAP2DSTORAGE) << "Unable to parse Locations section!";
329 return false;
330 }
331
332 while (1)
333 {
334 std::getline(file, buffer);
335 if (buffer == "Areas:") {
336 break;
337 }
338 if (file.eof())
339 {
340 yCError(MAP2DSTORAGE) << "Unexpected End Of File";
341 return false;
342 }
343 Bottle b;
345 size_t bot_size = b.size();
346 if (bot_size != 5)
347 {
348 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
349 return false;
350 }
351 Map2DLocation location;
352 std::string name = b.get(0).asString();
353 location.map_id = b.get(1).asString();
354 location.x = b.get(2).asFloat64();
355 location.y = b.get(3).asFloat64();
356 location.theta = b.get(4).asFloat64();
357 m_locations_storage[name] = location;
358 }
359
360 if (buffer != "Areas:")
361 {
362 yCError(MAP2DSTORAGE) << "Unable to parse Areas section!";
363 return false;
364 }
365
366 while (1)
367 {
368 Map2DArea area;
369 std::getline(file, buffer);
370 if (buffer == "Paths:") {
371 break;
372 }
373 if (file.eof()) {
374 break;
375 }
376
377 Bottle b;
379 size_t bot_size = b.size();
380 std::string name = b.get(0).asString();
381 area.map_id = b.get(1).asString();
382 size_t area_size = b.get(2).asInt32();
383 if (area_size <= 0 || bot_size != area_size * 2 + 3)
384 {
385 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
386 return false;
387 }
388 for (size_t ai = 3; ai < bot_size; ai += 2)
389 {
390 double xpos = b.get(ai).asFloat64();
391 double ypos = b.get(ai + 1).asFloat64();
392 area.points.push_back(yarp::math::Vec2D<double>(xpos, ypos));
393 }
394 m_areas_storage[name] = area;
395 }
396
397 if (buffer != "Paths:")
398 {
399 yCError(MAP2DSTORAGE) << "Unable to parse Paths section!";
400 return false;
401 }
402
403 while (1)
404 {
405 Map2DPath path;
406 std::getline(file, buffer);
407 if (file.eof()) {
408 break;
409 }
410
411 Bottle b;
413 size_t bot_size = b.size();
414 YARP_UNUSED(bot_size);
415 std::string name = b.get(0).asString();
416 size_t i = 1;
417 do
418 {
419 if (b.get(i).isList())
420 {
421 Bottle* ll = b.get(i).asList();
422 if (ll && ll->size() == 4)
423 {
424 Map2DLocation loc;
425 loc.map_id = ll->get(0).asString();
426 loc.x = ll->get(1).asFloat64();
427 loc.y = ll->get(2).asFloat64();
428 loc.theta = ll->get(3).asFloat64();
429 path.push_back(loc);
430 }
431 else
432 {
433 yCError(MAP2DSTORAGE) << "Unable to parse contents of Paths section!";
434 return false;
435 }
436 }
437 else
438 {
439 break;
440 }
441 i++;
442 } while (1);
443 m_paths_storage[name] = path;
444 }
445
446 return true;
447}
448
449bool Map2DStorage::priv_load_locations_and_areas_v3(std::ifstream& file)
450{
451 std::string buffer;
452 std::getline(file, buffer);
453 if (buffer != "Locations:")
454 {
455 yCError(MAP2DSTORAGE) << "Unable to parse Locations section!";
456 return false;
457 }
458
459 while (1)
460 {
461 std::getline(file, buffer);
462 if (buffer == "Areas:") {
463 break;
464 }
465 if (file.eof())
466 {
467 yCError(MAP2DSTORAGE) << "Unexpected End Of File";
468 return false;
469 }
470 Bottle b;
472 size_t bot_size = b.size();
473 if (bot_size != 6)
474 {
475 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
476 return false;
477 }
478 Map2DLocation location;
479 std::string name = b.get(0).asString();
480 location.map_id = b.get(1).asString();
481 location.x = b.get(2).asFloat64();
482 location.y = b.get(3).asFloat64();
483 location.theta = b.get(4).asFloat64();
484 location.description = b.get(5).asString();
485 m_locations_storage[name] = location;
486 }
487
488 if (buffer != "Areas:")
489 {
490 yCError(MAP2DSTORAGE) << "Unable to parse Areas section!";
491 return false;
492 }
493
494 while (1)
495 {
496 Map2DArea area;
497 std::getline(file, buffer);
498 if (buffer == "Paths:") {
499 break;
500 }
501 if (file.eof()) {
502 break;
503 }
504
505 Bottle b;
507 size_t bot_size = b.size();
508 std::string name = b.get(0).asString();
509 area.map_id = b.get(1).asString();
510 size_t area_size = b.get(2).asInt32();
511 if (area_size <= 0 || bot_size != 3 + area_size * 2 + 1)
512 {
513 yCError(MAP2DSTORAGE) << "Unable to parse contents of Areas section!";
514 return false;
515 }
516 for (size_t ai = 3; ai < bot_size-1; ai += 2)
517 {
518 double xpos = b.get(ai).asFloat64();
519 double ypos = b.get(ai + 1).asFloat64();
520 area.points.push_back(yarp::math::Vec2D<double>(xpos, ypos));
521 }
522 area.description = b.get(bot_size-1).asString();
523 m_areas_storage[name] = area;
524 }
525
526 if (buffer != "Paths:")
527 {
528 yCError(MAP2DSTORAGE) << "Unable to parse Paths section!";
529 return false;
530 }
531
532 while (1)
533 {
534 Map2DPath path;
535 std::getline(file, buffer);
536 if (file.eof()) {
537 break;
538 }
539
540 Bottle b;
542 size_t bot_size = b.size();
543 YARP_UNUSED(bot_size);
544 std::string name = b.get(0).asString();
545 size_t i = 1;
546 do
547 {
548 if (b.get(i).isList())
549 {
550 Bottle* ll = b.get(i).asList();
551 if (ll && ll->size() == 4)
552 {
553 Map2DLocation loc;
554 loc.map_id = ll->get(0).asString();
555 loc.x = ll->get(1).asFloat64();
556 loc.y = ll->get(2).asFloat64();
557 loc.theta = ll->get(3).asFloat64();
558 path.push_back(loc);
559 }
560 else
561 {
562 yCError(MAP2DSTORAGE) << "Unable to parse contents of Paths section!";
563 return false;
564 }
565 }
566 else
567 {
568 break;
569 }
570 i++;
571 } while (1);
572 path.description = b.get(bot_size - 1).asString();
573 m_paths_storage[name] = path;
574 }
575
576 return true;
577}
578
579bool Map2DStorage::loadLocationsAndExtras(std::string locations_file)
580{
581 std::ifstream file;
582 file.open (locations_file.c_str());
583
584 if(!file.is_open())
585 {
586 yCError(MAP2DSTORAGE) << "Unable to open" << locations_file << "locations file.";
587 return false;
588 }
589
590 std::string buffer;
591
592 std::getline(file, buffer);
593 if (buffer != "Version:")
594 {
595 yCError(MAP2DSTORAGE) << "Unable to parse Version section!";
596 file.close();
597 return false;
598 }
599 std::getline(file, buffer);
600 int version = atoi(buffer.c_str());
601
602 if (version == 1)
603 {
604 if (!priv_load_locations_and_areas_v1(file))
605 {
606 yCError(MAP2DSTORAGE) << "Call to load_locations_and_areas_v1 failed";
607 file.close();
608 return false;
609 }
610 }
611 else if (version == 2)
612 {
613 if (!priv_load_locations_and_areas_v2(file))
614 {
615 yCError(MAP2DSTORAGE) << "Call to load_locations_and_areas_v2 failed";
616 file.close();
617 return false;
618 }
619 }
620 else if (version == 3)
621 {
622 if (!priv_load_locations_and_areas_v3(file))
623 {
624 yCError(MAP2DSTORAGE) << "Call to load_locations_and_areas_v3 failed";
625 file.close();
626 return false;
627 }
628 }
629 else
630 {
631 yCError(MAP2DSTORAGE) << "Only versions 1-3 supported!";
632 file.close();
633 return false;
634 }
635
636 //on success
637 file.close();
638 yCDebug(MAP2DSTORAGE) << "Locations file" << locations_file << "loaded, "
639 << m_locations_storage.size() << "locations and "
640 << m_areas_storage.size() << " areas and "
641 << m_paths_storage.size() << " paths available";
642 return true;
643}
644
645bool Map2DStorage::saveLocationsAndExtras(std::string locations_file)
646{
647 std::ofstream file;
648 file.open (locations_file.c_str());
649
650 if(!file.is_open())
651 {
652 yCError(MAP2DSTORAGE) << "Unable to open" << locations_file << "locations file.";
653 return false;
654 }
655
656 std::string s = " ";
657 std::string q = "\"";
658
659 file << "Version:\n";
660 file << "3\n";
661
662 {
663 Map2DLocation tmp_loc;
664 file << "Locations:\n";
665 std::map<std::string, Map2DLocation>::iterator it;
666 for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
667 {
668 tmp_loc = it->second;
669 file << it->first << s << tmp_loc.map_id << s << tmp_loc.x << s << tmp_loc.y << s << tmp_loc.theta << s;
670 file << q << tmp_loc.description << q << "\n";
671 }
672 }
673
674 {
675 Map2DArea tmp_area;
676 file << "Areas:\n";
677 std::map<std::string, Map2DArea>::iterator it2;
678 for (it2 = m_areas_storage.begin(); it2 != m_areas_storage.end(); ++it2)
679 {
680 tmp_area = it2->second;
681 file << it2->first << s << tmp_area.map_id << s << tmp_area.points.size() << s;
682 for (size_t i = 0; i < tmp_area.points.size(); i++)
683 {
684 file << tmp_area.points[i].x << s;
685 file << tmp_area.points[i].y << s;
686 }
687 file << q << tmp_area.description << q;
688 file << "\n";
689 }
690 }
691
692 {
693
694 Map2DPath tmp_path;
695 file << "Paths:\n";
696 std::map<std::string, Map2DPath>::iterator it3;
697 for (it3 = m_paths_storage.begin(); it3 != m_paths_storage.end(); ++it3)
698 {
699 tmp_path = it3->second;
700 file << it3->first << " "; // the name of the path
701 for (size_t i=0; i<it3->second.size(); i++)
702 {
703 Map2DLocation tmp_loc = tmp_path[i];
704 file << "( " << tmp_loc.map_id << s << tmp_loc.x << s << tmp_loc.y << s << tmp_loc.theta << ") ";
705 }
706 file << q << tmp_path.description << q;
707 file << "\n";
708 }
709 }
710
711 file.close();
712 yCDebug(MAP2DSTORAGE) << "Locations file" << locations_file << "saved.";
713 return true;
714}
715
716
718{
719 m_maps_storage.clear();
720 return true;
721}
722
724{
725 std::string map_name = map.getMapName();
726 auto it = m_maps_storage.find(map_name);
727 if (it == m_maps_storage.end())
728 {
729 //add a new map
730 m_maps_storage[map_name] = map;
731 }
732 else
733 {
734 //the map already exists
735 m_maps_storage[map_name] = map;
736 }
737 return true;
738}
739
741{
742 auto it = m_maps_storage.find(map_name);
743 if (it != m_maps_storage.end())
744 {
745 map=it->second;
746 return true;
747 }
748 return false;
749}
750
751bool Map2DStorage::get_map_names(std::vector<std::string>& map_names)
752{
753 map_names.clear();
754 for (auto& it : m_maps_storage)
755 {
756 map_names.push_back(it.first);
757 }
758 return true;
759}
760
761bool Map2DStorage::remove_map(std::string map_name)
762{
763 size_t rem = m_maps_storage.erase(map_name);
764 if (rem == 0)
765 {
766 return false;
767 }
768 else
769 {
770 return true;
771 }
772}
773
775{
776 m_locations_storage.insert(std::pair<std::string, Map2DLocation>(location_name, loc));
777 return true;
778}
779
781{
782 m_areas_storage.insert(std::pair<std::string, Map2DArea>(area_name, area));
783 return true;
784}
785
787{
788 m_paths_storage.insert(std::pair<std::string, Map2DPath>(path_name, path));
789 return true;
790}
791
793{
794 auto it = m_locations_storage.find(location_name);
795 if (it != m_locations_storage.end())
796 {
797 loc = it->second;
798 return true;
799 }
800 return false;
801}
802
803bool Map2DStorage::getArea(std::string area_name, yarp::dev::Nav2D::Map2DArea& area)
804{
805 auto it = m_areas_storage.find(area_name);
806 if (it != m_areas_storage.end())
807 {
808 area = it->second;
809 return true;
810 }
811 return false;
812}
813
814bool Map2DStorage::getPath(std::string path_name, yarp::dev::Nav2D::Map2DPath& path)
815{
816 auto it = m_paths_storage.find(path_name);
817 if (it != m_paths_storage.end())
818 {
819 path = it->second;
820 return true;
821 }
822 return false;
823}
824
825bool Map2DStorage::getLocationsList(std::vector<std::string>& locations)
826{
827 locations.clear();
828 for (auto& it : m_locations_storage)
829 {
830 locations.push_back(it.first);
831 }
832 return true;
833}
834
835bool Map2DStorage::getAreasList(std::vector<std::string>& areas)
836{
837 areas.clear();
838 for (auto& it : m_areas_storage)
839 {
840 areas.push_back(it.first);
841 }
842 return true;
843}
844
845bool Map2DStorage::getPathsList(std::vector<std::string>& paths)
846{
847 paths.clear();
848 for (auto& it : m_paths_storage)
849 {
850 paths.push_back(it.first);
851 }
852 return true;
853}
854
855bool Map2DStorage::getAllLocations (std::vector<yarp::dev::Nav2D::Map2DLocation>& locations)
856{
857 locations.clear();
858 for (auto& it : m_locations_storage)
859 {
860 locations.push_back(it.second);
861 }
862 return true;
863}
864
865bool Map2DStorage::getAllAreas (std::vector<yarp::dev::Nav2D::Map2DArea>& areas)
866{
867 for (auto& it : m_areas_storage)
868 {
869 areas.push_back(it.second);
870 }
871 return true;
872}
873
874bool Map2DStorage::getAllPaths (std::vector<yarp::dev::Nav2D::Map2DPath>& paths)
875{
876 paths.clear();
877 for (auto& it : m_paths_storage)
878 {
879 paths.push_back(it.second);
880 }
881 return true;
882}
883
884bool Map2DStorage::renameLocation(std::string original_name, std::string new_name)
885{
886 std::map<std::string, Map2DLocation>::iterator orig_it;
887 orig_it = m_locations_storage.find(original_name);
888 std::map<std::string, Map2DLocation>::iterator new_it;
889 new_it = m_locations_storage.find(new_name);
890
891 if (orig_it != m_locations_storage.end() &&
892 new_it == m_locations_storage.end())
893 {
894 auto loc = orig_it->second;
895 m_locations_storage.erase(orig_it);
896 m_locations_storage.insert(std::pair<std::string, Map2DLocation>(new_name, loc));
897 return true;
898 }
899 return false;
900}
901
902bool Map2DStorage::deleteLocation(std::string location_name)
903{
904 std::map<std::string, Map2DLocation>::iterator it;
905 it = m_locations_storage.find(location_name);
906 if (it != m_locations_storage.end())
907 {
908 m_locations_storage.erase(it);
909 return true;
910 }
911 return false;
912}
913
914bool Map2DStorage::deleteArea(std::string area_name)
915{
916 std::map<std::string, Map2DArea>::iterator it;
917 it = m_areas_storage.find(area_name);
918 if (it != m_areas_storage.end())
919 {
920 m_areas_storage.erase(it);
921 return true;
922 }
923 return false;
924}
925
926bool Map2DStorage::deletePath(std::string path_name)
927{
928 std::map<std::string, Map2DPath>::iterator it;
929 it = m_paths_storage.find(path_name);
930 if (it != m_paths_storage.end())
931 {
932 m_paths_storage.erase(it);
933 return true;
934 }
935 return false;
936}
937
938bool Map2DStorage::renameArea(std::string original_name, std::string new_name)
939{
940
941 std::map<std::string, Map2DArea>::iterator orig_it;
942 orig_it = m_areas_storage.find(original_name);
943 std::map<std::string, Map2DArea>::iterator new_it;
944 new_it = m_areas_storage.find(new_name);
945
946 if (orig_it != m_areas_storage.end() &&
947 new_it == m_areas_storage.end())
948 {
949 auto area = orig_it->second;
950 m_areas_storage.erase(orig_it);
951 m_areas_storage.insert(std::pair<std::string, Map2DArea>(new_name, area));
952 return true;
953 }
954 return false;
955}
956
957bool Map2DStorage::renamePath(std::string original_name, std::string new_name)
958{
959
960 std::map<std::string, Map2DPath>::iterator orig_it;
961 orig_it = m_paths_storage.find(original_name);
962 std::map<std::string, Map2DPath>::iterator new_it;
963 new_it = m_paths_storage.find(new_name);
964
965 if (orig_it != m_paths_storage.end() &&
966 new_it == m_paths_storage.end())
967 {
968 auto area = orig_it->second;
969 m_paths_storage.erase(orig_it);
970 m_paths_storage.insert(std::pair<std::string, Map2DPath>(new_name, area));
971 return true;
972 }
973 return false;
974}
975
976
977
979{
980 m_locations_storage.clear();
981 return true;
982}
983
985{
986 m_areas_storage.clear();
987 return true;
988}
989
991{
992 m_paths_storage.clear();
993 return true;
994}
995
997{
998 for (auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
999 {
1000 it->second.clearMapTemporaryFlags();
1001 }
1002 return true;
1003}
1004
1006{
1007 auto it = m_maps_storage.find(map_name);
1008 if (it != m_maps_storage.end())
1009 {
1010 it->second.clearMapTemporaryFlags();
1011 return true;
1012 }
1013 else
1014 {
1015 return false;
1016 }
1017}
1018
1019bool Map2DStorage::read(yarp::os::ConnectionReader& connection)
1020{
1021 yCWarning(MAP2DSTORAGE) << "not yet implemented";
1022
1023 std::lock_guard<std::mutex> lock(m_mutex);
1025 yarp::os::Bottle out;
1026 bool ok = in.read(connection);
1027 if (!ok) {
1028 return false;
1029 }
1030
1031 //parse string command
1032 if (in.get(0).isString())
1033 {
1034 //parse_string_command(in, out);
1035 }
1036 // parse vocab command
1037 else if (in.get(0).isVocab32())
1038 {
1039 //parse_vocab_command(in, out);
1040 }
1041
1042 yarp::os::ConnectionWriter* returnToSender = connection.getWriter();
1043 if (returnToSender != nullptr)
1044 {
1045 out.write(*returnToSender);
1046 }
1047 else
1048 {
1049 yCError(MAP2DSTORAGE) << "Invalid return to sender";
1050 }
1051 return true;
1052}
1053
1054bool Map2DStorage::saveMapToDisk(std::string map_name, std::string file_name)
1055{
1056 auto p = m_maps_storage.find(map_name);
1057 if (p == m_maps_storage.end())
1058 {
1059 yCError(MAP2DSTORAGE) << "saveMapToDisk failed: map " << map_name << " not found";
1060 return false;
1061 }
1062 else
1063 {
1064 bool b = p->second.saveToFile(file_name);
1065 if (b)
1066 {
1067 yCInfo(MAP2DSTORAGE) << "file" << file_name << " successfully saved";
1068 return true;
1069 }
1070 else
1071 {
1072 yCError(MAP2DSTORAGE) << "save_map failed: unable to save " << map_name << " to " << file_name;
1073 return false;
1074 }
1075 }
1076 return true;
1077}
1078
1079bool Map2DStorage::loadMapFromDisk(std::string file_name)
1080{
1081 MapGrid2D map;
1082 bool r = map.loadFromFile(file_name);
1083 if (r)
1084 {
1085 std::string map_name = map.getMapName();
1086 auto p = m_maps_storage.find(map_name);
1087 if (p == m_maps_storage.end())
1088 {
1089 m_maps_storage[map_name] = map;
1090 yCInfo (MAP2DSTORAGE) << "file" << file_name << "successfully loaded.";
1091 return true;
1092 }
1093 else
1094 {
1095 yCError(MAP2DSTORAGE) << map_name << " already exists, skipping.";
1096 return false;
1097 }
1098 }
1099 else
1100 {
1101 yCError(MAP2DSTORAGE) << "load_map failed. Unable to load " + file_name;
1102 return false;
1103 }
1104 return true;
1105}
1106
1108{
1109 bool b = true;
1110 for (auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
1111 {
1112 b &= it->second.enable_map_compression_over_network(enable);
1113 }
1114 if (b)
1115 {
1116 if (enable) {yCInfo(MAP2DSTORAGE) << "compression mode of all maps enabled";}
1117 else {yCInfo(MAP2DSTORAGE) << "compression mode of all maps disabled";}
1118 return true;
1119 }
1120
1121 yCError(MAP2DSTORAGE) << "failed to set compression mode";
1122 return false;
1123}
bool ret
bool getLocationsList(std::vector< std::string > &locations) override
Get a list of the names of all stored locations.
bool renamePath(std::string original_name, std::string new_name) override
Searches for a path and renames it.
bool deleteArea(std::string area_name) override
Delete an area.
bool saveLocationsAndExtras(std::string locations_file) override
Save a collection of locations/area/paths etc to disk.
bool getPath(std::string path_name, yarp::dev::Nav2D::Map2DPath &path) override
Retrieves a path.
bool close() override
Close the DeviceDriver.
bool clearAllLocations() override
Delete all stored locations.
bool deleteLocation(std::string location_name) override
Delete a location.
bool clearMapTemporaryFlags(std::string map_name) override
Clear all temporary flags from a specific map.
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 saveMapToDisk(std::string map_name, std::string file_name) override
Save a map to disk.
bool store_map(const yarp::dev::Nav2D::MapGrid2D &map) override
Stores a map into the map server.
bool getAreasList(std::vector< std::string > &areas) override
Get a list of the names of all stored areas.
bool renameLocation(std::string original_name, std::string new_name) override
Searches for a location and renames it.
bool deletePath(std::string path_name) override
Delete a path.
bool saveMapsCollection(std::string maps_collection_file) override
Save a collection of maps to disk.
bool get_map(std::string map_name, yarp::dev::Nav2D::MapGrid2D &map) override
Gets a map from the map server.
Map2DStorage()
Map2DStorage.
bool renameArea(std::string original_name, std::string new_name) override
Searches for an area and renames it.
bool remove_map(std::string map_name) override
Removes a map from the map server.
bool loadMapsCollection(std::string maps_collection_file) override
Load a collection of maps from disk.
bool enableMapsCompression(bool enable) override
99999999999
bool get_map_names(std::vector< std::string > &map_names) override
Gets a list containing the names of all registered maps.
bool loadMapFromDisk(std::string file_name) override
Load a map from disk.
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 clearAllAreas() override
Delete all stored areas.
bool clearAllPaths() override
Delete all stored paths.
bool storePath(std::string path_name, yarp::dev::Nav2D::Map2DPath path) override
Store a path.
bool getAllLocations(std::vector< yarp::dev::Nav2D::Map2DLocation > &locations) override
Get a list of all stored locations.
bool clearAllMaps() override
Removes all the registered maps from the server.
bool getAllPaths(std::vector< yarp::dev::Nav2D::Map2DPath > &paths) override
Get a list of all stored paths.
bool storeArea(std::string area_name, yarp::dev::Nav2D::Map2DArea area) override
Store an area.
bool getPathsList(std::vector< std::string > &paths) override
Get a list of the names of all stored paths.
bool clearAllMapsTemporaryFlags() override
Clear all temporary flags from all stored maps.
bool getAllAreas(std::vector< yarp::dev::Nav2D::Map2DArea > &areas) override
Get a list of all stored areas.
bool getArea(std::string area_name, yarp::dev::Nav2D::Map2DArea &area) override
Retrieves an area.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool loadLocationsAndExtras(std::string locations_file) override
Load a collection of locations/areas/paths etc from disk.
std::string description
user defined string
Definition: Map2DAreaData.h:38
std::string map_id
name of the map
Definition: Map2DAreaData.h:30
std::vector< yarp::math::Vec2D< double > > points
list of points which define the vertices of the area
Definition: Map2DAreaData.h:34
std::string map_id
name of the map
double theta
orientation [deg] in the map reference frame
double y
y position of the location [m], expressed in the map reference frame
std::string description
user defined string
double x
x position of the location [m], expressed in the map reference frame
std::string description
user defined string
Definition: Map2DPathData.h:34
void push_back(yarp::dev::Nav2D::Map2DLocation loc)
Inserts a new location into the path @loc the location to be inserted.
Definition: Map2DPath.cpp:130
std::string getMapName() const
Retrieves the map name.
Definition: MapGrid2D.cpp:1085
bool crop(int left, int top, int right, int bottom)
Modifies the map, cropping pixels at the boundaries.
Definition: MapGrid2D.cpp:707
bool loadFromFile(std::string map_filename)
Loads a yarp map file from disk.
Definition: MapGrid2D.cpp:556
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void setReader(PortReader &reader) override
Set an external reader for port data.
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:64
void fromString(const std::string &text)
Initializes bottle from a string.
Definition: Bottle.cpp:204
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
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:230
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.
A class for storing options and configuration information.
Definition: Property.h:33
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
bool setDefaultContext(const std::string &contextName)
Sets the context for the current ResourceFinder object.
std::string findFile(const std::string &name)
Find the full path to a file.
A base class for nested structures that can be searched.
Definition: Searchable.h:63
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isString() const
Checks if value is a string.
Definition: Value.cpp:156
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
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCTrace(component,...)
Definition: LogComponent.h:84
#define yCWarning(component,...)
Definition: LogComponent.h:192
#define yCDebug(component,...)
Definition: LogComponent.h:128
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
For streams capable of holding different kinds of content, check what they actually have.
An interface to the operating system, including Port based communication.
#define YARP_UNUSED(var)
Definition: api.h:162