pr2_battery.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import rospy
34 
35 from python_qt_binding.QtCore import QSize
36 from rqt_robot_dashboard.widgets import BatteryDashWidget
37 
38 
39 class PR2Battery(BatteryDashWidget):
40  """
41  Dashboard widget to display PR2 battery state.
42  """
43  #TODO When nonbutton Dashboard objects are available rebase this widget
44  def __init__(self, context):
45  """
46  :param context: the plugin context
47  :type context: qt_gui.plugin.Plugin
48  """
49  # Use green icons above 60 percent
50  icons = []
51  charge_icons = []
52  icons.append(['ic-battery-0.svg'])
53  icons.append(['ic-battery-20.svg'])
54  icons.append(['ic-battery-40.svg'])
55  icons.append(['ic-battery-60-green.svg'])
56  icons.append(['ic-battery-80-green.svg'])
57  icons.append(['ic-battery-100-green.svg'])
58  charge_icons.append(['ic-battery-charge-0.svg'])
59  charge_icons.append(['ic-battery-charge-20.svg'])
60  charge_icons.append(['ic-battery-charge-40.svg'])
61  charge_icons.append(['ic-battery-charge-60-green.svg'])
62  charge_icons.append(['ic-battery-charge-80-green.svg'])
63  charge_icons.append(['ic-battery-charge-100-green.svg'])
64  super(PR2Battery, self).__init__('PR2 Battery', icons=icons, charge_icons=charge_icons)
65 
66  self._power_consumption = 0.0
67  self._pct = 0
68  self._time_remaining = rospy.rostime.Duration(0)
69  self._ac_present = 0
70  # use inherited function instead of accessing variable
71  self.set_charging(False)
72 
73  # use default size and set margin to 0 to display the full battery symbol
74  self.setFixedSize(self._icons[1].actualSize(QSize(60, 100)))
75  self.setMargin(0)
76 
77  self.update_perc(0)
78 
79  def set_power_state(self, msg):
80  """
81  Sets button state based on msg
82 
83  :param msg: message containing the power state of the PR2
84  :type msg: pr2_msgs.PowerState
85  """
86  # unset stale status, else the battery will stick to the stale loop, the unset_stale function is never called elsewhere
87  self.unset_stale()
88  last_pct = self._pct
89  # self._plugged in has been changed to self._charging
90  last_charging = self._charging
91  last_time_remaining = self._time_remaining
92 
93  self._power_consumption = msg.power_consumption
94  self._time_remaining = msg.time_remaining
95  self._pct = msg.relative_capacity / 100.0
96  # use inherited function instead of accessing variable
97  self.set_charging(msg.AC_present)
98  if (last_pct != self._pct or last_charging != self._charging or last_time_remaining != self._time_remaining):
99  drain_str = "remaining"
100  if (self._charging):
101  drain_str = "to full charge"
102  # use battery name varibale
103  self.setToolTip("%s: %.2f%% \nTime %s: %d Minutes" % (self._name, self._pct * 100.0, drain_str, self._time_remaining.to_sec() / 60.0))
104  self.update_perc(msg.relative_capacity)
105 
106  def set_stale(self):
107  # use super function of set_stale instead of copy/paste
108  super(PR2Battery, self).set_stale()
109  self._time_remaining = rospy.rostime.Duration(0)
110  self._power_consumption = 0


rqt_pr2_dashboard
Author(s): Aaron Blasdel
autogenerated on Fri Dec 11 2020 03:39:03