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

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

#include <networkWrappers/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.
 
bool close () override
 Close the DeviceDriver.
 
yarp::dev::ReturnValue getCurrentPosition (yarp::dev::Nav2D::Map2DLocation &loc) override
 Gets the current position of the robot w.r.t world reference frame.
 
yarp::dev::ReturnValue 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.
 
yarp::dev::ReturnValue 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.
 
yarp::dev::ReturnValue getLocalizationStatus (yarp::dev::Nav2D::LocalizationStatusEnum &status) override
 Gets the current status of the localization task.
 
yarp::dev::ReturnValue getEstimatedPoses (std::vector< yarp::dev::Nav2D::Map2DLocation > &poses) override
 Gets a set of pose estimates computed by the localization algorithm.
 
yarp::dev::ReturnValue 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.
 
yarp::dev::ReturnValue 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.
 
yarp::dev::ReturnValue startLocalizationService () override
 Starts the localization service.
 
yarp::dev::ReturnValue stopLocalizationService () override
 Stops the localization service.
 
- 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::dev::Nav2D::ILocalization2D
virtual ~ILocalization2D ()
 Destructor.
 
- Public Member Functions inherited from Localization2D_nwc_yarp_ParamsParser
 Localization2D_nwc_yarp_ParamsParser ()
 
 ~Localization2D_nwc_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.
 
bool getParamValue (const std::string &paramName, std::string &paramValue) const override
 Return the value (represented as a string) of the requested parameter.
 
std::string getConfiguration () const override
 Return the configuration of the device.
 
- Public Member Functions inherited from yarp::dev::IDeviceDriverParams
virtual ~IDeviceDriverParams ()
 

Protected Attributes

std::mutex m_mutex
 
yarp::os::Port m_rpc_port_localization_server
 
ILocalization2DMsgs m_RPC
 

Additional Inherited Members

- Public Attributes inherited from Localization2D_nwc_yarp_ParamsParser
const std::string m_device_classname = {"Localization2D_nwc_yarp"}
 
const std::string m_device_name = {"localization2D_nwc_yarp"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
std::string m_provided_configuration
 
const std::string m_local_defaultValue = {""}
 
const std::string m_remote_defaultValue = {""}
 
std::string m_local = {}
 
std::string m_remote = {}
 

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 shown in class: Localization2D_nwc_yarp_ParamsParser

Definition at line 36 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 170 of file Localization2D_nwc_yarp.cpp.

◆ getCurrentPosition() [1/2]

ReturnValue 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
a ReturnValue, convertible to true/false

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

Definition at line 105 of file Localization2D_nwc_yarp.cpp.

◆ getCurrentPosition() [2/2]

ReturnValue 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
a ReturnValue, convertible to true/false

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

Definition at line 118 of file Localization2D_nwc_yarp.cpp.

◆ getEstimatedOdometry()

ReturnValue 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
a ReturnValue, convertible to true/false

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

Definition at line 92 of file Localization2D_nwc_yarp.cpp.

◆ getEstimatedPoses()

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

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

Returns
a ReturnValue, convertible to true/false

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

Definition at line 132 of file Localization2D_nwc_yarp.cpp.

◆ getLocalizationStatus()

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

Gets the current status of the localization task.

Returns
a ReturnValue, convertible to true/false

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

Definition at line 145 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]

ReturnValue 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
a ReturnValue, convertible to true/false

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

Definition at line 74 of file Localization2D_nwc_yarp.cpp.

◆ setInitialPose() [2/2]

ReturnValue 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
a ReturnValue, convertible to true/false

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

Definition at line 80 of file Localization2D_nwc_yarp.cpp.

◆ startLocalizationService()

ReturnValue Localization2D_nwc_yarp::startLocalizationService ( )
overridevirtual

Starts the localization service.

Returns
a ReturnValue, convertible to true/false

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

Definition at line 158 of file Localization2D_nwc_yarp.cpp.

◆ stopLocalizationService()

ReturnValue Localization2D_nwc_yarp::stopLocalizationService ( )
overridevirtual

Stops the localization service.

Returns
a ReturnValue, convertible to true/false

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

Definition at line 164 of file Localization2D_nwc_yarp.cpp.

Member Data Documentation

◆ m_mutex

std::mutex Localization2D_nwc_yarp::m_mutex
protected

Definition at line 42 of file Localization2D_nwc_yarp.h.

◆ m_RPC

ILocalization2DMsgs Localization2D_nwc_yarp::m_RPC
protected

Definition at line 44 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 43 of file Localization2D_nwc_yarp.h.


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