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