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 import actionlib
00035 import rospy
00036
00037 from python_qt_binding.QtGui import QComboBox, QMessageBox
00038 from naoqi_bridge_msgs.msg import BodyPoseWithSpeedAction, BodyPoseWithSpeedGoal
00039
00040 class PostureWidget(QComboBox):
00041 def __init__(self):
00042 super(PostureWidget, self).__init__()
00043 self.setSizeAdjustPolicy(QComboBox.AdjustToContents)
00044 self.setInsertPolicy(QComboBox.InsertAlphabetically)
00045 self.setEditable(True)
00046
00047 posture_list = ["---", "Crouch", "LyingBack", "LyingBelly", "Sit", "SitOnChair", "SitRelax", "Stand", "StandInit", "StandZero"]
00048 self.addItems( posture_list )
00049 self.currentIndexChanged.connect( self.apply_posture )
00050
00051 self.bodyPoseClient = actionlib.SimpleActionClient('pose/body_pose_naoqi', BodyPoseWithSpeedAction)
00052
00053 def apply_posture(self):
00054 posture = self.currentText()
00055 rospy.loginfo("go to posture: "+ str(posture))
00056 self.bodyPoseClient.send_goal_and_wait(BodyPoseWithSpeedGoal(posture_name = posture, speed=0.7))
00057 state = self.bodyPoseClient.get_state()
00058 if not state == actionlib.GoalStatus.SUCCEEDED:
00059 QMessageBox(self, 'Error', str(posture)+' posture did not succeed: %s - cannot remove stiffness' % self.bodyPoseClient.get_goal_status_text())
00060 rospy.logerror("crouch pose did not succeed: %s", self.bodyPoseClient.get_goal_status_text())