6 #ifndef YARP_DEV_MAP2DSERVER_H
7 #define YARP_DEV_MAP2DSERVER_H
42 #define DEFAULT_THREAD_PERIOD 20
66 std::map<std::string, yarp::dev::Nav2D::MapGrid2D> m_maps_storage;
67 std::map<std::string, yarp::dev::Nav2D::Map2DLocation> m_locations_storage;
68 std::map<std::string, yarp::dev::Nav2D::Map2DPath> m_paths_storage;
69 std::map<std::string, yarp::dev::Nav2D::Map2DArea> m_areas_storage;
80 bool close()
override;
84 bool priv_load_locations_and_areas_v1(std::ifstream& file);
85 bool priv_load_locations_and_areas_v2(std::ifstream& file);
90 std::string m_rpcPortName;
92 bool m_enable_publish_ros_map;
93 bool m_enable_subscribe_ros_map;
95 #define ROSNODENAME "/map2DServerNode"
96 #define ROSTOPICNAME_MAP "/map"
97 #define ROSTOPICNAME_MAPMETADATA "/map_metadata"
111 bool updateVizMarkers();
contains the definition of a Map2DArea type
contains the definition of a Map2DLocation type
contains the definition of a Map2DPath type
contains the definition of a map type
contains the definition of a Vector type
map2DServer deprecated: A device capable of read/save collections of maps from disk,...
yarp::os::Bottle getOptions()
bool close() override
Close the DeviceDriver.
Map2DServer()
Map2DServer.
bool loadMaps(std::string filename)
bool saveMaps(std::string filename)
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
bool load_locations_and_areas(std::string locations_file)
bool save_locations_and_areas(std::string locations_file)
Interface implemented by all device drivers.
A simple collection of objects that can be described and transmitted in a portable way.
An interface for reading from a network connection.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Helper class for finding config files and other external resources.
A port that is specialized as an RPC server.
A base class for nested structures that can be searched.