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 PR2Battery(BatteryDashWidget):
00040 """
00041 Dashboard widget to display PR2 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(PR2Battery, self).__init__('PR2 Battery')
00050
00051 self._power_consumption = 0.0
00052 self._pct = 0
00053 self._time_remaining = rospy.rostime.Duration(0)
00054 self._ac_present = 0
00055 self._plugged_in = False
00056
00057 self.setFixedSize(self._icons[1].actualSize(QSize(50, 30)))
00058
00059 self.update_perc(0)
00060
00061 def set_power_state(self, msg):
00062 """
00063 Sets button state based on msg
00064
00065 :param msg: message containing the power state of the PR2
00066 :type msg: pr2_msgs.PowerState
00067 """
00068 last_pct = self._pct
00069 last_plugged_in = self._plugged_in
00070 last_time_remaining = self._time_remaining
00071
00072 self._power_consumption = msg.power_consumption
00073 self._time_remaining = msg.time_remaining
00074 self._pct = msg.relative_capacity / 100.0
00075 self._plugged_in = msg.AC_present
00076 if (last_pct != self._pct or last_plugged_in != self._plugged_in or last_time_remaining != self._time_remaining):
00077 drain_str = "remaining"
00078 if (self._plugged_in):
00079 drain_str = "to full charge"
00080 self.setToolTip("Battery: %.2f%% \nTime %s: %d Minutes" % (self._pct * 100.0, drain_str, self._time_remaining.to_sec() / 60.0))
00081 self.charging = True
00082 self.update_perc(msg.relative_capacity)
00083
00084 def set_stale(self):
00085 self._plugged_in = 0
00086 self._pct = 0
00087 self._time_remaining = rospy.rostime.Duration(0)
00088 self._power_consumption = 0
00089 self.setToolTip("Battery: Stale")