YARP
Yet Another Robot Platform

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

#include <localization2DServer/Localization2D_nws_yarp.h>

+ Inheritance diagram for Localization2D_nws_yarp:

Public Member Functions

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

Protected Attributes

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
 
bool m_enable_publish_odometry =true
 
bool m_enable_publish_location =true
 
yarp::dev::PolyDriver pLoc
 
yarp::dev::Nav2D::ILocalization2DiLoc = nullptr
 
double m_stats_time_last
 
double m_period
 
yarp::os::Stamp m_loc_stamp
 
yarp::os::Stamp m_odom_stamp
 
bool m_getdata_using_periodic_thread = true
 
yarp::dev::OdometryData m_current_odometry
 
yarp::dev::Nav2D::Map2DLocation m_current_position
 
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status = yarp::dev::Nav2D::LocalizationStatusEnum::localization_status_not_yet_localized
 

Additional Inherited Members

- Protected Member Functions inherited from yarp::os::PeriodicThread
virtual bool threadInit ()
 Initialization method. More...
 
virtual void threadRelease ()
 Release method. More...
 
virtual void beforeStart ()
 Called just before a new thread starts. More...
 
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(). More...
 

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:

Parameter name SubParameter Type Units Default Value Required Description Notes
GENERAL period double s 0.01 No The period of the working thread
GENERAL retrieve_position_periodically bool - true No If true, the subdevice is asked periodically to retrieve the current location. Otherwise the current location is obtained asynchronously when a getCurrentPosition() command is issued. -
GENERAL name string - /localization2D_nws_yarp No The name of the server, used as a prefix for the opened ports By default ports opened are /xxx/rpc and /xxx/streaming:o
GENERAL publish_odometry bool - true No Periodically publish odometry data over the network -
GENERAL publish_location bool - true No PEriodically publish location data over the network -
subdevice - string - - Yes The name of the of Localization device to be used -

Definition at line 44 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.

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 50 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 213 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 83 of file Localization2D_nws_yarp.cpp.

◆ initialize_YARP()

bool Localization2D_nws_yarp::initialize_YARP ( yarp::os::Searchable config)

Definition at line 189 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 93 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 234 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 441 of file Localization2D_nws_yarp.cpp.

Member Data Documentation

◆ iLoc

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

Definition at line 65 of file Localization2D_nws_yarp.h.

◆ m_2DLocationPort

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

Definition at line 56 of file Localization2D_nws_yarp.h.

◆ m_2DLocationPortName

std::string Localization2D_nws_yarp::m_2DLocationPortName
protected

Definition at line 57 of file Localization2D_nws_yarp.h.

◆ m_current_odometry

yarp::dev::OdometryData Localization2D_nws_yarp::m_current_odometry
protected

Definition at line 73 of file Localization2D_nws_yarp.h.

◆ m_current_position

yarp::dev::Nav2D::Map2DLocation Localization2D_nws_yarp::m_current_position
protected

Definition at line 74 of file Localization2D_nws_yarp.h.

◆ m_current_status

yarp::dev::Nav2D::LocalizationStatusEnum Localization2D_nws_yarp::m_current_status = yarp::dev::Nav2D::LocalizationStatusEnum::localization_status_not_yet_localized
protected

Definition at line 75 of file Localization2D_nws_yarp.h.

◆ m_enable_publish_location

bool Localization2D_nws_yarp::m_enable_publish_location =true
protected

Definition at line 61 of file Localization2D_nws_yarp.h.

◆ m_enable_publish_odometry

bool Localization2D_nws_yarp::m_enable_publish_odometry =true
protected

Definition at line 60 of file Localization2D_nws_yarp.h.

◆ m_getdata_using_periodic_thread

bool Localization2D_nws_yarp::m_getdata_using_periodic_thread = true
protected

Definition at line 71 of file Localization2D_nws_yarp.h.

◆ m_loc_stamp

yarp::os::Stamp Localization2D_nws_yarp::m_loc_stamp
protected

Definition at line 69 of file Localization2D_nws_yarp.h.

◆ m_local_name

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

Definition at line 53 of file Localization2D_nws_yarp.h.

◆ m_odom_stamp

yarp::os::Stamp Localization2D_nws_yarp::m_odom_stamp
protected

Definition at line 70 of file Localization2D_nws_yarp.h.

◆ m_odometryPort

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

Definition at line 58 of file Localization2D_nws_yarp.h.

◆ m_odometryPortName

std::string Localization2D_nws_yarp::m_odometryPortName
protected

Definition at line 59 of file Localization2D_nws_yarp.h.

◆ m_period

double Localization2D_nws_yarp::m_period
protected

Definition at line 68 of file Localization2D_nws_yarp.h.

◆ m_rpcPort

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

Definition at line 54 of file Localization2D_nws_yarp.h.

◆ m_rpcPortName

std::string Localization2D_nws_yarp::m_rpcPortName
protected

Definition at line 55 of file Localization2D_nws_yarp.h.

◆ m_stats_time_last

double Localization2D_nws_yarp::m_stats_time_last
protected

Definition at line 67 of file Localization2D_nws_yarp.h.

◆ pLoc

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

Definition at line 64 of file Localization2D_nws_yarp.h.


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