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 icons = []
00014 charge_icons = []
00015 icons.append(['ic-battery-0.svg'])
00016 icons.append(['ic-battery-20.svg'])
00017 icons.append(['ic-battery-40.svg'])
00018 icons.append(['ic-battery-60-green.svg'])
00019 icons.append(['ic-battery-80-green.svg'])
00020 icons.append(['ic-battery-100-green.svg'])
00021 charge_icons.append(['ic-battery-charge-0.svg'])
00022 charge_icons.append(['ic-battery-charge-20.svg'])
00023 charge_icons.append(['ic-battery-charge-40.svg'])
00024 charge_icons.append(['ic-battery-charge-60-green.svg'])
00025 charge_icons.append(['ic-battery-charge-80-green.svg'])
00026 charge_icons.append(['ic-battery-charge-100-green.svg'])
00027 super(TurtlebotBattery, self).__init__(name=name, icons=icons, charge_icons=charge_icons)
00028
00029 self._power_consumption = 0.0
00030 self._pct = 0.0
00031 self._cap = 2.7
00032 self._char_cap =2.7
00033 self._time_remaining = 0.0
00034
00035 def set_power_state(self, msg):
00036 last_pct = self._pct
00037 last_plugged_in = self._charging
00038 last_time_remaining = self._time_remaining
00039 self._char_cap = 0.8*self._char_cap +0.2*float(msg['Charge (Ah)'])
00040
00041 if self._char_cap < float(msg['Capacity (Ah)']):
00042 self._cap = float(msg['Capacity (Ah)'])
00043 else:
00044 self._cap = self._char_cap
00045
00046 self._power_consumption = float(msg['Current (A)'])*float(msg['Voltage (V)'])
00047
00048 if float(msg['Current (A)'])<0:
00049 tmp = (float(msg['Charge (Ah)'])/non_zero(float(msg['Current (A)'])))*60.0
00050 else:
00051 tmp = ((float(msg['Charge (Ah)'])-self._cap)/non_zero(float(msg['Current (A)'])))*60.0
00052
00053 self._time_remaining = 0.8*self._time_remaining + 0.2*tmp
00054
00055 self._pct = float(msg['Charge (Ah)'])/self._cap
00056
00057 if self._pct == 1 and float(msg['Current (A)']) == 0:
00058 self._charging = True
00059 else:
00060 self._charging = (float(msg['Current (A)'])>0)
00061
00062 self.update_perc(self._pct*100)
00063 self.update_time(self._pct*100)
00064