battery.py
Go to the documentation of this file.
1 import roslib;roslib.load_manifest('create_dashboard')
2 import rospy
3 
4 from rqt_robot_dashboard.widgets import BatteryDashWidget
5 
6 def non_zero(value):
7  if value < 0.00001 and value > -0.00001:
8  return 0.00001
9  return value
10 
11 class TurtlebotBattery(BatteryDashWidget):
12  def __init__(self, name='battery'):
13  icons = []
14  charge_icons = []
15  icons.append(['ic-battery-0.svg'])
16  icons.append(['ic-battery-20.svg'])
17  icons.append(['ic-battery-40.svg'])
18  icons.append(['ic-battery-60-green.svg'])
19  icons.append(['ic-battery-80-green.svg'])
20  icons.append(['ic-battery-100-green.svg'])
21  charge_icons.append(['ic-battery-charge-0.svg'])
22  charge_icons.append(['ic-battery-charge-20.svg'])
23  charge_icons.append(['ic-battery-charge-40.svg'])
24  charge_icons.append(['ic-battery-charge-60-green.svg'])
25  charge_icons.append(['ic-battery-charge-80-green.svg'])
26  charge_icons.append(['ic-battery-charge-100-green.svg'])
27  super(TurtlebotBattery, self).__init__(name=name, icons=icons, charge_icons=charge_icons)
28 
29  self._power_consumption = 0.0
30  self._pct = 0.0
31  self._cap = 2.7
32  self._char_cap =2.7
33  self._time_remaining = 0.0
34 
35  def set_power_state(self, msg):
36  last_pct = self._pct
37  last_plugged_in = self._charging
38  last_time_remaining = self._time_remaining
39  self._char_cap = 0.8*self._char_cap +0.2*float(msg['Charge (Ah)'])
40  #make sure that battery percentage is not greater than 100%
41  if self._char_cap < float(msg['Capacity (Ah)']):
42  self._cap = float(msg['Capacity (Ah)'])
43  else:
44  self._cap = self._char_cap
45 
46  self._power_consumption = float(msg['Current (A)'])*float(msg['Voltage (V)'])
47  #determine if we're charging or discharging
48  if float(msg['Current (A)'])<0:
49  tmp = (float(msg['Charge (Ah)'])/non_zero(float(msg['Current (A)'])))*60.0
50  else:
51  tmp = ((float(msg['Charge (Ah)'])-self._cap)/non_zero(float(msg['Current (A)'])))*60.0
52 
53  self._time_remaining = 0.8*self._time_remaining + 0.2*tmp
54 
55  self._pct = float(msg['Charge (Ah)'])/self._cap
56 
57  if self._pct == 1 and float(msg['Current (A)']) == 0:
58  self._charging = True
59  else:
60  self._charging = (float(msg['Current (A)'])>0)
61 
62  self.update_perc(self._pct*100)
63  self.update_time(self._pct*100)
64 
def __init__(self, name='battery')
Definition: battery.py:12
def non_zero(value)
Definition: battery.py:6


create_dashboard
Author(s): Ze'ev Klapow , Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:38:04