Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 import roslib
00039 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00040
00041 from naoqi_bridge_msgs.msg import BodyPoseAction, BodyPoseGoal
00042 import actionlib
00043
00044 import rospy
00045 from rosgraph import rosenv
00046
00047 from .status_control import StatusControl
00048 from .power_state_control import PowerStateControl
00049 from .motors import Motors
00050 from .avahi import AvahiWidget
00051 from .posture import PostureWidget
00052
00053 from rqt_robot_dashboard.dashboard import Dashboard
00054 from rqt_robot_dashboard.monitor_dash_widget import MonitorDashWidget
00055 from rqt_robot_dashboard.console_dash_widget import ConsoleDashWidget
00056
00057 from PyQt4 import QtGui, QtCore
00058
00059 class NAOqiDashboard(Dashboard):
00060
00061 def setup(self, context):
00062 self.name = 'NAOqi Dashboard (%s)'%rosenv.get_master_uri()
00063
00064 self._robot_combobox = AvahiWidget()
00065
00066
00067 self._monitor = MonitorDashWidget(self.context)
00068
00069
00070 self._console = ConsoleDashWidget(self.context, minimal=False)
00071
00072
00073 self._temp_joint_button = StatusControl('Joint temperature', 'temperature_joints')
00074
00075
00076 self._temp_head_button = StatusControl('CPU temperature', 'temperature_head')
00077
00078
00079 self._motors_button = Motors(self.context)
00080
00081
00082 self._postures = PostureWidget()
00083
00084
00085 self.posture_combobox = QtGui.QComboBox()
00086 self.posture_combobox.addItem("Crouch")
00087 self.posture_combobox.addItem("Stand")
00088 self.posture_combobox.addItem("Stand Init")
00089 self.posture_combobox.addItem("Stand Zero")
00090 self.posture_combobox.addItem("Lying Back")
00091 self.posture_combobox.addItem("Lying Belly")
00092 self.posture_combobox.addItem("Sit")
00093 self.posture_combobox.addItem("Sit on chair")
00094 self.posture_combobox.addItem("Sit relax")
00095 self.posture_button = QtGui.QPushButton("Go!")
00096 self.posture_button.clicked.connect(self.handle_posture)
00097
00098
00099 self._power_state_ctrl = PowerStateControl('Battery')
00100
00101 self._agg_sub = rospy.Subscriber('/diagnostics_agg', DiagnosticArray, self.new_diagnostic_message)
00102
00103 def get_widgets(self):
00104 return [ [self._robot_combobox],
00105 [self._monitor, self._console, self._temp_joint_button, self._temp_head_button,
00106 self._motors_button],
00107 [self._power_state_ctrl],
00108
00109 [QtGui.QLabel("Posture"), self._postures]
00110 ]
00111
00112
00113 def handle_posture(self):
00114 print "handle posture"
00115
00116
00117 def shutdown_dashboard(self):
00118 self._agg_sub.unregister()
00119
00120 def new_diagnostic_message(self, msg):
00121 """
00122 callback to process dashboard_agg messages
00123
00124 :param msg: dashboard_agg DashboardState message
00125 :type msg: pr2_msgs.msg.DashboardState
00126 """
00127 self._dashboard_message = msg
00128 highest_level = DiagnosticStatus.OK
00129 highest_message = 'All OK'
00130 for status in msg.status:
00131 for black in ['/Joystick']:
00132 if status.name.startswith(black):
00133 continue
00134 if status.level > highest_level:
00135 highest_level = status.level
00136 highest_message = status.message
00137 if status.name == '/NAOqi/Joints/Status':
00138 highestTemp = ""
00139 lowestStiff = -1.0
00140 highestStiff = -1.0
00141 hotJoints = ""
00142 for kv in status.values:
00143 if kv.key == 'Highest Temperature':
00144 highestTemp = kv.value
00145 elif kv.key == 'Highest Stiffness':
00146 highestStiff = float(kv.value)
00147 elif kv.key == 'Lowest Stiffness without Hands':
00148 lowestStiff = float(kv.value)
00149 elif kv.key == 'Hot Joints':
00150 hotJoints = str(kv.value)
00151 self.set_buttonStatus(self._temp_joint_button, status, "Joints ", " (%s deg C %s)"%(highestTemp, hotJoints))
00152
00153 if(lowestStiff < 0.0 or highestStiff < 0.0):
00154 self._motors_button.set_stale()
00155 elif(lowestStiff > 0.9):
00156 self._motors_button.set_error()
00157 elif(highestStiff < 0.05):
00158 self._motors_button.set_ok()
00159 else:
00160 self._motors_button.set_warn()
00161 self.set_buttonStatus(self._motors_button, status, "Stiffness ", " (low: %f / high: %f)"%(lowestStiff, highestStiff))
00162 elif status.name == '/NAOqi/Computer/CPU':
00163 for kv in status.values:
00164 if kv.key == "Temperature":
00165 self.set_buttonStatus(self._temp_head_button, status, "CPU temperature ", "(%s C)" % kv.value)
00166 elif status.name == '/NAOqi/Power System/Status':
00167 if status.level == 3:
00168 self._power_state_ctrl.set_stale()
00169 else:
00170 self._power_state_ctrl.set_power_state(status.values)
00171
00172 if len(msg.status):
00173 class Status(object):
00174 pass
00175
00176 status = Status()
00177 status.level = highest_level
00178 self.set_buttonStatus(self._monitor, status, '', ' %s' % highest_message)
00179
00180 def set_buttonStatus(self, button, status, statusPrefix = "", statusSuffix = ""):
00181 statusString = "Unknown"
00182 if status.level == DiagnosticStatus.OK:
00183 button.update_state(0)
00184 statusString = "OK"
00185 elif status.level == DiagnosticStatus.WARN:
00186 button.update_state(1)
00187 statusString = "Warn"
00188 elif status.level == DiagnosticStatus.ERROR:
00189 button.update_state(2)
00190 statusString = "Error"
00191 elif status.level == 3:
00192 button.update_state(3)
00193 statusString = "Stale"
00194 button.setToolTip(statusPrefix + statusString + statusSuffix)
00195
00196 def save_settings(self, plugin_settings, instance_settings):
00197 self._console.save_settings(plugin_settings, instance_settings)
00198 self._monitor.save_settings(plugin_settings, instance_settings)
00199
00200 def restore_settings(self, plugin_settings, instance_settings):
00201 self._console.restore_settings(plugin_settings, instance_settings)
00202 self._monitor.restore_settings(plugin_settings, instance_settings)