YARP
Yet Another Robot Platform
Localization2DServer Class Reference

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

#include <localization2DServer/Localization2DServer.h>

+ Inheritance diagram for Localization2DServer:

Public Member Functions

 Localization2DServer ()
 
virtual bool open (yarp::os::Searchable &prop) override
 Open the DeviceDriver. More...
 
virtual bool close () override
 Close the DeviceDriver. More...
 
virtual bool detachAll () override
 Detach the object (you must have first called attach). More...
 
virtual bool attachAll (const yarp::dev::PolyDriverList &l) override
 Attach to a list of objects. More...
 
virtual void run () override
 Loop function. More...
 
bool initialize_YARP (yarp::os::Searchable &config)
 
bool initialize_ROS (yarp::os::Searchable &config)
 
virtual 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)
 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::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor. More...
 
- Public Member Functions inherited from yarp::os::PortReader
virtual ~PortReader ()
 Destructor. More...
 
virtual Type getReadType () const
 

Protected Attributes

bool m_ros_publish_odometry_on_topic
 
bool m_ros_publish_odometry_on_tf
 
std::string m_local_name
 
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
 
std::string m_robot_frame
 
std::string m_fixed_frame
 
std::string m_child_frame_id
 
std::string m_parent_frame_id
 
yarp::os::Nodem_ros_node
 
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometrym_odometry_publisher
 
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessagem_tf_publisher
 
yarp::dev::PolyDriver pLoc
 
yarp::dev::Nav2D::ILocalization2DiLoc
 
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
 
yarp::dev::OdometryData m_current_odometry
 
yarp::dev::Nav2D::Map2DLocation m_current_position
 
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
 

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

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

Localization2DServer

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 - /localizationServer No The name of the server, used as a prefix for the opened ports By default ports opened are /localizationServer/rpc and /localizationServer/streaming:o
subdevice - string - - Yes The name of the of Localization device to be used -
ROS publish_tf bool - false No If true, odometry data will be published on global ROS /tf topic -
ROS publish_odom bool - false No If true, odometry data will be published on a user-defined ROS topic The default name of the topic is built as: name+"/odom"

Definition at line 59 of file Localization2DServer.h.

Constructor & Destructor Documentation

◆ Localization2DServer()

Localization2DServer::Localization2DServer ( )

Definition at line 55 of file Localization2DServer.cpp.

Member Function Documentation

◆ attachAll()

bool Localization2DServer::attachAll ( const yarp::dev::PolyDriverList p)
overridevirtual

Attach to a list of objects.

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

Implements yarp::dev::IMultipleWrapper.

Definition at line 67 of file Localization2DServer.cpp.

◆ close()

bool Localization2DServer::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 302 of file Localization2DServer.cpp.

◆ detachAll()

bool Localization2DServer::detachAll ( )
overridevirtual

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

Returns
true/false on success failure.

Implements yarp::dev::IMultipleWrapper.

Definition at line 108 of file Localization2DServer.cpp.

◆ initialize_ROS()

bool Localization2DServer::initialize_ROS ( yarp::os::Searchable config)

Definition at line 213 of file Localization2DServer.cpp.

◆ initialize_YARP()

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

Definition at line 278 of file Localization2DServer.cpp.

◆ open()

bool Localization2DServer::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 118 of file Localization2DServer.cpp.

◆ read()

bool Localization2DServer::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 331 of file Localization2DServer.cpp.

◆ run()

void Localization2DServer::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 503 of file Localization2DServer.cpp.

Member Data Documentation

◆ iLoc

yarp::dev::Nav2D::ILocalization2D* Localization2DServer::iLoc
protected

Definition at line 91 of file Localization2DServer.h.

◆ m_2DLocationPort

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

Definition at line 75 of file Localization2DServer.h.

◆ m_2DLocationPortName

std::string Localization2DServer::m_2DLocationPortName
protected

Definition at line 76 of file Localization2DServer.h.

◆ m_child_frame_id

std::string Localization2DServer::m_child_frame_id
protected

Definition at line 83 of file Localization2DServer.h.

◆ m_current_odometry

yarp::dev::OdometryData Localization2DServer::m_current_odometry
protected

Definition at line 99 of file Localization2DServer.h.

◆ m_current_position

yarp::dev::Nav2D::Map2DLocation Localization2DServer::m_current_position
protected

Definition at line 100 of file Localization2DServer.h.

◆ m_current_status

yarp::dev::Nav2D::LocalizationStatusEnum Localization2DServer::m_current_status
protected

Definition at line 101 of file Localization2DServer.h.

◆ m_fixed_frame

std::string Localization2DServer::m_fixed_frame
protected

Definition at line 80 of file Localization2DServer.h.

◆ m_getdata_using_periodic_thread

bool Localization2DServer::m_getdata_using_periodic_thread
protected

Definition at line 97 of file Localization2DServer.h.

◆ m_loc_stamp

yarp::os::Stamp Localization2DServer::m_loc_stamp
protected

Definition at line 95 of file Localization2DServer.h.

◆ m_local_name

std::string Localization2DServer::m_local_name
protected

Definition at line 72 of file Localization2DServer.h.

◆ m_odom_stamp

yarp::os::Stamp Localization2DServer::m_odom_stamp
protected

Definition at line 96 of file Localization2DServer.h.

◆ m_odometry_publisher

yarp::os::Publisher<yarp::rosmsg::nav_msgs::Odometry> Localization2DServer::m_odometry_publisher
protected

Definition at line 86 of file Localization2DServer.h.

◆ m_odometryPort

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

Definition at line 77 of file Localization2DServer.h.

◆ m_odometryPortName

std::string Localization2DServer::m_odometryPortName
protected

Definition at line 78 of file Localization2DServer.h.

◆ m_parent_frame_id

std::string Localization2DServer::m_parent_frame_id
protected

Definition at line 84 of file Localization2DServer.h.

◆ m_period

double Localization2DServer::m_period
protected

Definition at line 94 of file Localization2DServer.h.

◆ m_robot_frame

std::string Localization2DServer::m_robot_frame
protected

Definition at line 79 of file Localization2DServer.h.

◆ m_ros_node

yarp::os::Node* Localization2DServer::m_ros_node
protected

Definition at line 85 of file Localization2DServer.h.

◆ m_ros_publish_odometry_on_tf

bool Localization2DServer::m_ros_publish_odometry_on_tf
protected

Definition at line 69 of file Localization2DServer.h.

◆ m_ros_publish_odometry_on_topic

bool Localization2DServer::m_ros_publish_odometry_on_topic
protected

Definition at line 68 of file Localization2DServer.h.

◆ m_rpcPort

yarp::os::Port Localization2DServer::m_rpcPort
protected

Definition at line 73 of file Localization2DServer.h.

◆ m_rpcPortName

std::string Localization2DServer::m_rpcPortName
protected

Definition at line 74 of file Localization2DServer.h.

◆ m_stats_time_last

double Localization2DServer::m_stats_time_last
protected

Definition at line 93 of file Localization2DServer.h.

◆ m_tf_publisher

yarp::os::Publisher<yarp::rosmsg::tf2_msgs::TFMessage> Localization2DServer::m_tf_publisher
protected

Definition at line 87 of file Localization2DServer.h.

◆ pLoc

yarp::dev::PolyDriver Localization2DServer::pLoc
protected

Definition at line 90 of file Localization2DServer.h.


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