YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches

localization2D_nws_yarp: A localization server which can be wrap multiple algorithms and devices to provide robot localization in a 2D World. More...

#include <networkWrappers/localization2D_nws_yarp/Localization2D_nws_yarp.h>

+ Inheritance diagram for Localization2D_nws_yarp:

Public Member Functions

 Localization2D_nws_yarp ()
 
 ~Localization2D_nws_yarp ()=default
 
bool open (yarp::os::Searchable &prop) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
bool detach () override
 Detach the object (you must have first called attach).
 
bool attach (yarp::dev::PolyDriver *driver) override
 Attach to another object.
 
void run () override
 Loop function.
 
bool threadInit () override
 Initialization method.
 
void threadRelease () override
 Release method.
 
bool read (yarp::os::ConnectionReader &connection) override
 Read this object from a network connection.
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (DeviceDriver &&other) noexcept=delete
 
virtual ~DeviceDriver ()
 
virtual std::string id () const
 Return the id assigned to the PolyDriver.
 
virtual void setId (const std::string &id)
 Set the id for this device.
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver.
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others.
 
- Public Member Functions inherited from yarp::os::PeriodicThread
 PeriodicThread (double period, ShouldUseSystemClock useSystemClock=ShouldUseSystemClock::No, PeriodicThreadClock clockAccuracy=PeriodicThreadClock::Relative)
 Constructor.
 
 PeriodicThread (double period, PeriodicThreadClock clockAccuracy)
 Constructor.
 
virtual ~PeriodicThread ()
 
bool start ()
 Call this to start the thread.
 
void step ()
 Call this to "step" the thread rather than starting it.
 
void stop ()
 Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called).
 
void askToStop ()
 Stop the thread.
 
bool isRunning () const
 Returns true when the thread is started, false otherwise.
 
bool isSuspended () const
 Returns true when the thread is suspended, false otherwise.
 
bool setPeriod (double period)
 Set the (new) period of the thread.
 
double getPeriod () const
 Return the current period of the thread.
 
void suspend ()
 Suspend the thread, the thread keeps running by doLoop is never executed.
 
void resume ()
 Resume the thread if previously suspended.
 
void resetStat ()
 Reset thread statistics.
 
double getEstimatedPeriod () const
 Return estimated period since last reset.
 
void getEstimatedPeriod (double &av, double &std) const
 Return estimated period since last reset.
 
unsigned int getIterations () const
 Return the number of iterations performed since last reset.
 
double getEstimatedUsed () const
 Return the estimated duration of the run() function since last reset.
 
void getEstimatedUsed (double &av, double &std) const
 Return estimated duration of the run() function since last reset.
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that.
 
int getPriority () const
 Query the current priority of the thread, if the OS supports that.
 
int getPolicy () const
 Query the current scheduling policy of the thread, if the OS supports that.
 
- Public Member Functions inherited from yarp::dev::WrapperSingle
 ~WrapperSingle () override
 Destructor.
 
bool attachAll (const yarp::dev::PolyDriverList &drivers) final
 Attach to a list of objects.
 
bool detachAll () final
 Detach the object (you must have first called attach).
 
- Public Member Functions inherited from yarp::dev::IWrapper
virtual ~IWrapper ()
 Destructor.
 
- Public Member Functions inherited from yarp::dev::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor.
 
- Public Member Functions inherited from yarp::os::PortReader
virtual ~PortReader ()
 Destructor.
 
virtual Type getReadType () const
 
- Public Member Functions inherited from Localization2D_nws_yarp_ParamsParser
 Localization2D_nws_yarp_ParamsParser ()
 
 ~Localization2D_nws_yarp_ParamsParser () override=default
 
bool parseParams (const yarp::os::Searchable &config) override
 Parse the DeviceDriver parameters.
 
std::string getDeviceClassName () const override
 Get the name of the DeviceDriver class.
 
std::string getDeviceName () const override
 Get the name of the device (i.e.
 
std::string getDocumentationOfDeviceParams () const override
 Get the documentation of the DeviceDriver's parameters.
 
std::vector< std::string > getListOfParams () const override
 Return a list of all params used by the device.
 
- Public Member Functions inherited from yarp::dev::IDeviceDriverParams
virtual ~IDeviceDriverParams ()
 

Protected Attributes

ILocalization2DRPCd m_RPC
 
std::string m_local_name = "/localization2D_nws_yarp"
 
yarp::os::Port m_rpcPort
 
std::string m_rpcPortName
 
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocationm_2DLocationPort
 
std::string m_2DLocationPortName
 
yarp::os::BufferedPort< yarp::dev::OdometryDatam_odometryPort
 
std::string m_odometryPortName
 
yarp::dev::PolyDriver pLoc
 
yarp::dev::Nav2D::ILocalization2DiLoc = nullptr
 
double m_stats_time_last
 

Additional Inherited Members

- Public Attributes inherited from Localization2D_nws_yarp_ParamsParser
const std::string m_device_classname = {"Localization2D_nws_yarp"}
 
const std::string m_device_name = {"localization2D_nws_yarp"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
const std::string m_GENERAL_period_defaultValue = {"0.01"}
 
const std::string m_GENERAL_retrieve_position_periodically_defaultValue = {"true"}
 
const std::string m_GENERAL_name_defaultValue = {"/localization2D_nws_yarp"}
 
const std::string m_GENERAL_publish_odometry_defaultValue = {"true"}
 
const std::string m_GENERAL_publish_location_defaultValue = {"true"}
 
double m_GENERAL_period = {0.01}
 
bool m_GENERAL_retrieve_position_periodically = {true}
 
std::string m_GENERAL_name = {"/localization2D_nws_yarp"}
 
bool m_GENERAL_publish_odometry = {true}
 
bool m_GENERAL_publish_location = {true}
 
- Protected Member Functions inherited from yarp::os::PeriodicThread
virtual void beforeStart ()
 Called just before a new thread starts.
 
virtual void afterStart (bool success)
 Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start().
 

Detailed Description

localization2D_nws_yarp: A localization server which can be wrap multiple algorithms and devices to provide robot localization in a 2D World.

Localization2D_nws_yarp

Parameters required by this device are shown in class: Localization2D_nws_yarp_ParamsParser

Definition at line 36 of file Localization2D_nws_yarp.h.

Constructor & Destructor Documentation

◆ Localization2D_nws_yarp()

Localization2D_nws_yarp::Localization2D_nws_yarp ( )

Definition at line 44 of file Localization2D_nws_yarp.cpp.

◆ ~Localization2D_nws_yarp()

Localization2D_nws_yarp::~Localization2D_nws_yarp ( )
default

Member Function Documentation

◆ attach()

bool Localization2D_nws_yarp::attach ( yarp::dev::PolyDriver driver)
overridevirtual

Attach to another object.

Parameters
driverthe polydriver that you want to attach to.
Returns
true/false on success failure.

Implements yarp::dev::IWrapper.

Definition at line 49 of file Localization2D_nws_yarp.cpp.

◆ close()

bool Localization2D_nws_yarp::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 172 of file Localization2D_nws_yarp.cpp.

◆ detach()

bool Localization2D_nws_yarp::detach ( )
overridevirtual

Detach the object (you must have first called attach).

Returns
true/false on success failure.

Implements yarp::dev::IWrapper.

Definition at line 89 of file Localization2D_nws_yarp.cpp.

◆ open()

bool Localization2D_nws_yarp::open ( yarp::os::Searchable config)
overridevirtual

Open the DeviceDriver.

Parameters
configis a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device).
Returns
true/false upon success/failure

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 101 of file Localization2D_nws_yarp.cpp.

◆ read()

bool Localization2D_nws_yarp::read ( yarp::os::ConnectionReader reader)
overridevirtual

Read this object from a network connection.

Override this for your particular class.

Parameters
readeran interface to the network connection for reading
Returns
true iff the object is successfully read

Implements yarp::os::PortReader.

Definition at line 182 of file Localization2D_nws_yarp.cpp.

◆ run()

void Localization2D_nws_yarp::run ( )
overridevirtual

Loop function.

This is the thread itself. The thread calls the run() function every <period> ms. At the end of each run, the thread will sleep the amounth of time required, taking into account the time spent inside the loop function. Example: requested period is 10ms, the run() function take 3ms to be executed, the thread will sleep for 7ms.

Note: after each run is completed, the thread will call a yield() in order to facilitate other threads to run.

Implements yarp::os::PeriodicThread.

Definition at line 196 of file Localization2D_nws_yarp.cpp.

◆ threadInit()

bool Localization2D_nws_yarp::threadInit ( )
overridevirtual

Initialization method.

The thread executes this function when it starts and before "run". This is a good place to perform initialization tasks that need to be done by the thread itself (device drivers initialization, memory allocation etc). If the function returns false the thread quits and never calls "run". The return value of threadInit() is notified to the class and passed as a parameter to afterStart(). Note that afterStart() is called by the same thread that is executing the "start" method.

Reimplemented from yarp::os::PeriodicThread.

Definition at line 147 of file Localization2D_nws_yarp.cpp.

◆ threadRelease()

void Localization2D_nws_yarp::threadRelease ( )
overridevirtual

Release method.

The thread executes this function once when it exits, after the last "run". This is a good place to release resources that were initialized in threadInit() (release memory, and device driver resources).

Reimplemented from yarp::os::PeriodicThread.

Definition at line 163 of file Localization2D_nws_yarp.cpp.

Member Data Documentation

◆ iLoc

yarp::dev::Nav2D::ILocalization2D* Localization2D_nws_yarp::iLoc = nullptr
protected

Definition at line 59 of file Localization2D_nws_yarp.h.

◆ m_2DLocationPort

yarp::os::BufferedPort<yarp::dev::Nav2D::Map2DLocation> Localization2D_nws_yarp::m_2DLocationPort
protected

Definition at line 52 of file Localization2D_nws_yarp.h.

◆ m_2DLocationPortName

std::string Localization2D_nws_yarp::m_2DLocationPortName
protected

Definition at line 53 of file Localization2D_nws_yarp.h.

◆ m_local_name

std::string Localization2D_nws_yarp::m_local_name = "/localization2D_nws_yarp"
protected

Definition at line 49 of file Localization2D_nws_yarp.h.

◆ m_odometryPort

yarp::os::BufferedPort<yarp::dev::OdometryData> Localization2D_nws_yarp::m_odometryPort
protected

Definition at line 54 of file Localization2D_nws_yarp.h.

◆ m_odometryPortName

std::string Localization2D_nws_yarp::m_odometryPortName
protected

Definition at line 55 of file Localization2D_nws_yarp.h.

◆ m_RPC

ILocalization2DRPCd Localization2D_nws_yarp::m_RPC
protected

Definition at line 46 of file Localization2D_nws_yarp.h.

◆ m_rpcPort

yarp::os::Port Localization2D_nws_yarp::m_rpcPort
protected

Definition at line 50 of file Localization2D_nws_yarp.h.

◆ m_rpcPortName

std::string Localization2D_nws_yarp::m_rpcPortName
protected

Definition at line 51 of file Localization2D_nws_yarp.h.

◆ m_stats_time_last

double Localization2D_nws_yarp::m_stats_time_last
protected

Definition at line 61 of file Localization2D_nws_yarp.h.

◆ pLoc

yarp::dev::PolyDriver Localization2D_nws_yarp::pLoc
protected

Definition at line 58 of file Localization2D_nws_yarp.h.


The documentation for this class was generated from the following files: