6#ifndef YARP_DEV_LOCALIZATION2D_NWS_YARP_H
7#define YARP_DEV_LOCALIZATION2D_NWS_YARP_H
66 void publish_2DLocation_on_yarp_port();
67 void publish_odometry_on_yarp_port();
74 bool close()
override;
define control board standard interfaces
This class is the parameters parser for class Localization2D_nws_yarp.
localization2D_nws_yarp: A localization server which can be wrap multiple algorithms and devices to p...
void run() override
Loop function.
yarp::os::BufferedPort< yarp::dev::OdometryData > m_odometryPort
std::string m_rpcPortName
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::dev::PolyDriver pLoc
std::string m_2DLocationPortName
yarp::dev::Nav2D::ILocalization2D * iLoc
std::string m_odometryPortName
bool m_getdata_using_periodic_thread
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 threadInit() override
Initialization method.
Localization2D_nws_yarp()
void threadRelease() override
Release method.
bool detach() override
Detach the object (you must have first called attach).
ILocalization2DRPCd * m_RPC
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation > m_2DLocationPort
~Localization2D_nws_yarp()=default
Interface implemented by all device drivers.
ILocalization2D interface.
A container for a device driver.
Helper interface for an object that can wrap/or "attach" to a single other device.
A mini-server for performing network communication in the background.
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...
A mini-server for network communication.
A base class for nested structures that can be searched.