dashboard.py
Go to the documentation of this file.
1 import roslib;roslib.load_manifest('create_dashboard')
2 import rospy
3 
4 import diagnostic_msgs
5 import create_node.srv
6 import create_node.msg
7 
8 from rqt_robot_dashboard.dashboard import 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
12 
13 from .battery import TurtlebotBattery
14 
15 import rospkg
16 import os.path
17 
18 rp = rospkg.RosPack()
19 
20 image_path = image_path = os.path.join(rp.get_path('create_dashboard'), 'images')
21 
22 class BreakerButton(IconToolButton):
23  def __init__(self, name, onclick):
24  self._on_icon = ['bg-green.svg', 'ic-breaker.svg']
25  self._off_icon = ['bg-red.svg', 'ic-breaker.svg']
26 
27  icons = [self._off_icon, self._on_icon]
28 
29  super(BreakerButton, self).__init__(name, icons=icons)
30 
31  self.setFixedSize(self._icons[0].actualSize(QSize(50,30)))
32 
33  self.clicked.connect(onclick)
34 
36  def setup(self, context):
37  self.message = None
38 
39  self._dashboard_message = None
41 
42  self._raw_byte = None
43  self.digital_outs = [0,0,0]
44 
45  # These were moved out of get_widgets because they are sometimes not defined
46  # before being used by dashboard_callback. Could be done more cleanly than this
47  # though.
48  self.lap_bat = BatteryDashWidget("Laptop")
49  self.create_bat = TurtlebotBattery("Create")
50  self.breakers = [BreakerButton('breaker0', lambda: self.toggle_breaker(0)),
51  BreakerButton('breaker1', lambda: self.toggle_breaker(1)),
52  BreakerButton('breaker2', lambda: self.toggle_breaker(2))]
53 
54  # This is what gets dashboard_callback going eagerly
55  self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback)
56  self._power_control = rospy.ServiceProxy('turtlebot_node/set_digital_outputs', create_node.srv.SetDigitalOutputs)
57 
58  def get_widgets(self):
59  self.mode = MenuDashWidget('Mode')
60 
61  self.mode.add_action('Full', self.on_full_mode)
62  self.mode.add_action('Passive', self.on_passive_mode)
63  self.mode.add_action('Safe', self.on_safe_mode)
64 
65  return [[MonitorDashWidget(self.context), ConsoleDashWidget(self.context), self.mode],
66  self.breakers,
67  [self.lap_bat, self.create_bat],
68  [NavViewDashWidget(self.context)]]
69 
70  def dashboard_callback(self, msg):
71  self._dashboard_message = msg
72  self._last_dashboard_message_time = rospy.get_time()
73 
74  battery_status = {} # Used to store TurtlebotBattery status info
75  breaker_status = {}
76  laptop_battery_status = {}
77  op_mode = None
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:
82  print value
83  battery_status[value.key]=value.value
84  # Create battery actually doesn't check public or check
85  # charging state. Could maybe done by looking at +-
86  # of current value
87  # Below is kobuki battery code.
88  # Best place to fix this is in create driver to match the kobuki
89  # diagnostics
90  #elif value.key == "Charging State":
91  # if value.value == "Trickle Charging" or value.value == "Full Charging":
92  # self.create_bat.set_charging(True)
93  # else:
94  # self.create_bat.set_charging(False)
95  elif status.name == "/Mode/Operating Mode":
96  op_mode=status.message
97  elif status.name == "/Digital IO/Digital Outputs":
98  #print "got digital IO"
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
104 
105  # If battery diagnostics were found, calculate percentages and stuff
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)
112 
113  if (battery_status):
114  self.create_bat.set_power_state(battery_status)
115 
116  if (breaker_status):
117  self._raw_byte = int(breaker_status['Raw Byte'])
118  self._update_breakers()
119 
120  def toggle_breaker(self, index):
121  try:
122  self.digital_outs[index] = not self.digital_outs[index]
123  power_cmd = create_node.srv.SetDigitalOutputsRequest(self.digital_outs[0], self.digital_outs[1], self.digital_outs[2])
124  #print power_cmd
125  self._power_control(power_cmd)
126 
127  return True
128  except rospy.ServiceException, e:
129  self.message = QMessageBox()
130  self.message.setText("Service call failed with error: %s"%(e))
131  self.message.exec_()
132  return False
133 
134  return False
135 
136  def _update_breakers(self):
137  tmp = self._raw_byte
138  for i in range(0,3):
139  self.digital_outs[i]=tmp%2
140  self.breakers[i].update_state(self.digital_outs[i])
141  tmp = tmp >> 1
142 
143  def on_passive_mode(self):
144  passive = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",create_node.srv.SetTurtlebotMode )
145  try:
146  passive(create_node.msg.TurtlebotSensorState.OI_MODE_PASSIVE)
147  except rospy.ServiceException, e:
148  self.message = QMessageBox()
149  self.message.setText("Failed to put the turtlebot in passive mode: service call failed with error: %s"%(e))
150  self.message.exec_()
151 
152  def on_safe_mode(self):
153  safe = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",create_node.srv.SetTurtlebotMode)
154  try:
155  safe(create_node.msg.TurtlebotSensorState.OI_MODE_SAFE)
156  except rospy.ServiceException, e:
157  self.message = QMessageBox()
158  self.message.setText("Failed to put the turtlebot in safe mode: service call failed with error: %s"%(e))
159  self.message.exec_()
160 
161  def on_full_mode(self):
162  full = rospy.ServiceProxy("/turtlebot_node/set_operation_mode", create_node.srv.SetTurtlebotMode)
163  try:
164  full(create_node.msg.TurtlebotSensorState.OI_MODE_FULL)
165  except rospy.ServiceException, e:
166  self.message = QMessageBox()
167  self.message.setText("Failed to put the turtlebot in full mode: service call failed with error: %s"%(e))
168  self.message.exec_()
def __init__(self, name, onclick)
Definition: dashboard.py:23


create_dashboard
Author(s): Ze'ev Klapow , Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:38:04