YARP
Yet Another Robot Platform
BatteryWrapper.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 "BatteryWrapper.h"
20 #include <sstream>
21 #include <string>
23 #include <yarp/os/LogComponent.h>
24 #include <yarp/os/LogStream.h>
25 #include <time.h>
26 #include <stdlib.h>
27 
28 using namespace yarp::sig;
29 using namespace yarp::dev;
30 using namespace yarp::os;
31 using namespace std;
32 
33 namespace {
34 YARP_LOG_COMPONENT(BATTERYWRAPPER, "yarp.devices.BatteryWrapper")
35 }
36 
38 {
39  m_period = DEFAULT_THREAD_PERIOD;
40  m_ibattery_p = nullptr;
41  m_ownDevices = false;
42  memset(m_log_buffer, 0, 1024);
43 }
44 
46 {
47  threadRelease();
48  m_ibattery_p = nullptr;
49 }
50 
51 bool BatteryWrapper::attachAll(const PolyDriverList &battery2attach)
52 {
53  if (m_ownDevices)
54  {
55  return false;
56  }
57 
58  if (battery2attach.size() != 1)
59  {
60  yCError(BATTERYWRAPPER, "Cannot attach more than one device");
61  return false;
62  }
63 
64  yarp::dev::PolyDriver * Idevice2attach = battery2attach[0]->poly;
65 
66  if (Idevice2attach->isValid())
67  {
68  Idevice2attach->view(m_ibattery_p);
69  }
70 
71  if(nullptr == m_ibattery_p)
72  {
73  yCError(BATTERYWRAPPER, "Subdevice passed to attach method is invalid");
74  return false;
75  }
76  attach(m_ibattery_p);
77  PeriodicThread::setPeriod(m_period);
78  return PeriodicThread::start();
79 }
80 
82 {
83  if (PeriodicThread::isRunning())
84  {
85  PeriodicThread::stop();
86  }
87  m_ibattery_p = nullptr;
88  return true;
89 }
90 
91 void BatteryWrapper::attach(yarp::dev::IBattery *s)
92 {
93  m_ibattery_p=s;
94 }
95 
96 void BatteryWrapper::detach()
97 {
98  m_ibattery_p = nullptr;
99 }
100 
101 bool BatteryWrapper::read(yarp::os::ConnectionReader& connection)
102 {
103  yarp::os::Bottle in;
104  yarp::os::Bottle out;
105  bool ok = in.read(connection);
106  if (!ok) return false;
107 
108  // parse in, prepare out
109  int code = in.get(0).asVocab();
110  bool ret = false;
111  if (code == VOCAB_IBATTERY)
112  {
113  int cmd = in.get(1).asVocab();
114  if (cmd == VOCAB_BATTERY_INFO)
115  {
116  if (m_ibattery_p)
117  {
118  std::string info;
119  m_ibattery_p->getBatteryInfo(info);
120  out.addVocab(VOCAB_IS);
121  out.addVocab(cmd);
122  out.addString(info);
123  ret = true;
124  }
125  }
126  else
127  {
128  yCError(BATTERYWRAPPER, "Invalid vocab received");
129  }
130  }
131  else
132  {
133  yCError(BATTERYWRAPPER, "Invalid vocab received");
134  }
135 
136  if (!ret)
137  {
138  out.clear();
139  out.addVocab(VOCAB_FAILED);
140  }
141 
142  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
143  if (returnToSender != nullptr)
144  {
145  out.write(*returnToSender);
146  }
147  return true;
148 }
149 
151 {
152  return true;
153 }
154 
156 {
157  Property params;
158  params.fromString(config.toString());
159 
160  if (!config.check("period"))
161  {
162  m_period = 1.0;
163  yCWarning(BATTERYWRAPPER) << "Missing 'period' parameter. Assuming default value 1.0 s";
164  }
165  else
166  {
167  m_period = config.find("period").asFloat32();
168  }
169  yCInfo(BATTERYWRAPPER) << "Using period:" << m_period << "s";
170 
171  if (!config.check("quitPortName"))
172  {
173  m_quitPortName = config.find("quitPortName").asString();
174  }
175 
176  if (!config.check("name"))
177  {
178  yCError(BATTERYWRAPPER) << "Missing 'name' parameter. Check you configuration file; it must be like:";
179  yCError(BATTERYWRAPPER) << "--name: prefix of the ports opened by the device, e.g. /robotName/battery1";
180  yCError(BATTERYWRAPPER) << "/data:o and /rpc:i are automatically appended by the wrapper at the end";
181  return false;
182  }
183  else
184  {
185  m_streamingPortName = config.find("name").asString() + "/data:o";
186  m_rpcPortName = config.find("name").asString() + "/rpc:i";
187  }
188 
189  m_enable_shutdown = config.check("enable_shutdown", Value(0), "enable/disable the automatic shutdown").asBool();
190  m_enable_log = config.check("enable_log", Value(0), "enable/disable log to file").asBool();
191 
192  if(!initialize_YARP(config))
193  {
194  yCError(BATTERYWRAPPER) << m_sensorId << "Error initializing YARP ports";
195  return false;
196  }
197 
198  if (m_enable_log)
199  {
200  yCInfo(BATTERYWRAPPER, "writing to log file batteryLog.txt");
201  m_logFile = fopen("batteryLog.txt", "w");
202  }
203 
204  if (config.check("subdevice"))
205  {
206  PolyDriverList driverlist;
207  Property p;
208  p.fromString(config.toString());
209  p.unput("device");
210  p.unput("subdevice");
211  p.put("device", config.find("subdevice").asString());
212  p.setMonitor(config.getMonitor(), "subdevice"); // pass on any monitoring
213 
214  if (!m_driver.open(p) || !m_driver.isValid())
215  {
216  yCError(BATTERYWRAPPER) << "Failed to open subdevice.. check params";
217  return false;
218  }
219 
220  driverlist.push(&m_driver, "1");
221  if (!attachAll(driverlist))
222  {
223  yCError(BATTERYWRAPPER) << "Failed to open subdevice.. check params";
224  return false;
225  }
226  m_ownDevices = true;
227  }
228 
229  return true;
230 }
231 
232 bool BatteryWrapper::initialize_YARP(yarp::os::Searchable &params)
233 {
234  if (!m_streamingPort.open(m_streamingPortName.c_str()))
235  {
236  yCError(BATTERYWRAPPER) << "Error opening port" << m_streamingPortName;
237  return false;
238  }
239  if (!m_rpcPort.open(m_rpcPortName.c_str()))
240  {
241  yCError(BATTERYWRAPPER) << "Error opening port" << m_rpcPortName;
242  return false;
243  }
244  m_rpcPort.setReader(*this);
245  return true;
246 }
247 
249 {
250 }
251 
253 {
254  if (m_ibattery_p!=nullptr)
255  {
256  m_log_buffer[0] = 0;
257  double battery_charge = 0;
258  double battery_voltage = 0;
259  double battery_current = 0;
260  double battery_temperature = 0;
262 
263  bool ret = true;
264  ret &= m_ibattery_p->getBatteryCharge(battery_charge);
265  ret &= m_ibattery_p->getBatteryVoltage(battery_voltage);
266  ret &= m_ibattery_p->getBatteryCurrent(battery_current);
267  ret &= m_ibattery_p->getBatteryTemperature(battery_temperature);
268  ret &= m_ibattery_p->getBatteryStatus(status);
269 
270  if (ret)
271  {
272  m_lastStateStamp.update();
273  yarp::os::Bottle& b = m_streamingPort.prepare();
274  b.clear();
275  b.addFloat64(battery_voltage); //0
276  b.addFloat64(battery_current); //1
277  b.addFloat64(battery_charge); //2
278  b.addFloat64(battery_temperature); //3
279  b.addInt32(status); //4
280  m_streamingPort.setEnvelope(m_lastStateStamp);
281  m_streamingPort.write();
282 
283  // if the battery is not charging, checks its status of charge
284  if (battery_current>0.4) check_battery_status(battery_charge);
285 
286  // save data to file
287  if (m_enable_log)
288  {
289  time_t rawtime;
290  struct tm * timeinfo;
291  time(&rawtime);
292  timeinfo = localtime(&rawtime);
293  char* battery_timestamp = asctime(timeinfo);
294  std::snprintf(m_log_buffer, 1024, "battery status: %+6.1fA % 6.1fV charge:% 6.1f%% time: %s", battery_current, battery_voltage, battery_charge, battery_timestamp);
295  fprintf(m_logFile, "%s", m_log_buffer);
296  }
297  }
298  else
299  {
300  yCError(BATTERYWRAPPER, "BatteryWrapper: %s: Sensor returned error", m_sensorId.c_str());
301  }
302  }
303 }
304 
306 {
307  yCTrace(BATTERYWRAPPER, "BatteryWrapper::Close");
308  if (PeriodicThread::isRunning())
309  {
310  PeriodicThread::stop();
311  }
312 
313  //close the device
314  m_driver.close();
315 
316  m_streamingPort.interrupt();
317  m_streamingPort.close();
318  m_rpcPort.interrupt();
319  m_rpcPort.close();
320 
321  // save data to file
322  if (m_enable_log)
323  {
324  fclose(m_logFile);
325  }
326 
327  PeriodicThread::stop();
328  detachAll();
329  return true;
330 }
331 
332 void BatteryWrapper::notify_message(string msg)
333 {
334 #ifdef WIN32
335  yCWarning(BATTERYWRAPPER, "%s", msg.c_str());
336 #else
337  yCWarning(BATTERYWRAPPER, "%s", msg.c_str());
338  string cmd = "echo " + msg + " | wall";
339  int retval;
340  retval = system(cmd.c_str());
341  yCDebug(BATTERYWRAPPER) << "system executed command" << cmd.c_str() << " with return value:" << retval;
342 #endif
343 }
344 
345 void BatteryWrapper::emergency_shutdown(string msg)
346 {
347 #ifdef WIN32
348  string cmd;
349  cmd = "shutdown /s /t 120 /c " + msg;
350  yCWarning(BATTERYWRAPPER, "%s", msg.c_str());
351  system(cmd.c_str());
352 #else
353  string cmd;
354  int retval;
355  yCWarning(BATTERYWRAPPER, "%s", msg.c_str());
356  cmd = "echo " + msg + " | wall";
357  retval = system(cmd.c_str());
358  yCDebug(BATTERYWRAPPER) << "system executed command" << cmd.c_str() << " with return value:" << retval;
359 
360  cmd = "sudo shutdown -h 2 " + msg;
361  retval = system(cmd.c_str());
362  yCDebug(BATTERYWRAPPER) << "system executed command" << cmd.c_str() << " with return value:" << retval;
363 
364 #ifdef ICUB_SSH_SHUTDOWN
365  cmd = "ssh icub@pc104 sudo shutdown -h 2";
366  retval = system(cmd.c_str());
367  yCDebug(BATTERYWRAPPER) << "system executed command" << cmd.c_str() << " with return value:" << retval;
368 #endif
369 #endif
370 }
371 
372 void BatteryWrapper::check_battery_status(double battery_charge)
373 {
374  static bool notify_15 = true;
375  static bool notify_12 = true;
376  static bool notify_10 = true;
377  static bool notify_0 = true;
378 
379  if (battery_charge > 20)
380  {
381  notify_15 = true;
382  notify_12 = true;
383  notify_10 = true;
384  notify_0 = true;
385  }
386 
387  if (battery_charge < 5)
388  {
389  if (notify_0)
390  {
391  if (m_enable_shutdown)
392  {
393  emergency_shutdown("CRITICAL WARNING: battery charge below critical level 5%. The robot will be stopped and the system will shutdown in 2mins.");
394  if (m_quitPortName != "") { stop_robot(m_quitPortName); }
395  notify_0 = false;
396  }
397  else
398  {
399  notify_message("CRITICAL WARNING: battery charge reached critical level 5%, but the emergency shutodown is currently disabled!");
400  notify_0 = false;
401  }
402  }
403  }
404  else if (battery_charge < 10)
405  {
406  if (notify_10) { notify_message("WARNING: battery charge below 10%"); notify_10 = false; }
407  }
408  else if (battery_charge < 12)
409  {
410  if (notify_12) { notify_message("WARNING: battery charge below 12%"); notify_12 = false; }
411  }
412  else if (battery_charge < 15)
413  {
414  if (notify_15) { notify_message("WARNING: battery charge below 15%"); notify_15 = false; }
415  }
416 }
417 
418 void BatteryWrapper::stop_robot(string quit_port)
419 {
420  //typical quit_port:
421  // "/icub/quit"
422  // "/ikart/quit"
423 
424  Port port_shutdown;
425  port_shutdown.open((m_streamingPortName + "/shutdown:o").c_str());
426  yarp::os::Network::connect((m_streamingPortName + "/shutdown:o").c_str(), quit_port.c_str());
427  Bottle bot;
428  bot.addString("quit");
429  port_shutdown.write(bot);
430  port_shutdown.interrupt();
431  port_shutdown.close();
432 }
yarp::os::Port::close
void close() override
Stop port activity.
Definition: Port.cpp:357
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::Value::asVocab
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:231
BatteryWrapper::threadInit
bool threadInit() override
Initialization method.
Definition: BatteryWrapper.cpp:150
yarp::dev::IBattery::getBatteryInfo
virtual bool getBatteryInfo(std::string &battery_info)=0
get the battery hardware characteristics (e.g.
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
BatteryWrapper::threadRelease
void threadRelease() override
Release method.
Definition: BatteryWrapper.cpp:248
yarp::os::Bottle::clear
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:124
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::dev::IBattery::getBatteryStatus
virtual bool getBatteryStatus(Battery_status &status)=0
get the battery status
yarp::sig
Signal processing.
Definition: Image.h:25
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
yarp::dev::IBattery::getBatteryTemperature
virtual bool getBatteryTemperature(double &temperature)=0
get the battery temperature
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
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
yarp::dev::PolyDriverList::size
int size() const
Definition: PolyDriverList.cpp:39
yarp::dev::PolyDriver::isValid
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:199
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::os::BufferedPort::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: BufferedPort-inl.h:82
yarp::os::BufferedPort::setEnvelope
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
Definition: BufferedPort-inl.h:232
yarp::os::Value::asFloat32
virtual yarp::conf::float32_t asFloat32() const
Get 32-bit floating point value.
Definition: Value.cpp:219
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
yarp::os::Port::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:82
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardInterfaces.h
define control board standard interfaces
yarp::os::Bottle::addFloat64
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition: Bottle.cpp:161
yarp::dev::PolyDriver::open
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:143
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
BatteryWrapper::detachAll
bool detachAll() override
Detach the object (you must have first called attach).
Definition: BatteryWrapper.cpp:81
yarp::dev::PolyDriverList::push
void push(PolyDriver *p, const char *k)
Definition: PolyDriverList.cpp:44
yarp::os::BufferedPort::prepare
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
Definition: BufferedPort-inl.h:114
yarp::os::Port
A mini-server for network communication.
Definition: Port.h:50
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
yarp::os::Bottle::write
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:233
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
yarp::os::NetworkBase::connect
static bool connect(const std::string &src, const std::string &dest, const std::string &carrier="", bool quiet=true)
Request that an output port connect to an input port.
Definition: Network.cpp:685
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:19
yarp::dev::PolyDriver::close
bool close() override
Close the DeviceDriver.
Definition: PolyDriver.cpp:176
yarp::os::BufferedPort::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: BufferedPort-inl.h:41
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
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::addInt32
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition: Bottle.cpp:143
BatteryWrapper::BatteryWrapper
BatteryWrapper()
Definition: BatteryWrapper.cpp:37
yarp::os::ConnectionReader::getWriter
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
yarp::dev::IBattery::getBatteryCurrent
virtual bool getBatteryCurrent(double &current)=0
Get the instantaneous current measurement.
yarp::os::Bottle::addString
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:173
yarp::os::Port::setReader
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:505
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
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
LogComponent.h
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::dev::IBattery::getBatteryVoltage
virtual bool getBatteryVoltage(double &voltage)=0
Get the instantaneous voltage measurement.
yarp::os::Port::write
bool write(const PortWriter &writer, const PortWriter *callback=nullptr) const override
Write an object to the port.
Definition: Port.cpp:430
yarp::os::Stamp::update
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:113
yarp::os::BufferedPort::write
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
Definition: BufferedPort-inl.h:126
yarp::dev::IBattery
A generic battery interface.
Definition: IBattery.h:33
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
BatteryWrapper::~BatteryWrapper
~BatteryWrapper()
Definition: BatteryWrapper.cpp:45
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD
Definition: AnalogWrapper.h:45
yarp::os::BufferedPort::close
void close() override
Stop port activity.
Definition: BufferedPort-inl.h:73
yarp::os::Bottle::read
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:243
yarp::os::Port::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:377
BatteryWrapper::run
void run() override
Loop function.
Definition: BatteryWrapper.cpp:252
yCTrace
#define yCTrace(component,...)
Definition: LogComponent.h:88
VOCAB_IS
constexpr yarp::conf::vocab32_t VOCAB_IS
Definition: GenericVocabs.h:17
BatteryWrapper.h
BatteryWrapper::attachAll
bool attachAll(const yarp::dev::PolyDriverList &p) override
Attach to a list of objects.
Definition: BatteryWrapper.cpp:51
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
BatteryWrapper::close
bool close() override
Close the DeviceDriver.
Definition: BatteryWrapper.cpp:305
yarp::os::Property::unput
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1029
BatteryWrapper::open
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Definition: BatteryWrapper.cpp:155
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
yarp::dev::IBattery::getBatteryCharge
virtual bool getBatteryCharge(double &charge)=0
get the battery status of charge