YARP
Yet Another Robot Platform
Map2D_nws_ros.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_MAP2D_NWS_ROS_H
7 #define YARP_DEV_MAP2D_NWS_ROS_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/IMap2D.h>
26 #include <yarp/dev/MapGrid2D.h>
27 #include <yarp/dev/Map2DLocation.h>
28 #include <yarp/dev/Map2DArea.h>
29 #include <yarp/dev/Map2DPath.h>
30 #include <yarp/dev/WrapperSingle.h>
31 #include <yarp/os/ResourceFinder.h>
32 
33 #include <yarp/dev/PolyDriver.h>
34 #include <yarp/dev/DeviceDriver.h>
35 #include <yarp/dev/api.h>
36 #include <yarp/os/Publisher.h>
37 #include <yarp/os/Subscriber.h>
38 #include <yarp/os/Node.h>
42 
63  public yarp::os::PortReader,
65 {
66 public:
67  Map2D_nws_ros();
69  bool open(yarp::os::Searchable &params) override;
70  bool close() override;
71  bool detach() override;
72  bool attach(yarp::dev::PolyDriver* driver) override;
73 
74 private:
75  //drivers and interfaces
76  yarp::dev::Nav2D::IMap2D* m_iMap2D = nullptr;
78 
79  std::mutex m_mutex;
80  std::string m_rpcPortName;
81  yarp::os::Node* m_node = nullptr;
82  bool m_enable_publish_map;
83  bool m_enable_subscribe_map;
84 
85  #define ROSNODENAME "/map2DServerNode"
86  #define ROSTOPICNAME_MAP "/map"
87  #define ROSTOPICNAME_MAPMETADATA "/map_metadata"
88 
89  yarp::os::RpcServer m_rpcPort;
95 
96  bool read(yarp::os::ConnectionReader& connection) override;
97 
98  bool updateVizMarkers(std::string map_name = "ros_map");
99  bool subscribeMapFromRos(std::string map_name = "ros_map");
100  bool publishMapToRos(std::string map_name = "ros_map");
101 };
102 
103 #endif // YARP_DEV_MAP2D_NWS_ROS_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
map2D_nws_ros: A device capable of read/save collections of maps from disk, and make them accessible ...
Definition: Map2D_nws_ros.h:65
bool close() override
Close the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool detach() override
Detach the object (you must have first called attach).
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Map2D_nws_ros()
Map2D_nws_ros.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
IMap2D Interface.
Definition: IMap2D.h:36
A container for a device driver.
Definition: PolyDriver.h:24
Helper interface for an object that can wrap/or "attach" to a single other device.
Definition: WrapperSingle.h:32
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
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