Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import rospy
00034
00035 from python_qt_binding.QtCore import QSize
00036 from rqt_robot_dashboard.widgets import BatteryDashWidget
00037
00038
00039 class COBBattery(BatteryDashWidget):
00040 """
00041 Dashboard widget to display COB battery state.
00042 """
00043
00044 def __init__(self, context):
00045 """
00046 :param context: the plugin context
00047 :type context: qt_gui.plugin.Plugin
00048 """
00049 super(COBBattery, self).__init__('COB Battery')
00050 self._power_consumption = 0.0
00051 self._pct = 0
00052 self._time_remaining = rospy.rostime.Duration(0)
00053 self._ac_present = 0
00054 self._plugged_in = False
00055
00056 self.setFixedSize(self._icons[1].actualSize(QSize(50, 30)))
00057
00058 self.update_perc(0)
00059
00060 def set_power_state(self, msg):
00061 """
00062 Sets button state based on msg
00063
00064 :param msg: message containing the power state of the COB
00065 :type msg: pr2_msgs.PowerState
00066 """
00067 last_pct = self._pct
00068 last_plugged_in = self._plugged_in
00069 last_time_remaining = self._time_remaining
00070
00071 self._power_consumption = msg.power_consumption
00072 self._time_remaining = msg.time_remaining
00073 self._pct = msg.relative_capacity / 100.0
00074 self._plugged_in = msg.AC_present
00075 if (last_pct != self._pct or last_plugged_in != self._plugged_in or last_time_remaining != self._time_remaining):
00076 drain_str = "remaining"
00077 if (self._plugged_in):
00078 drain_str = "to full charge"
00079 self.charging = True
00080 self.setToolTip("Battery: %.2f%% \nTime %s: %d Minutes" % (self._pct * 100.0, drain_str, self._time_remaining.to_sec() / 60.0))
00081 self.update_perc(msg.relative_capacity)
00082
00083 def set_stale(self):
00084 self._plugged_in = 0
00085 self._pct = 0
00086 self._time_remaining = rospy.rostime.Duration(0)
00087 self._power_consumption = 0
00088 self.setToolTip("Battery: Stale")