YARP
Yet Another Robot Platform
Localization2D_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_LOCALIZATION2D_NWS_YARP_H
7 #define YARP_DEV_LOCALIZATION2D_NWS_YARP_H
8 
9 
10 #include <yarp/os/Network.h>
11 #include <yarp/os/RFModule.h>
12 #include <yarp/os/Time.h>
13 #include <yarp/os/Port.h>
14 #include <yarp/os/Stamp.h>
15 #include <yarp/os/Node.h>
16 #include <yarp/os/Publisher.h>
17 #include <yarp/os/BufferedPort.h>
18 #include <yarp/os/PeriodicThread.h>
19 #include <yarp/dev/PolyDriver.h>
20 #include <yarp/dev/WrapperSingle.h>
23 #include <yarp/dev/OdometryData.h>
24 #include <math.h>
25 
49 {
50 protected:
51 
52  //yarp
53  std::string m_local_name = "/localization2D_nws_yarp";
55  std::string m_rpcPortName;
57  std::string m_2DLocationPortName;
59  std::string m_odometryPortName;
62 
63  //drivers and interfaces
66 
68  double m_period;
72 
76 
77 private:
78  void publish_2DLocation_on_yarp_port();
79  void publish_odometry_on_yarp_port();
80 
81 public:
83 
84  bool open(yarp::os::Searchable& prop) override;
85  bool close() override;
86  bool detach() override;
87  bool attach(yarp::dev::PolyDriver* driver) override;
88  void run() override;
89 
91  bool read(yarp::os::ConnectionReader& connection) override;
92 };
93 
94 #endif // YARP_DEV_LOCALIZATION2D_NWS_YARP_H
define control board standard interfaces
localization2D_nws_yarp: A localization server which can be wrap multiple algorithms and devices to p...
void run() override
Loop function.
yarp::dev::OdometryData m_current_odometry
yarp::os::BufferedPort< yarp::dev::OdometryData > m_odometryPort
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::dev::PolyDriver pLoc
yarp::dev::Nav2D::ILocalization2D * iLoc
bool initialize_YARP(yarp::os::Searchable &config)
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool close() override
Close the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
yarp::dev::Nav2D::Map2DLocation m_current_position
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation > m_2DLocationPort
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
ILocalization2D interface.
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.
An abstraction for a periodic thread.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:25
A mini-server for network communication.
Definition: Port.h:47
A base class for nested structures that can be searched.
Definition: Searchable.h:66
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
@ localization_status_not_yet_localized