YARP
Yet Another Robot Platform
BatteryClient.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #include "BatteryClient.h"
20 
21 #include <yarp/os/Log.h>
22 #include <yarp/os/LogComponent.h>
23 #include <yarp/os/LogStream.h>
24 
27 using namespace yarp::dev;
28 using namespace yarp::os;
29 using namespace yarp::sig;
30 
31 namespace {
32 YARP_LOG_COMPONENT(BATTERYCLIENT, "yarp.device.batteryClient")
33 } // namespace
34 
36 {
37  mutex.lock();
38  count=0;
39  deltaT=0;
40  deltaTMax=0;
41  deltaTMin=1e22;
42  now=Time::now();
43  prev=now;
44  mutex.unlock();
45 }
46 
48 {
50  resetStat();
51 }
52 
54 {
55  now=Time::now();
56  mutex.lock();
57 
58  if (count>0)
59  {
60  double tmpDT=now-prev;
61  deltaT+=tmpDT;
62  if (tmpDT>deltaTMax)
63  deltaTMax=tmpDT;
64  if (tmpDT<deltaTMin)
65  deltaTMin=tmpDT;
66 
67  //compare network time
68  if (tmpDT*1000<BATTERY_TIMEOUT)
69  {
70  state = b.get(5).asInt32();
71  }
72  else
73  {
75  }
76  }
77 
78  prev=now;
79  count++;
80 
81  lastBottle=b;
82  Stamp newStamp;
83  getEnvelope(newStamp);
84 
85  //initialization (first received data)
86  if (lastStamp.isValid()==false)
87  {
88  lastStamp = newStamp;
89  }
90 
91  //now compare timestamps
92  if ((1000*(newStamp.getTime()-lastStamp.getTime()))<BATTERY_TIMEOUT)
93  {
94  state = b.get(5).asInt32();
95  }
96  else
97  {
99  }
100  lastStamp = newStamp;
101 
102  mutex.unlock();
103 }
104 
106 {
107  mutex.lock();
108  int ret=state;
110  {
111  data=lastBottle;
112  stmp = lastStamp;
113  }
114  mutex.unlock();
115 
116  return ret;
117 }
118 
120 {
121  mutex.lock();
122  double voltage = lastBottle.get(0).asFloat64();
123  mutex.unlock();
124  return voltage;
125 }
126 
128 {
129  mutex.lock();
130  double current = lastBottle.get(1).asFloat64();
131  mutex.unlock();
132  return current;
133 }
134 
136 {
137  mutex.lock();
138  double charge = lastBottle.get(2).asFloat64();
139  mutex.unlock();
140  return charge;
141 }
142 
144 {
145  mutex.lock();
146  int status = lastBottle.get(4).asInt32();
147  mutex.unlock();
148  return status;
149 }
150 
152 {
153  mutex.lock();
154  double temperature = lastBottle.get(3).asFloat64();
155  mutex.unlock();
156  return temperature;
157 }
158 
160 {
161  mutex.lock();
162  int ret=count;
163  mutex.unlock();
164  return ret;
165 }
166 
167 // time is in ms
168 void BatteryInputPortProcessor::getEstFrequency(int &ite, double &av, double &min, double &max)
169 {
170  mutex.lock();
171  ite=count;
172  min=deltaTMin*1000;
173  max=deltaTMax*1000;
174  if (count<1)
175  {
176  av=0;
177  }
178  else
179  {
180  av=deltaT/count;
181  }
182  av=av*1000;
183  mutex.unlock();
184 }
185 
187 {
188  local.clear();
189  remote.clear();
190  yCDebug(BATTERYCLIENT) << config.toString();
191  local = config.find("local").asString();
192  remote = config.find("remote").asString();
193 
194  if (local=="")
195  {
196  yCError(BATTERYCLIENT, "open(): Invalid local name. --local parameter missing.");
197  return false;
198  }
199  if (remote=="")
200  {
201  yCError(BATTERYCLIENT, "open(): Invalid remote name. --remote parameter missing.");
202  return false;
203  }
204 
205  std::string local_stream = local;
206  local_stream += "/data:i";
207  std::string local_rpc = local;
208  local_rpc += "/rpc:o";
209  std::string remote_stream = remote;
210  remote_stream += "/data:o";
211  std::string remote_rpc = remote;
212  remote_rpc += "/rpc:i";
213 
214  if (!inputPort.open(local_stream))
215  {
216  yCError(BATTERYCLIENT, "open(): Could not open port %s, check network", local_stream.c_str());
217  return false;
218  }
219  inputPort.useCallback();
220 
221  if (!rpcPort.open(local_rpc))
222  {
223  yCError(BATTERYCLIENT, "open(): Could not open rpc port %s, check network", local_rpc.c_str());
224  return false;
225  }
226 
227  bool ok=Network::connect(remote_stream.c_str(), local_stream.c_str(), "udp");
228  if (!ok)
229  {
230  yCError(BATTERYCLIENT, "open(): Could not connect %s -> %s", remote_stream.c_str(), local_stream.c_str());
231  return false;
232  }
233 
234  ok=Network::connect(local_rpc, remote_rpc);
235  if (!ok)
236  {
237  yCError(BATTERYCLIENT, "open() Could not connect %s -> %s", remote_rpc.c_str(), local_rpc.c_str());
238  return false;
239  }
240 
241  return true;
242 }
243 
245 {
246  rpcPort.close();
247  inputPort.close();
248  return true;
249 }
250 
251 bool BatteryClient::getBatteryVoltage(double &voltage)
252 {
253  voltage = inputPort.getVoltage();
254  return true;
255 }
256 
257 bool BatteryClient::getBatteryCurrent(double &current)
258 {
259  current = inputPort.getCurrent();
260  return true;
261 }
262 
264 {
265  charge = inputPort.getCharge();
266  return true;
267 }
268 
270 {
271  status = (Battery_status)inputPort.getStatus();
272  return true;
273 }
274 
275 bool BatteryClient::getBatteryTemperature(double &temperature)
276 {
277  temperature = inputPort.getTemperature();
278  return true;
279 }
280 
281 bool BatteryClient::getBatteryInfo(std::string &battery_info)
282 {
283  Bottle cmd, response;
286  bool ok = rpcPort.write(cmd, response);
287  if (CHECK_FAIL(ok, response)!=false)
288  {
289  battery_info = response.get(2).asString();
290  return true;
291  }
292  return false;
293 }
294 
296 {
297  return lastTs;
298 }
LogStream.h
yarp::dev::IBattery::Battery_status
Battery_status
Definition: IBattery.h:36
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
BatteryInputPortProcessor::getEstFrequency
void getEstFrequency(int &ite, double &av, double &min, double &max)
Definition: BatteryClient.cpp:168
BatteryInputPortProcessor::onRead
void onRead(yarp::os::Bottle &v) override
Definition: BatteryClient.cpp:53
BatteryInputPortProcessor::BatteryInputPortProcessor
BatteryInputPortProcessor()
Definition: BatteryClient.cpp:47
yarp::sig
Signal processing.
Definition: Image.h:25
BatteryClient::open
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: BatteryClient.cpp:186
BatteryInputPortProcessor::getIterations
int getIterations()
Definition: BatteryClient.cpp:159
BatteryInputPortProcessor::getVoltage
double getVoltage()
Definition: BatteryClient.cpp:119
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
VOCAB_BATTERY_INFO
constexpr yarp::conf::vocab32_t VOCAB_BATTERY_INFO
Definition: IBattery.h:18
BatteryClient::getBatteryCurrent
bool getBatteryCurrent(double &current) override
Get the instantaneous current measurement.
Definition: BatteryClient.cpp:257
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
BatteryClient::getLastInputStamp
yarp::os::Stamp getLastInputStamp() override
Get the time stamp for the last read data.
Definition: BatteryClient.cpp:295
BatteryInputPortProcessor::getLast
int getLast(yarp::os::Bottle &data, yarp::os::Stamp &stmp)
Definition: BatteryClient.cpp:105
BatteryInputPortProcessor::getStatus
int getStatus()
Definition: BatteryClient.cpp:143
yarp::dev::IBattery::BATTERY_TIMEOUT
@ BATTERY_TIMEOUT
Definition: IBattery.h:41
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
Log.h
BatteryClient.h
BatteryInputPortProcessor::getTemperature
double getTemperature()
Definition: BatteryClient.cpp:151
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
BatteryClient::getBatteryCharge
bool getBatteryCharge(double &charge) override
get the battery status of charge
Definition: BatteryClient.cpp:263
yarp::os::Stamp::getTime
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:37
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
BatteryInputPortProcessor::getCharge
double getCharge()
Definition: BatteryClient.cpp:135
BATTERY_TIMEOUT
const int BATTERY_TIMEOUT
Definition: BatteryClient.h:37
BatteryClient::close
bool close() override
Close the DeviceDriver.
Definition: BatteryClient.cpp:244
VOCAB_IBATTERY
constexpr yarp::conf::vocab32_t VOCAB_IBATTERY
Definition: IBattery.h:17
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
yarp::os::Bottle::addVocab
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:167
BatteryClient::getBatteryTemperature
bool getBatteryTemperature(double &temperature) override
get the battery temperature
Definition: BatteryClient.cpp:275
LogComponent.h
BatteryInputPortProcessor::resetStat
void resetStat()
Definition: BatteryClient.cpp:35
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::os::Value::asInt32
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
BatteryClient::getBatteryStatus
bool getBatteryStatus(Battery_status &status) override
get the battery status
Definition: BatteryClient.cpp:269
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
BatteryInputPortProcessor::getCurrent
double getCurrent()
Definition: BatteryClient.cpp:127
yarp::dev::IBattery::BATTERY_GENERAL_ERROR
@ BATTERY_GENERAL_ERROR
Definition: IBattery.h:40
BatteryClient::getBatteryVoltage
bool getBatteryVoltage(double &voltage) override
Get the instantaneous voltage measurement.
Definition: BatteryClient.cpp:251
BatteryClient::getBatteryInfo
bool getBatteryInfo(std::string &battery_info) override
get the battery hardware charactestics (e.g.
Definition: BatteryClient.cpp:281