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 from __future__ import with_statement
00034
00035 PKG = 'qualification'
00036
00037 import roslib; roslib.load_manifest(PKG)
00038 import rospy
00039 import actionlib
00040 import threading
00041 import sys
00042
00043 from pr2_controllers_msgs.msg import SingleJointPositionAction, SingleJointPositionGoal
00044 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
00045 from sensor_msgs.msg import JointState
00046
00047 HEIGHT = 0.28
00048 TOLERANCE = 0.10
00049 TORSO_NAME = 'torso_lift_joint'
00050
00051 class LastMessage():
00052 def __init__(self, topic, msg_type):
00053 self.msg = None
00054 rospy.Subscriber(topic, msg_type, self.callback)
00055
00056 def last(self):
00057 return self.msg
00058
00059 def callback(self, msg):
00060 self.msg = msg
00061
00062 def check_torso_up(msg):
00063 for i, name in enumerate(msg.name):
00064 if name == TORSO_NAME:
00065 return abs(msg.position[i] - HEIGHT) < TOLERANCE
00066 return False
00067
00068 if __name__ == '__main__':
00069 rospy.init_node('torso_lifter_client')
00070
00071 rospy.sleep(2)
00072
00073 _mutex = threading.Lock()
00074
00075 last_state = LastMessage('joint_states', JointState)
00076
00077 client = actionlib.SimpleActionClient('torso_controller/position_joint_action',
00078 SingleJointPositionAction)
00079 rospy.loginfo('Waiting for torso action client')
00080 client.wait_for_server()
00081
00082 goal = SingleJointPositionGoal()
00083 goal.position = HEIGHT
00084
00085 client.send_goal(goal)
00086
00087
00088 client.wait_for_result(rospy.Duration.from_sec(60))
00089
00090
00091 ok = False
00092 msg = None
00093 with _mutex:
00094 msg = last_state.last()
00095 if msg:
00096 ok = check_torso_up(msg)
00097
00098
00099
00100 r = TestResultRequest()
00101 if not msg:
00102 r.text_summary = 'No joint state messages receieved. Unable to tell if torso up'
00103 r.result = TestResultRequest.RESULT_FAIL
00104 elif not ok:
00105 r.text_summary = 'Attempted to drive torso up, unable to do so.'
00106 r.result = TestResultRequest.RESULT_FAIL
00107 else:
00108 r.text_summary = 'Drove torso up, OK'
00109 r.result = TestResultRequest.RESULT_PASS
00110
00111 try:
00112 rospy.wait_for_service('test_result', 5)
00113 except:
00114 rospy.logfatal('Unable to contact result service. Exiting')
00115 sys.exit(-1)
00116
00117 result_proxy = rospy.ServiceProxy('test_result', TestResult)
00118 result_proxy.call(r)
00119
00120
00121 rospy.spin()
00122
00123