YARP
Yet Another Robot Platform

Localization2D_nwc_yarp A device which allows a user application retrieve the current position of the robot in the world. More...

#include <localization2D_nwc_yarp/Localization2D_nwc_yarp.h>

+ Inheritance diagram for Localization2D_nwc_yarp:

Public Member Functions

bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver. More...
 
bool close () override
 Close the DeviceDriver. More...
 
bool getCurrentPosition (yarp::dev::Nav2D::Map2DLocation &loc) override
 Gets the current position of the robot w.r.t world reference frame. More...
 
bool getEstimatedOdometry (yarp::dev::OdometryData &odom) override
 Gets the estimated odometry the robot, including its velocity expressed in the world and in the local reference frame. More...
 
bool setInitialPose (const yarp::dev::Nav2D::Map2DLocation &loc) override
 Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame. More...
 
bool getLocalizationStatus (yarp::dev::Nav2D::LocalizationStatusEnum &status) override
 Gets the current status of the localization task. More...
 
bool getEstimatedPoses (std::vector< yarp::dev::Nav2D::Map2DLocation > &poses) override
 Gets a set of pose estimates computed by the localization algorithm. More...
 
bool setInitialPose (const yarp::dev::Nav2D::Map2DLocation &loc, const yarp::sig::Matrix &cov) override
 Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame. More...
 
bool getCurrentPosition (yarp::dev::Nav2D::Map2DLocation &loc, yarp::sig::Matrix &cov) override
 Gets the current position of the robot w.r.t world reference frame, plus the covariance. More...
 
bool startLocalizationService () override
 Starts the localization service. More...
 
bool stopLocalizationService () override
 Stops the localization service. More...
 
- 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
 
 ~DeviceDriver () override
 
bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver. More...
 
bool close () override
 Close the DeviceDriver. More...
 
virtual std::string id () const
 Return the id assigned to the PolyDriver. More...
 
virtual void setId (const std::string &id)
 Set the id for this device. 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 open (Searchable &config)
 Initialize the object. More...
 
virtual bool close ()
 Shut the object down. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 
- Public Member Functions inherited from yarp::dev::Nav2D::ILocalization2D
virtual ~ILocalization2D ()
 Destructor. More...
 
virtual bool startLocalizationService ()=0
 Starts the localization service. More...
 
virtual bool stopLocalizationService ()=0
 Stops the localization service. More...
 
virtual bool getLocalizationStatus (LocalizationStatusEnum &status)=0
 Gets the current status of the localization task. More...
 
virtual bool getEstimatedPoses (std::vector< yarp::dev::Nav2D::Map2DLocation > &poses)=0
 Gets a set of pose estimates computed by the localization algorithm. More...
 
virtual bool getCurrentPosition (yarp::dev::Nav2D::Map2DLocation &loc)=0
 Gets the current position of the robot w.r.t world reference frame. More...
 
virtual bool getCurrentPosition (yarp::dev::Nav2D::Map2DLocation &loc, yarp::sig::Matrix &cov)=0
 Gets the current position of the robot w.r.t world reference frame, plus the covariance. More...
 
virtual bool getEstimatedOdometry (yarp::dev::OdometryData &odom)=0
 Gets the estimated odometry the robot, including its velocity expressed in the world and in the local reference frame. More...
 
virtual bool setInitialPose (const yarp::dev::Nav2D::Map2DLocation &loc)=0
 Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame. More...
 
virtual bool setInitialPose (const yarp::dev::Nav2D::Map2DLocation &loc, const yarp::sig::Matrix &cov)=0
 Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame. More...
 

Protected Attributes

std::mutex m_mutex
 
yarp::os::Port m_rpc_port_localization_server
 
std::string m_local_name
 
std::string m_remote_name
 
ILocalization2DMsgs m_RPC
 

Detailed Description

Localization2D_nwc_yarp A device which allows a user application retrieve the current position of the robot in the world.

Localization2D_nwc_yarp

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
local - string - - Yes Full port name opened by the Localization2D_nwc_yarp device.
remote - string - - Yes Full port name of the port opened on the server side, to which the Localization2D_nwc_yarp connects to.

Definition at line 38 of file Localization2D_nwc_yarp.h.

Member Function Documentation

◆ close()

bool Localization2D_nwc_yarp::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 186 of file Localization2D_nwc_yarp.cpp.

◆ getCurrentPosition() [1/2]

bool Localization2D_nwc_yarp::getCurrentPosition ( yarp::dev::Nav2D::Map2DLocation loc)
overridevirtual

Gets the current position of the robot w.r.t world reference frame.

Parameters
locthe location of the robot
Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 121 of file Localization2D_nwc_yarp.cpp.

◆ getCurrentPosition() [2/2]

bool Localization2D_nwc_yarp::getCurrentPosition ( yarp::dev::Nav2D::Map2DLocation loc,
yarp::sig::Matrix cov 
)
overridevirtual

Gets the current position of the robot w.r.t world reference frame, plus the covariance.

Parameters
locthe location of the robot
covthe 3x3 covariance matrix
Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 134 of file Localization2D_nwc_yarp.cpp.

◆ getEstimatedOdometry()

bool Localization2D_nwc_yarp::getEstimatedOdometry ( yarp::dev::OdometryData odom)
overridevirtual

Gets the estimated odometry the robot, including its velocity expressed in the world and in the local reference frame.

Parameters
locthe estimated odometry.
Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 108 of file Localization2D_nwc_yarp.cpp.

◆ getEstimatedPoses()

bool Localization2D_nwc_yarp::getEstimatedPoses ( std::vector< yarp::dev::Nav2D::Map2DLocation > &  poses)
overridevirtual

Gets a set of pose estimates computed by the localization algorithm.

Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 148 of file Localization2D_nwc_yarp.cpp.

◆ getLocalizationStatus()

bool Localization2D_nwc_yarp::getLocalizationStatus ( yarp::dev::Nav2D::LocalizationStatusEnum status)
overridevirtual

Gets the current status of the localization task.

Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 161 of file Localization2D_nwc_yarp.cpp.

◆ open()

bool Localization2D_nwc_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 26 of file Localization2D_nwc_yarp.cpp.

◆ setInitialPose() [1/2]

bool Localization2D_nwc_yarp::setInitialPose ( const yarp::dev::Nav2D::Map2DLocation loc)
overridevirtual

Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame.

Parameters
locthe location of the robot
Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 90 of file Localization2D_nwc_yarp.cpp.

◆ setInitialPose() [2/2]

bool Localization2D_nwc_yarp::setInitialPose ( const yarp::dev::Nav2D::Map2DLocation loc,
const yarp::sig::Matrix cov 
)
overridevirtual

Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame.

Parameters
locthe location of the robot
covthe 3x3 covariance matrix
Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 96 of file Localization2D_nwc_yarp.cpp.

◆ startLocalizationService()

bool Localization2D_nwc_yarp::startLocalizationService ( )
overridevirtual

Starts the localization service.

Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 174 of file Localization2D_nwc_yarp.cpp.

◆ stopLocalizationService()

bool Localization2D_nwc_yarp::stopLocalizationService ( )
overridevirtual

Stops the localization service.

Returns
true/false

Implements yarp::dev::Nav2D::ILocalization2D.

Definition at line 180 of file Localization2D_nwc_yarp.cpp.

Member Data Documentation

◆ m_local_name

std::string Localization2D_nwc_yarp::m_local_name
protected

Definition at line 45 of file Localization2D_nwc_yarp.h.

◆ m_mutex

std::mutex Localization2D_nwc_yarp::m_mutex
protected

Definition at line 43 of file Localization2D_nwc_yarp.h.

◆ m_remote_name

std::string Localization2D_nwc_yarp::m_remote_name
protected

Definition at line 46 of file Localization2D_nwc_yarp.h.

◆ m_RPC

ILocalization2DMsgs Localization2D_nwc_yarp::m_RPC
protected

Definition at line 47 of file Localization2D_nwc_yarp.h.

◆ m_rpc_port_localization_server

yarp::os::Port Localization2D_nwc_yarp::m_rpc_port_localization_server
protected

Definition at line 44 of file Localization2D_nwc_yarp.h.


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