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

Battery_nwc_yarp: The client side of any IBattery capable device. More...

#include <battery_nwc_yarp/battery_nwc_yarp.h>

+ Inheritance diagram for Battery_nwc_yarp:

Public Member Functions

bool open (yarp::os::Searchable &config) override
 Initialize the object.
 
bool close () override
 Shut the object down.
 
yarp::os::Stamp getLastInputStamp () override
 Get the time stamp for the last read data.
 
bool getBatteryVoltage (double &voltage) override
 Get the instantaneous voltage measurement.
 
bool getBatteryCurrent (double &current) override
 Get the instantaneous current measurement.
 
bool getBatteryCharge (double &charge) override
 get the battery status of charge
 
bool getBatteryStatus (Battery_status &status) override
 get the battery status
 
bool getBatteryInfo (std::string &battery_info) override
 get the battery hardware charactestics (e.g.
 
bool getBatteryTemperature (double &temperature) override
 get the battery temperature
 
- 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::IPreciselyTimed
virtual ~IPreciselyTimed ()
 
- Public Member Functions inherited from yarp::dev::IBattery
virtual ~IBattery ()
 

Protected Attributes

BatteryInputPortProcessor inputPort
 
yarp::os::Port rpcPort
 
std::string local
 
std::string remote
 
std::string m_carrier
 
yarp::os::Stamp lastTs
 
std::string deviceId
 

Additional Inherited Members

- Public Types inherited from yarp::dev::IBattery
enum  Battery_status {
  BATTERY_OK_STANDBY = 0 ,
  BATTERY_OK_IN_CHARGE = 1 ,
  BATTERY_OK_IN_USE = 2 ,
  BATTERY_GENERAL_ERROR = 3 ,
  BATTERY_TIMEOUT = 4 ,
  BATTERY_LOW_WARNING = 5 ,
  BATTERY_CRITICAL_WARNING = 6
}
 

Detailed Description

Battery_nwc_yarp: The client side of any IBattery capable device.

Still single thread! concurrent access is unsafe.

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 batteryClient device.
remote - string - - Yes Full port name of the port opened on the server side, to which the batteryClient connects to.
carrier - string - tcp No The carier used for the connection with the server.

Definition at line 79 of file battery_nwc_yarp.h.

Member Function Documentation

◆ close()

bool Battery_nwc_yarp::close ( )
overridevirtual

Shut the object down.

You should override this.

Returns
true/false on success/failure.

Reimplemented from yarp::os::IConfig.

Definition at line 234 of file battery_nwc_yarp.cpp.

◆ getBatteryCharge()

bool Battery_nwc_yarp::getBatteryCharge ( double charge)
overridevirtual

get the battery status of charge

Parameters
chargethe charge measurement (0-100%)
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 253 of file battery_nwc_yarp.cpp.

◆ getBatteryCurrent()

bool Battery_nwc_yarp::getBatteryCurrent ( double current)
overridevirtual

Get the instantaneous current measurement.

Parameters
currentthe current measurement
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 247 of file battery_nwc_yarp.cpp.

◆ getBatteryInfo()

bool Battery_nwc_yarp::getBatteryInfo ( std::string &  battery_info)
overridevirtual

get the battery hardware charactestics (e.g.

max voltage etc)

Parameters
astring containing the battery infos
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 271 of file battery_nwc_yarp.cpp.

◆ getBatteryStatus()

bool Battery_nwc_yarp::getBatteryStatus ( Battery_status status)
overridevirtual

get the battery status

Parameters
statusthe battery status
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 259 of file battery_nwc_yarp.cpp.

◆ getBatteryTemperature()

bool Battery_nwc_yarp::getBatteryTemperature ( double temperature)
overridevirtual

get the battery temperature

Parameters
tempraturethe battery temperature
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 265 of file battery_nwc_yarp.cpp.

◆ getBatteryVoltage()

bool Battery_nwc_yarp::getBatteryVoltage ( double voltage)
overridevirtual

Get the instantaneous voltage measurement.

Parameters
voltagethe voltage measurement
Returns
true/false.

Implements yarp::dev::IBattery.

Definition at line 241 of file battery_nwc_yarp.cpp.

◆ getLastInputStamp()

Stamp Battery_nwc_yarp::getLastInputStamp ( )
overridevirtual

Get the time stamp for the last read data.

Returns
last time stamp.

Implements yarp::dev::IPreciselyTimed.

Definition at line 285 of file battery_nwc_yarp.cpp.

◆ open()

bool Battery_nwc_yarp::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 175 of file battery_nwc_yarp.cpp.

Member Data Documentation

◆ deviceId

std::string Battery_nwc_yarp::deviceId
protected

Definition at line 91 of file battery_nwc_yarp.h.

◆ inputPort

BatteryInputPortProcessor Battery_nwc_yarp::inputPort
protected

Definition at line 85 of file battery_nwc_yarp.h.

◆ lastTs

yarp::os::Stamp Battery_nwc_yarp::lastTs
protected

Definition at line 90 of file battery_nwc_yarp.h.

◆ local

std::string Battery_nwc_yarp::local
protected

Definition at line 87 of file battery_nwc_yarp.h.

◆ m_carrier

std::string Battery_nwc_yarp::m_carrier
protected

Definition at line 89 of file battery_nwc_yarp.h.

◆ remote

std::string Battery_nwc_yarp::remote
protected

Definition at line 88 of file battery_nwc_yarp.h.

◆ rpcPort

yarp::os::Port Battery_nwc_yarp::rpcPort
protected

Definition at line 86 of file battery_nwc_yarp.h.


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