YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
battery_nwc_yarp.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: LGPL-2.1-or-later
4 */
5
6#ifndef YARP_DEV_BATTERYCLIENT_BATTERYCLIENT_H
7#define YARP_DEV_BATTERYCLIENT_BATTERYCLIENT_H
8
9
10#include <yarp/os/Network.h>
13#include <yarp/dev/IBattery.h>
16#include <yarp/sig/Vector.h>
17#include <yarp/os/Time.h>
18#include <yarp/dev/PolyDriver.h>
19
20#include <mutex>
21
22
23#define DEFAULT_THREAD_PERIOD 20 //ms
24const int BATTERY_TIMEOUT=100; //ms
25
26
27class BatteryInputPortProcessor : public yarp::os::BufferedPort<yarp::os::Bottle>
28{
29 yarp::os::Bottle lastBottle;
30 std::mutex mutex;
31 yarp::os::Stamp lastStamp;
32 double deltaT;
33 double deltaTMax;
34 double deltaTMin;
35 double prev;
36 double now;
37
38 int state;
39 int count;
40
41public:
42
43 inline void resetStat();
44
46
48 void onRead(yarp::os::Bottle &v) override;
49
50 inline int getLast(yarp::os::Bottle &data, yarp::os::Stamp &stmp);
51
52 inline int getIterations();
53
54 // time is in ms
55 void getEstFrequency(int &ite, double &av, double &min, double &max);
56
57 double getVoltage();
58 double getCurrent();
59 double getCharge();
60 double getTemperature();
61 int getStatus();
62
63};
64
83{
84protected:
87 std::string local;
88 std::string remote;
89 std::string m_carrier;
90 yarp::os::Stamp lastTs; //used by IPreciselyTimed
91 std::string deviceId;
92
93public:
94
95 /* DeviceDriver methods */
96 bool open(yarp::os::Searchable& config) override;
97 bool close() override;
98
99
100 /* IPreciselyTimed methods */
106
112 bool getBatteryVoltage(double &voltage) override;
113
119 bool getBatteryCurrent(double &current) override;
120
126 bool getBatteryCharge(double &charge) override;
127
133 bool getBatteryStatus(Battery_status &status) override;
134
140 bool getBatteryInfo(std::string &battery_info) override;
141
147 bool getBatteryTemperature(double &temperature) override;
148};
149
150#endif // YARP_DEV_BATTERYCLIENT_BATTERYCLIENT_H
define control board standard interfaces
contains the definition of a Vector type
const int BATTERY_TIMEOUT
int getLast(yarp::os::Bottle &data, yarp::os::Stamp &stmp)
void onRead(yarp::os::Bottle &v) override
void getEstFrequency(int &ite, double &av, double &min, double &max)
Battery_nwc_yarp: The client side of any IBattery capable device.
bool close() override
Shut the object down.
yarp::os::Stamp getLastInputStamp() override
Get the time stamp for the last read data.
std::string m_carrier
bool getBatteryVoltage(double &voltage) override
Get the instantaneous voltage measurement.
bool getBatteryCharge(double &charge) override
get the battery status of charge
yarp::os::Stamp lastTs
bool open(yarp::os::Searchable &config) override
Initialize the object.
yarp::os::Port rpcPort
bool getBatteryTemperature(double &temperature) override
get the battery temperature
bool getBatteryStatus(Battery_status &status) override
get the battery status
bool getBatteryCurrent(double &current) override
Get the instantaneous current measurement.
bool getBatteryInfo(std::string &battery_info) override
get the battery hardware charactestics (e.g.
BatteryInputPortProcessor inputPort
Interface implemented by all device drivers.
A generic battery interface.
Definition IBattery.h:28
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:64
A mini-server for performing network communication in the background.
A mini-server for network communication.
Definition Port.h:46
A base class for nested structures that can be searched.
Definition Searchable.h:56
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21