cob_battery.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import rospy
19 
20 from python_qt_binding.QtCore import QSize
21 from rqt_robot_dashboard.widgets import BatteryDashWidget
22 
23 
24 class COBBattery(BatteryDashWidget):
25  """
26  Dashboard widget to display COB battery state.
27  """
28  #TODO When nonbutton Dashboard objects are available rebase this widget
29  def __init__(self, context):
30  """
31  :param context: the plugin context
32  :type context: qt_gui.plugin.Plugin
33  """
34  super(COBBattery, self).__init__('COB Battery')
35  self._time_remaining = 0.0
36  self._charging = False
37 
38  self.setFixedSize(self._icons[1].actualSize(QSize(50, 30)))
39 
40  self.update_perc(0)
41 
42  def set_power_state(self, msg):
43  """
44  Sets button state based on msg
45 
46  :param msg: message containing the power state of the COB
47  :type msg: cob_msgs.PowerState
48  """
49  last_charging = self._charging
50  last_time_remaining = self._time_remaining
51 
52  self._time_remaining = msg.time_remaining
53  self._charging = msg.charging
54  if (last_charging != self._charging or last_time_remaining != self._time_remaining):
55  drain_str = "remaining"
56  if (self._charging):
57  drain_str = "to full charge"
58  self.charging = True
59  self.setToolTip("Battery: %.2f%% \nTime %s: %.2f Minutes" % (msg.relative_remaining_capacity, drain_str, self._time_remaining * 60.0))
60  self.update_perc(msg.relative_remaining_capacity)
61 
62  def set_stale(self):
63  self._charging = 0
64  self._time_remaining = rospy.rostime.Duration(0)
65  self.setToolTip("Battery: Stale")


cob_dashboard
Author(s): Alexander Bubeck
autogenerated on Wed Apr 7 2021 03:03:02