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 from python_qt_binding.QtGui import QMessageBox
00038
00039 import actionlib
00040 import rospy
00041 from rqt_robot_dashboard.widgets import MenuDashWidget
00042 import std_srvs.srv
00043
00044 from naoqi_bridge_msgs.msg import BodyPoseAction, BodyPoseGoal
00045
00046
00047 class Motors(MenuDashWidget):
00048 """
00049 Dashboard widget to display motor state and allow interaction.
00050 """
00051 def __init__(self, context):
00052 """
00053 :param context: the plugin context
00054 :type context: qt_gui.plugin.Plugin
00055 :param reset_callback: calback for the "reset" action
00056 :type reset_callback: function
00057 :param halt_callback: calback for the "reset" action
00058 :type halt_callback: function
00059 """
00060 ok_icon = ['bg-green.svg', 'ic-motors.svg']
00061 warn_icon = ['bg-yellow.svg', 'ic-motors.svg', 'ol-warn-badge.svg']
00062 err_icon = ['bg-red.svg', 'ic-motors.svg', 'ol-err-badge.svg']
00063 stale_icon = ['bg-grey.svg', 'ic-motors.svg', 'ol-stale-badge.svg']
00064
00065 icons = [ok_icon, warn_icon, err_icon, stale_icon]
00066
00067 super(Motors, self).__init__('Motors', icons)
00068 self.update_state(3)
00069
00070 self.add_action('Init pose', self.on_init_pose)
00071 self.add_action('Sit down && remove stiffness', self.on_sit_down)
00072 self.add_action('Remove stiffness immediately', self.on_remove_stiffness)
00073
00074
00075 self.bodyPoseClient = actionlib.SimpleActionClient('body_pose', BodyPoseAction)
00076 self.stiffnessEnableClient = rospy.ServiceProxy("body_stiffness/enable", std_srvs.srv.Empty)
00077 self.stiffnessDisableClient = rospy.ServiceProxy("body_stiffness/disable", std_srvs.srv.Empty)
00078
00079 def set_ok(self):
00080 self.update_state(0)
00081
00082 def set_warn(self):
00083 self.update_state(1)
00084
00085 def set_error(self):
00086 self.update_state(2)
00087
00088 def set_stale(self):
00089 self.update_state(3)
00090
00091 def on_init_pose(self):
00092 self.stiffnessEnableClient.call()
00093 self.bodyPoseClient.send_goal_and_wait(BodyPoseGoal(pose_name = 'init'))
00094
00095 def on_sit_down(self):
00096 self.bodyPoseClient.send_goal_and_wait(BodyPoseGoal(pose_name = 'crouch'))
00097 state = self.bodyPoseClient.get_state()
00098 if state == actionlib.GoalStatus.SUCCEEDED:
00099 self.stiffnessDisableClient.call()
00100 else:
00101 QMessageBox(self, 'Error', 'crouch pose did not succeed: %s - cannot remove stiffness' % self.bodyPoseClient.get_goal_status_text())
00102 rospy.logerror("crouch pose did not succeed: %s", self.bodyPoseClient.get_goal_status_text())
00103
00104 def on_remove_stiffness(self):
00105 reply = QMessageBox.question(self, 'Caution',
00106 'Robot may fall. Continue to remove stiffness?', QMessageBox.Yes, QMessageBox.No)
00107 if(reply == QMessageBox.Yes):
00108 self.stiffnessDisableClient.call()