YARP
Yet Another Robot Platform
Map2D_nws_yarp.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_YARP
7 #define YARP_DEV_MAP2D_NWS_YARP
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 
53  public yarp::os::PortReader,
55 {
56 public:
59  bool open(yarp::os::Searchable& params) override;
60  bool close() override;
61  bool detach() override;
62  bool attach(yarp::dev::PolyDriver* driver) override;
63 
64 private:
65  //drivers and interfaces
66  yarp::dev::Nav2D::IMap2D* m_iMap2D = nullptr;
68 
69 private:
70  std::mutex m_mutex;
71  std::string m_rpcPortName;
72  yarp::os::RpcServer m_rpcPort;
73  bool m_send_maps_compressed=false;
74 
75  bool read(yarp::os::ConnectionReader& connection) override;
76 
77  void parse_string_command(yarp::os::Bottle& in, yarp::os::Bottle& out);
78  void parse_vocab_command(yarp::os::Bottle& in, yarp::os::Bottle& out);
79 };
80 
81 #endif // YARP_DEV_MAP2D_NWS_YARP
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_yarp: A device capable of read/save collections of maps from disk, and make them accessible...
Map2D_nws_yarp()
Map2D_nws_yarp.
bool detach() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool close() override
Close the DeviceDriver.
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
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.
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