1 import roslib;roslib.load_manifest(
'create_dashboard')
9 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget, MenuDashWidget, BatteryDashWidget, IconToolButton, NavViewDashWidget
10 from QtGui
import QMessageBox, QAction
11 from python_qt_binding.QtCore
import QSize
13 from .battery
import TurtlebotBattery
20 image_path = image_path = os.path.join(rp.get_path(
'create_dashboard'),
'images')
24 self.
_on_icon = [
'bg-green.svg',
'ic-breaker.svg']
29 super(BreakerButton, self).
__init__(name, icons=icons)
31 self.setFixedSize(self._icons[0].actualSize(QSize(50,30)))
33 self.clicked.connect(onclick)
48 self.
lap_bat = BatteryDashWidget(
"Laptop")
56 self.
_power_control = rospy.ServiceProxy(
'turtlebot_node/set_digital_outputs', create_node.srv.SetDigitalOutputs)
59 self.
mode = MenuDashWidget(
'Mode')
68 [NavViewDashWidget(self.
context)]]
76 laptop_battery_status = {}
78 for status
in msg.status:
79 print(
"Status callback %s"%status.name)
80 if status.name ==
"/Power System/Battery":
81 for value
in status.values:
83 battery_status[value.key]=value.value
95 elif status.name ==
"/Mode/Operating Mode":
96 op_mode=status.message
97 elif status.name ==
"/Digital IO/Digital Outputs":
99 for value
in status.values:
100 breaker_status[value.key]=value.value
101 elif status.name ==
"/Power System/Laptop Battery":
102 for value
in status.values:
103 laptop_battery_status[value.key]=value.value
106 if (laptop_battery_status):
107 percentage = float(laptop_battery_status[
'Charge (Ah)'])/float(laptop_battery_status[
'Capacity (Ah)'])
108 self.lap_bat.update_perc(percentage*100)
109 self.lap_bat.update_time(percentage*100)
110 charging_state =
True if float(laptop_battery_status[
'Current (A)']) > 0.0
else False 111 self.lap_bat.set_charging(charging_state)
114 self.create_bat.set_power_state(battery_status)
117 self.
_raw_byte = int(breaker_status[
'Raw Byte'])
128 except rospy.ServiceException, e:
130 self.message.setText(
"Service call failed with error: %s"%(e))
144 passive = rospy.ServiceProxy(
"/turtlebot_node/set_operation_mode",create_node.srv.SetTurtlebotMode )
146 passive(create_node.msg.TurtlebotSensorState.OI_MODE_PASSIVE)
147 except rospy.ServiceException, e:
149 self.message.setText(
"Failed to put the turtlebot in passive mode: service call failed with error: %s"%(e))
153 safe = rospy.ServiceProxy(
"/turtlebot_node/set_operation_mode",create_node.srv.SetTurtlebotMode)
155 safe(create_node.msg.TurtlebotSensorState.OI_MODE_SAFE)
156 except rospy.ServiceException, e:
158 self.message.setText(
"Failed to put the turtlebot in safe mode: service call failed with error: %s"%(e))
162 full = rospy.ServiceProxy(
"/turtlebot_node/set_operation_mode", create_node.srv.SetTurtlebotMode)
164 full(create_node.msg.TurtlebotSensorState.OI_MODE_FULL)
165 except rospy.ServiceException, e:
167 self.message.setText(
"Failed to put the turtlebot in full mode: service call failed with error: %s"%(e))
def dashboard_callback(self, msg)
def toggle_breaker(self, index)
_last_dashboard_message_time
def _update_breakers(self)
def on_passive_mode(self)