localization2DClient
A device which allows a user application retrieve the current position of the robot in the world.
More...
#include <localization2DClient/Localization2DClient.h>
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... | |
![]() | |
~DeviceDriver () override=default | |
Destructor. More... | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. More... | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. More... | |
![]() | |
virtual | ~IConfig () |
Destructor. More... | |
virtual bool | configure (Searchable &config) |
Change online parameters. More... | |
![]() | |
virtual | ~ILocalization2D () |
Destructor. 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 |
localization2DClient
A device which allows a user application retrieve the current position of the robot in the world.
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 Localization2DClient device. | |
remote | - | string | - | - | Yes | Full port name of the port opened on the server side, to which the Localization2DClient connects to. | E.g.(https://github.com/robotology/navigation/src/localizationServer) |
Definition at line 39 of file Localization2DClient.h.
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 393 of file Localization2DClient.cpp.
|
overridevirtual |
Gets the current position of the robot w.r.t world reference frame.
loc | the location of the robot |
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 187 of file Localization2DClient.cpp.
|
overridevirtual |
Gets the current position of the robot w.r.t world reference frame, plus the covariance.
loc | the location of the robot |
cov | the 3x3 covariance matrix |
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 220 of file Localization2DClient.cpp.
|
overridevirtual |
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local reference frame.
loc | the estimated odometry. |
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 149 of file Localization2DClient.cpp.
|
overridevirtual |
Gets a set of pose estimates computed by the localization algorithm.
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 263 of file Localization2DClient.cpp.
|
overridevirtual |
Gets the current status of the localization task.
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 313 of file Localization2DClient.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is 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). |
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 26 of file Localization2DClient.cpp.
|
overridevirtual |
Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame.
loc | the location of the robot |
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 84 of file Localization2DClient.cpp.
|
overridevirtual |
Sets the initial pose for the localization algorithm which estimates the current position of the robot w.r.t world reference frame.
loc | the location of the robot |
cov | the 3x3 covariance matrix |
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 113 of file Localization2DClient.cpp.
|
overridevirtual |
Starts the localization service.
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 343 of file Localization2DClient.cpp.
|
overridevirtual |
Stops the localization service.
Implements yarp::dev::Nav2D::ILocalization2D.
Definition at line 368 of file Localization2DClient.cpp.
|
protected |
Definition at line 46 of file Localization2DClient.h.
|
protected |
Definition at line 44 of file Localization2DClient.h.
|
protected |
Definition at line 47 of file Localization2DClient.h.
|
protected |
Definition at line 45 of file Localization2DClient.h.