Go to the documentation of this file.00001 import roslib;roslib.load_manifest('kobuki_dashboard')
00002 import rospy
00003
00004 import diagnostic_msgs
00005
00006 from rqt_robot_dashboard.dashboard import Dashboard
00007 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget, MenuDashWidget, BatteryDashWidget, IconToolButton
00008 from QtGui import QMessageBox, QAction
00009 from python_qt_binding.QtCore import QSize
00010
00011 from .led_widget import LedWidget
00012 from .motor_widget import MotorWidget
00013
00014 class KobukiDashboard(Dashboard):
00015 def setup(self, context):
00016 self.message = None
00017
00018 self._dashboard_message = None
00019 self._last_dashboard_message_time = 0.0
00020
00021 self._motor_widget = MotorWidget('/mobile_base/commands/motor_power')
00022 self._laptop_bat = BatteryDashWidget("Laptop")
00023 self._kobuki_bat = BatteryDashWidget("Kobuki")
00024
00025 self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback)
00026
00027 def get_widgets(self):
00028 leds = [LedWidget('/mobile_base/commands/led1'), LedWidget('/mobile_base/commands/led2')]
00029 return [[MonitorDashWidget(self.context), ConsoleDashWidget(self.context), self._motor_widget], leds, [self._laptop_bat, self._kobuki_bat]]
00030
00031 def dashboard_callback(self, msg):
00032 self._dashboard_message = msg
00033 self._last_dashboard_message_time = rospy.get_time()
00034
00035 laptop_battery_status = {}
00036 for status in msg.status:
00037 if status.name == "/Kobuki/Motor State":
00038 motor_state = int(status.values[0].value)
00039 self._motor_widget.update_state(motor_state)
00040
00041 elif status.name == "/Power System/Battery":
00042 for value in status.values:
00043 if value.key == 'Percent':
00044 self._kobuki_bat.update_perc(float(value.value))
00045
00046
00047 self._kobuki_bat.update_time(float(value.value))
00048 elif value.key == "Charging State":
00049 if value.value == "Trickle Charging" or value.value == "Full Charging":
00050 self._kobuki_bat.set_charging(True)
00051 else:
00052 self._kobuki_bat.set_charging(False)
00053 elif status.name == "/Power System/Laptop Battery":
00054 for value in status.values:
00055 laptop_battery_status[value.key]=value.value
00056
00057 if (laptop_battery_status):
00058 percentage = float(laptop_battery_status['Charge (Ah)'])/float(laptop_battery_status['Capacity (Ah)'])
00059 self._laptop_bat.update_perc(percentage*100)
00060 self._laptop_bat.update_time(percentage*100)
00061 charging_state = True if float(laptop_battery_status['Current (A)']) > 0.0 else False
00062 self._laptop_bat.set_charging(charging_state)
00063
00064 def shutdown_dashboard(self):
00065 self._dashboard_agg_sub.unregister()