battery.py
Go to the documentation of this file.
00001 import roslib;roslib.load_manifest('create_dashboard')
00002 import rospy
00003 
00004 from rqt_robot_dashboard.widgets import BatteryDashWidget
00005 
00006 def non_zero(value): 
00007    if value < 0.00001 and value > -0.00001: 
00008       return 0.00001 
00009    return value
00010 
00011 class TurtlebotBattery(BatteryDashWidget):
00012     def __init__(self, name='battery'):
00013         super(TurtlebotBattery, self).__init__(name)
00014 
00015         self._power_consumption = 0.0
00016         self._pct = 0.0
00017         self._cap = 2.7
00018         self._char_cap =2.7
00019         self._time_remaining = 0.0
00020 
00021     def set_power_state(self, msg):
00022         last_pct = self._pct
00023         last_plugged_in = self._charging
00024         last_time_remaining = self._time_remaining
00025         self._char_cap = 0.8*self._char_cap +0.2*float(msg['Charge (Ah)'])
00026         #make sure that battery percentage is not greater than 100%
00027         if self._char_cap < float(msg['Capacity (Ah)']):
00028           self._cap = float(msg['Capacity (Ah)'])
00029         else:
00030           self._cap = self._char_cap
00031     
00032         self._power_consumption = float(msg['Current (A)'])*float(msg['Voltage (V)'])
00033         #determine if we're charging or discharging
00034         if float(msg['Current (A)'])<0:
00035           tmp = (float(msg['Charge (Ah)'])/non_zero(float(msg['Current (A)'])))*60.0
00036         else:
00037           tmp = ((float(msg['Charge (Ah)'])-self._cap)/non_zero(float(msg['Current (A)'])))*60.0
00038     
00039         self._time_remaining = 0.8*self._time_remaining + 0.2*tmp
00040     
00041         self._pct = float(msg['Charge (Ah)'])/self._cap
00042     
00043         if self._pct == 1 and float(msg['Current (A)']) == 0:
00044             self._charging = True
00045         else:
00046             self._charging = (float(msg['Current (A)'])>0)
00047             
00048         self.update_perc(self._pct*100)
00049         self.update_time(self._pct*100)
00050 


create_dashboard
Author(s): Ze'ev Klapow
autogenerated on Mon Oct 6 2014 08:12:16