42 if (m_maps_storage.size() == 0)
44 yCError(MAP2DSTORAGE) <<
"Map storage is empty";
50 file.open(mapsfile.c_str());
53 yCError(MAP2DSTORAGE) <<
"Sorry unable to open" << mapsfile;
59 for (
auto& it : m_maps_storage)
62 std::string map_filename = it.first +
".map";
68 ret &= it.second.saveToFile(map_filename);
79 file.open(mapsfile.c_str());
82 yCError(MAP2DSTORAGE) <<
"loadMaps() Unable to open:" << mapsfile;
89 std::getline(file,
buffer);
90 std::istringstream iss(
buffer);
95 if (dummy ==
"mapfile:")
97 std::string mapfilename;
101 std::string mapfilenameWithPath = m_rf_mapCollection.
findFile(mapfilename);
109 auto p = m_maps_storage.find(map_name);
110 if (p == m_maps_storage.end())
112 if (option ==
"crop") {
113 map.
crop(-1, -1, -1, -1);
115 m_maps_storage[map_name] = map;
119 yCError(MAP2DSTORAGE) <<
"A map with the same name '" << map_name <<
"'was found, skipping...";
125 yCError(MAP2DSTORAGE) <<
"Problems opening map file" << mapfilenameWithPath;
131 yCError(MAP2DSTORAGE) <<
"Invalid syntax, missing mapfile tag";
144 std::string collection_file_name=
"maps_collection.ini";
145 std::string locations_file_name=
"locations.ini";
146 if (config.
check(
"mapCollectionFile"))
148 collection_file_name= config.
find(
"mapCollectionFile").
asString();
151 if (config.
check(
"mapCollectionContext"))
153 std::string collection_context_name= config.
find(
"mapCollectionContext").
asString();
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);
158 if (collection_file_with_path==
"")
160 yCInfo(MAP2DSTORAGE) <<
"No locations loaded";
165 if (
ret) {
yCInfo(MAP2DSTORAGE) <<
"Location file" << locations_file_with_path <<
"successfully loaded."; }
166 else {
yCError(MAP2DSTORAGE) <<
"Problems opening file" << locations_file_with_path; }
169 if (collection_file_with_path==
"")
171 yCError(MAP2DSTORAGE) <<
"Unable to find file" << collection_file_name <<
"within the specified context:" << collection_context_name;
176 yCInfo(MAP2DSTORAGE) <<
"Map collection file:" << collection_file_with_path <<
"successfully loaded.";
177 if (m_maps_storage.size() > 0)
179 yCInfo(MAP2DSTORAGE) <<
"Available maps are:";
180 for (
auto& it : m_maps_storage)
182 yCInfo(MAP2DSTORAGE) << it.first;
187 yCInfo(MAP2DSTORAGE) <<
"No maps available";
189 if (m_locations_storage.size() > 0)
191 yCInfo(MAP2DSTORAGE) <<
"Available Locations are:";
192 for (
auto& it : m_locations_storage)
194 yCInfo(MAP2DSTORAGE) << it.first;
199 yCInfo(MAP2DSTORAGE) <<
"No locations available";
202 if (m_areas_storage.size() > 0)
204 yCInfo(MAP2DSTORAGE) <<
"Available areas are:";
205 for (
auto& it : m_areas_storage)
207 yCInfo(MAP2DSTORAGE) << it.first;
212 yCInfo(MAP2DSTORAGE) <<
"No areas available";
217 yCError(MAP2DSTORAGE) <<
"Unable to load map collection file:" << collection_file_with_path;
222 if (!config.
check(
"name"))
224 m_rpcPortName =
"/map2DStorage/rpc";
232 if (!m_rpcPort.
open(m_rpcPortName))
234 yCError(MAP2DSTORAGE,
"Failed to open port %s", m_rpcPortName.c_str());
244 yCTrace(MAP2DSTORAGE,
"Close");
248bool Map2DStorage::priv_load_locations_and_areas_v1(std::ifstream& file)
251 std::getline(file,
buffer);
252 if (
buffer !=
"Locations:")
254 yCError(MAP2DSTORAGE) <<
"Unable to parse Locations section!";
260 std::getline(file,
buffer);
266 yCError(MAP2DSTORAGE) <<
"Unexpected End Of File";
271 size_t bot_size = b.
size();
274 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
283 m_locations_storage[name] = location;
288 yCError(MAP2DSTORAGE) <<
"Unable to parse Areas section!";
295 std::getline(file,
buffer);
302 size_t bot_size = b.
size();
306 if (area_size <= 0 || bot_size != area_size * 2 + 3)
308 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
311 for (
size_t ai = 3; ai < bot_size; ai += 2)
317 m_areas_storage[name] = area;
322bool Map2DStorage::priv_load_locations_and_areas_v2(std::ifstream& file)
325 std::getline(file,
buffer);
326 if (
buffer !=
"Locations:")
328 yCError(MAP2DSTORAGE) <<
"Unable to parse Locations section!";
334 std::getline(file,
buffer);
340 yCError(MAP2DSTORAGE) <<
"Unexpected End Of File";
345 size_t bot_size = b.
size();
348 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
357 m_locations_storage[name] = location;
362 yCError(MAP2DSTORAGE) <<
"Unable to parse Areas section!";
369 std::getline(file,
buffer);
379 size_t bot_size = b.
size();
383 if (area_size <= 0 || bot_size != area_size * 2 + 3)
385 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
388 for (
size_t ai = 3; ai < bot_size; ai += 2)
394 m_areas_storage[name] = area;
399 yCError(MAP2DSTORAGE) <<
"Unable to parse Paths section!";
406 std::getline(file,
buffer);
413 size_t bot_size = b.
size();
422 if (ll && ll->
size() == 4)
433 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Paths section!";
443 m_paths_storage[name] = path;
449bool Map2DStorage::priv_load_locations_and_areas_v3(std::ifstream& file)
452 std::getline(file,
buffer);
453 if (
buffer !=
"Locations:")
455 yCError(MAP2DSTORAGE) <<
"Unable to parse Locations section!";
461 std::getline(file,
buffer);
467 yCError(MAP2DSTORAGE) <<
"Unexpected End Of File";
472 size_t bot_size = b.
size();
475 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
485 m_locations_storage[name] = location;
490 yCError(MAP2DSTORAGE) <<
"Unable to parse Areas section!";
497 std::getline(file,
buffer);
507 size_t bot_size = b.
size();
511 if (area_size <= 0 || bot_size != 3 + area_size * 2 + 1)
513 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Areas section!";
516 for (
size_t ai = 3; ai < bot_size-1; ai += 2)
523 m_areas_storage[name] = area;
528 yCError(MAP2DSTORAGE) <<
"Unable to parse Paths section!";
535 std::getline(file,
buffer);
542 size_t bot_size = b.
size();
551 if (ll && ll->
size() == 4)
562 yCError(MAP2DSTORAGE) <<
"Unable to parse contents of Paths section!";
573 m_paths_storage[name] = path;
582 file.open (locations_file.c_str());
586 yCError(MAP2DSTORAGE) <<
"Unable to open" << locations_file <<
"locations file.";
592 std::getline(file,
buffer);
595 yCError(MAP2DSTORAGE) <<
"Unable to parse Version section!";
599 std::getline(file,
buffer);
600 int version = atoi(
buffer.c_str());
604 if (!priv_load_locations_and_areas_v1(file))
606 yCError(MAP2DSTORAGE) <<
"Call to load_locations_and_areas_v1 failed";
611 else if (version == 2)
613 if (!priv_load_locations_and_areas_v2(file))
615 yCError(MAP2DSTORAGE) <<
"Call to load_locations_and_areas_v2 failed";
620 else if (version == 3)
622 if (!priv_load_locations_and_areas_v3(file))
624 yCError(MAP2DSTORAGE) <<
"Call to load_locations_and_areas_v3 failed";
631 yCError(MAP2DSTORAGE) <<
"Only versions 1-3 supported!";
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";
648 file.open (locations_file.c_str());
652 yCError(MAP2DSTORAGE) <<
"Unable to open" << locations_file <<
"locations file.";
657 std::string q =
"\"";
659 file <<
"Version:\n";
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)
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;
677 std::map<std::string, Map2DArea>::iterator it2;
678 for (it2 = m_areas_storage.begin(); it2 != m_areas_storage.end(); ++it2)
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++)
684 file << tmp_area.
points[i].x << s;
685 file << tmp_area.
points[i].y << s;
696 std::map<std::string, Map2DPath>::iterator it3;
697 for (it3 = m_paths_storage.begin(); it3 != m_paths_storage.end(); ++it3)
699 tmp_path = it3->second;
700 file << it3->first <<
" ";
701 for (
size_t i=0; i<it3->second.size(); i++)
704 file <<
"( " << tmp_loc.
map_id << s << tmp_loc.
x << s << tmp_loc.
y << s << tmp_loc.
theta <<
") ";
712 yCDebug(MAP2DSTORAGE) <<
"Locations file" << locations_file <<
"saved.";
719 m_maps_storage.clear();
726 auto it = m_maps_storage.find(map_name);
727 if (it == m_maps_storage.end())
730 m_maps_storage[map_name] = map;
735 m_maps_storage[map_name] = map;
742 auto it = m_maps_storage.find(map_name);
743 if (it != m_maps_storage.end())
754 for (
auto& it : m_maps_storage)
756 map_names.push_back(it.first);
763 size_t rem = m_maps_storage.erase(map_name);
776 m_locations_storage.insert(std::pair<std::string, Map2DLocation>(location_name, loc));
782 m_areas_storage.insert(std::pair<std::string, Map2DArea>(area_name, area));
788 m_paths_storage.insert(std::pair<std::string, Map2DPath>(path_name, path));
794 auto it = m_locations_storage.find(location_name);
795 if (it != m_locations_storage.end())
805 auto it = m_areas_storage.find(area_name);
806 if (it != m_areas_storage.end())
816 auto it = m_paths_storage.find(path_name);
817 if (it != m_paths_storage.end())
828 for (
auto& it : m_locations_storage)
830 locations.push_back(it.first);
838 for (
auto& it : m_areas_storage)
840 areas.push_back(it.first);
848 for (
auto& it : m_paths_storage)
850 paths.push_back(it.first);
858 for (
auto& it : m_locations_storage)
860 locations.push_back(it.second);
867 for (
auto& it : m_areas_storage)
869 areas.push_back(it.second);
877 for (
auto& it : m_paths_storage)
879 paths.push_back(it.second);
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);
891 if (orig_it != m_locations_storage.end() &&
892 new_it == m_locations_storage.end())
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));
904 std::map<std::string, Map2DLocation>::iterator it;
905 it = m_locations_storage.find(location_name);
906 if (it != m_locations_storage.end())
908 m_locations_storage.erase(it);
916 std::map<std::string, Map2DArea>::iterator it;
917 it = m_areas_storage.find(area_name);
918 if (it != m_areas_storage.end())
920 m_areas_storage.erase(it);
928 std::map<std::string, Map2DPath>::iterator it;
929 it = m_paths_storage.find(path_name);
930 if (it != m_paths_storage.end())
932 m_paths_storage.erase(it);
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);
946 if (orig_it != m_areas_storage.end() &&
947 new_it == m_areas_storage.end())
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));
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);
965 if (orig_it != m_paths_storage.end() &&
966 new_it == m_paths_storage.end())
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));
980 m_locations_storage.clear();
986 m_areas_storage.clear();
992 m_paths_storage.clear();
998 for (
auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
1000 it->second.clearMapTemporaryFlags();
1007 auto it = m_maps_storage.find(map_name);
1008 if (it != m_maps_storage.end())
1010 it->second.clearMapTemporaryFlags();
1021 yCWarning(MAP2DSTORAGE) <<
"not yet implemented";
1023 std::lock_guard<std::mutex> lock(m_mutex);
1026 bool ok = in.
read(connection);
1043 if (returnToSender !=
nullptr)
1045 out.
write(*returnToSender);
1049 yCError(MAP2DSTORAGE) <<
"Invalid return to sender";
1056 auto p = m_maps_storage.find(map_name);
1057 if (p == m_maps_storage.end())
1059 yCError(MAP2DSTORAGE) <<
"saveMapToDisk failed: map " << map_name <<
" not found";
1064 bool b = p->second.saveToFile(file_name);
1067 yCInfo(MAP2DSTORAGE) <<
"file" << file_name <<
" successfully saved";
1072 yCError(MAP2DSTORAGE) <<
"save_map failed: unable to save " << map_name <<
" to " << file_name;
1086 auto p = m_maps_storage.find(map_name);
1087 if (p == m_maps_storage.end())
1089 m_maps_storage[map_name] = map;
1090 yCInfo (MAP2DSTORAGE) <<
"file" << file_name <<
"successfully loaded.";
1095 yCError(MAP2DSTORAGE) << map_name <<
" already exists, skipping.";
1101 yCError(MAP2DSTORAGE) <<
"load_map failed. Unable to load " + file_name;
1110 for (
auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
1112 b &= it->second.enable_map_compression_over_network(enable);
1116 if (enable) {
yCInfo(MAP2DSTORAGE) <<
"compression mode of all maps enabled";}
1117 else {
yCInfo(MAP2DSTORAGE) <<
"compression mode of all maps disabled";}
1121 yCError(MAP2DSTORAGE) <<
"failed to set compression mode";
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 ¶ms) 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
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
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
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.
A simple collection of objects that can be described and transmitted in a portable way.
void fromString(const std::string &text)
Initializes bottle from a string.
size_type size() const
Gets the number of elements in the bottle.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
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.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
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.
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.
virtual bool isString() const
Checks if value is a string.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual bool isList() const
Checks if value is a list.
virtual Bottle * asList() const
Get list value.
virtual bool isVocab32() const
Checks if value is a vocabulary identifier.
virtual std::string asString() const
Get string value.
#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.