YARP
Yet Another Robot Platform
Map2DServer.h
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 #ifndef YARP_DEV_MAP2DSERVER_H
7 #define YARP_DEV_MAP2DSERVER_H
8 
9 #include <vector>
10 #include <iostream>
11 #include <string>
12 #include <sstream>
13 #include <mutex>
14 
15 #include <yarp/os/Network.h>
16 #include <yarp/os/Port.h>
17 #include <yarp/os/Bottle.h>
18 #include <yarp/os/Time.h>
19 #include <yarp/os/Property.h>
20 
21 #include <yarp/os/PeriodicThread.h>
22 #include <yarp/os/BufferedPort.h>
23 #include <yarp/os/RpcServer.h>
24 #include <yarp/sig/Vector.h>
25 #include <yarp/dev/MapGrid2D.h>
26 #include <yarp/dev/Map2DLocation.h>
27 #include <yarp/dev/Map2DArea.h>
28 #include <yarp/dev/Map2DPath.h>
29 #include <yarp/os/ResourceFinder.h>
30 
31 #include <yarp/dev/PolyDriver.h>
32 #include <yarp/dev/DeviceDriver.h>
33 #include <yarp/dev/api.h>
34 #include <yarp/os/Publisher.h>
35 #include <yarp/os/Subscriber.h>
36 #include <yarp/os/Node.h>
40 
41 
42 #define DEFAULT_THREAD_PERIOD 20 //ms
43 
61 class Map2DServer :
64 {
65 private:
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;
70 
71 public:
72  Map2DServer();
74 
75  bool saveMaps(std::string filename);
76  bool loadMaps(std::string filename);
77  bool load_locations_and_areas(std::string locations_file);
78  bool save_locations_and_areas(std::string locations_file);
79  bool open(yarp::os::Searchable &params) override;
80  bool close() override;
82 
83 private:
84  bool priv_load_locations_and_areas_v1(std::ifstream& file);
85  bool priv_load_locations_and_areas_v2(std::ifstream& file);
86 
87 private:
88  yarp::os::ResourceFinder m_rf_mapCollection;
89  std::mutex m_mutex;
90  std::string m_rpcPortName;
91  yarp::os::Node* m_rosNode;
92  bool m_enable_publish_ros_map;
93  bool m_enable_subscribe_ros_map;
94 
95  #define ROSNODENAME "/map2DServerNode"
96  #define ROSTOPICNAME_MAP "/map"
97  #define ROSTOPICNAME_MAPMETADATA "/map_metadata"
98 
99  yarp::os::RpcServer m_rpcPort;
105 
106  bool read(yarp::os::ConnectionReader& connection) override;
107  inline void list_response(yarp::os::Bottle& out);
108 
109  void parse_string_command(yarp::os::Bottle& in, yarp::os::Bottle& out);
110  void parse_vocab_command(yarp::os::Bottle& in, yarp::os::Bottle& out);
111  bool updateVizMarkers();
112 };
113 
114 #endif // YARP_DEV_MAP2DSERVER_H
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,...
Definition: Map2DServer.h:64
yarp::os::Bottle getOptions()
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)
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
An interface for reading from a network connection.
The Node class.
Definition: Node.h:24
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:25
Helper class for finding config files and other external resources.
A port that is specialized as an RPC server.
Definition: RpcServer.h:24
A base class for nested structures that can be searched.
Definition: Searchable.h:66