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

Battery_nws_ros2: A ros2 nws to get the status of a battery and publish it on a ros2 topic. The attached device must implement a yarp::dev::IBattery interface. More...

#include </home/runner/work/yarp-documentation/yarp-documentation/yarp/opt-modules/yarp-devices-ros2/src/devices/battery_nws_ros2/Battery_nws_ros2.h>

+ Inheritance diagram for Battery_nws_ros2:

Public Member Functions

 Battery_nws_ros2 ()
 
 ~Battery_nws_ros2 ()
 
bool open (yarp::os::Searchable &params) override
 Initialize the object.
 
bool close () override
 Shut the object down.
 
bool attach (yarp::dev::PolyDriver *driver) override
 Attach to another object.
 
bool detach () override
 Detach the object (you must have first called attach).
 
bool threadInit () override
 Initialization method.
 
void threadRelease () override
 Release method.
 
void run () override
 Loop function.
 
- Public Member Functions inherited from yarp::os::PeriodicThread
 PeriodicThread (double period, ShouldUseSystemClock useSystemClock=ShouldUseSystemClock::No, PeriodicThreadClock clockAccuracy=PeriodicThreadClock::Relative)
 Constructor.
 
 PeriodicThread (double period, PeriodicThreadClock clockAccuracy)
 Constructor.
 
virtual ~PeriodicThread ()
 
bool start ()
 Call this to start the thread.
 
void step ()
 Call this to "step" the thread rather than starting it.
 
void stop ()
 Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called).
 
void askToStop ()
 Stop the thread.
 
bool isRunning () const
 Returns true when the thread is started, false otherwise.
 
bool isSuspended () const
 Returns true when the thread is suspended, false otherwise.
 
bool setPeriod (double period)
 Set the (new) period of the thread.
 
double getPeriod () const
 Return the current period of the thread.
 
void suspend ()
 Suspend the thread, the thread keeps running by doLoop is never executed.
 
void resume ()
 Resume the thread if previously suspended.
 
void resetStat ()
 Reset thread statistics.
 
double getEstimatedPeriod () const
 Return estimated period since last reset.
 
void getEstimatedPeriod (double &av, double &std) const
 Return estimated period since last reset.
 
unsigned int getIterations () const
 Return the number of iterations performed since last reset.
 
double getEstimatedUsed () const
 Return the estimated duration of the run() function since last reset.
 
void getEstimatedUsed (double &av, double &std) const
 Return estimated duration of the run() function since last reset.
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that.
 
int getPriority () const
 Query the current priority of the thread, if the OS supports that.
 
int getPolicy () const
 Query the current scheduling policy of the thread, if the OS supports that.
 
- 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.
 
bool close () override
 Close the 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::os::IConfig
virtual ~IConfig ()
 Destructor.
 
virtual bool configure (Searchable &config)
 Change online parameters.
 
- Public Member Functions inherited from yarp::dev::WrapperSingle
 ~WrapperSingle () override
 Destructor.
 
bool attachAll (const yarp::dev::PolyDriverList &drivers) final
 Attach to a list of objects.
 
bool detachAll () final
 Detach the object (you must have first called attach).
 
- Public Member Functions inherited from yarp::dev::IWrapper
virtual ~IWrapper ()
 Destructor.
 
- Public Member Functions inherited from yarp::dev::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor.
 

Additional Inherited Members

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

Detailed Description

Battery_nws_ros2: A ros2 nws to get the status of a battery and publish it on a ros2 topic. The attached device must implement a yarp::dev::IBattery interface.

Device description

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
period - double s 0.02 No refresh period of the broadcasted values in s default 0.02s
node_name - string - - Yes name of the ros2 node
topic_name - string - - Yes name of the topic where the device must publish the data must begin with an initial '/'

Definition at line 37 of file Battery_nws_ros2.h.

Constructor & Destructor Documentation

◆ Battery_nws_ros2()

Battery_nws_ros2::Battery_nws_ros2 ( )

Definition at line 14 of file Battery_nws_ros2.cpp.

◆ ~Battery_nws_ros2()

Battery_nws_ros2::~Battery_nws_ros2 ( )

Definition at line 18 of file Battery_nws_ros2.cpp.

Member Function Documentation

◆ attach()

bool Battery_nws_ros2::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 24 of file Battery_nws_ros2.cpp.

◆ close()

bool Battery_nws_ros2::close ( )
overridevirtual

Shut the object down.

You should override this.

Returns
true/false on success/failure.

Reimplemented from yarp::os::IConfig.

Definition at line 152 of file Battery_nws_ros2.cpp.

◆ detach()

bool Battery_nws_ros2::detach ( )
overridevirtual

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

Returns
true/false on success failure.

Implements yarp::dev::IWrapper.

Definition at line 43 of file Battery_nws_ros2.cpp.

◆ open()

bool Battery_nws_ros2::open ( yarp::os::Searchable config)
overridevirtual

Initialize the object.

You should override this.

Parameters
configis a list of parameters for the object. Which parameters are effective for your object can vary.
Returns
true/false upon success/failure

Reimplemented from yarp::os::IConfig.

Definition at line 58 of file Battery_nws_ros2.cpp.

◆ run()

void Battery_nws_ros2::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 103 of file Battery_nws_ros2.cpp.

◆ threadInit()

bool Battery_nws_ros2::threadInit ( )
overridevirtual

Initialization method.

The thread executes this function when it starts and before "run". This is a good place to perform initialization tasks that need to be done by the thread itself (device drivers initialization, memory allocation etc). If the function returns false the thread quits and never calls "run". The return value of threadInit() is notified to the class and passed as a parameter to afterStart(). Note that afterStart() is called by the same thread that is executing the "start" method.

Reimplemented from yarp::os::PeriodicThread.

Definition at line 53 of file Battery_nws_ros2.cpp.

◆ threadRelease()

void Battery_nws_ros2::threadRelease ( )
overridevirtual

Release method.

The thread executes this function once when it exits, after the last "run". This is a good place to release resources that were initialized in threadInit() (release memory, and device driver resources).

Reimplemented from yarp::os::PeriodicThread.

Definition at line 99 of file Battery_nws_ros2.cpp.


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