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