dashboard.py
Go to the documentation of this file.
1 import roslib;roslib.load_manifest('kobuki_dashboard')
2 import rospy
3 
4 import diagnostic_msgs
5 
6 from rqt_robot_dashboard.dashboard import Dashboard
7 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget, MenuDashWidget, IconToolButton
8 from QtWidgets import QMessageBox, QAction
9 from python_qt_binding.QtCore import QSize
10 
11 from .battery_widget import BatteryWidget
12 from .led_widget import LedWidget
13 from .motor_widget import MotorWidget
14 
16  def setup(self, context):
17  self.message = None
18 
19  self._dashboard_message = None
21 
22  self._motor_widget = MotorWidget('/mobile_base/commands/motor_power')
23  self._laptop_bat = BatteryWidget("Laptop")
24  self._kobuki_bat = BatteryWidget("Kobuki")
25 
26  self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback)
27 
28  def get_widgets(self):
29  leds = [LedWidget('/mobile_base/commands/led1'), LedWidget('/mobile_base/commands/led2')]
30  return [[MonitorDashWidget(self.context), ConsoleDashWidget(self.context), self._motor_widget], leds, [self._laptop_bat, self._kobuki_bat]]
31 
32  def dashboard_callback(self, msg):
33  self._dashboard_message = msg
34  self._last_dashboard_message_time = rospy.get_time()
35 
36  laptop_battery_status = {}
37  for status in msg.status:
38  if status.name == "/Kobuki/Motor State":
39  motor_state = int(status.values[0].value)
40  self._motor_widget.update_state(motor_state)
41 
42  elif status.name == "/Power System/Battery":
43  for value in status.values:
44  if value.key == 'Percent':
45  self._kobuki_bat.update_perc(float(value.value))
46  # This should be self._last_dashboard_message_time?
47  # Is it even used graphically by the widget
48  self._kobuki_bat.update_time(float(value.value))
49  elif value.key == "Charging State":
50  if value.value == "Trickle Charging" or value.value == "Full Charging":
51  self._kobuki_bat.set_charging(True)
52  else:
53  self._kobuki_bat.set_charging(False)
54  elif status.name == "/Power System/Laptop Battery":
55  for value in status.values:
56  laptop_battery_status[value.key]=value.value
57 
58  if (laptop_battery_status):
59  percentage = float(laptop_battery_status['Charge (Ah)'])/float(laptop_battery_status['Capacity (Ah)'])
60  self._laptop_bat.update_perc(percentage*100)
61  self._laptop_bat.update_time(percentage*100)
62  charging_state = True if float(laptop_battery_status['Current (A)']) > 0.0 else False
63  self._laptop_bat.set_charging(charging_state)
64 
65  def shutdown_dashboard(self):
66  self._dashboard_agg_sub.unregister()


kobuki_dashboard
Author(s): Ze'ev Klapow, Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:52:52