1 import roslib;roslib.load_manifest(
'kobuki_dashboard')
8 from QtWidgets
import QMessageBox, QAction
9 from python_qt_binding.QtCore
import QSize
11 from .battery_widget
import BatteryWidget
12 from .led_widget
import LedWidget
13 from .motor_widget
import MotorWidget
29 leds = [LedWidget(
'/mobile_base/commands/led1'), LedWidget(
'/mobile_base/commands/led2')]
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)
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))
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)
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
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)
66 self._dashboard_agg_sub.unregister()
_last_dashboard_message_time
def shutdown_dashboard(self)
def dashboard_callback(self, msg)