$search
00001 #!/usr/bin/env python 00002 00003 import roslib 00004 #from rospy.exceptions import ROSException 00005 roslib.load_manifest('nao_driver') 00006 import rospy 00007 import roslib.rostime 00008 from roslib.rostime import Duration 00009 00010 00011 import actionlib 00012 import nao_msgs.msg 00013 import trajectory_msgs.msg 00014 from trajectory_msgs.msg import JointTrajectoryPoint 00015 import std_srvs.srv 00016 00017 # go to crouching position 00018 def joint_angle_client(): 00019 #inhibitWalkSrv = rospy.ServiceProxy("inhibit_walk", std_srvs.srv.Empty) 00020 #uninhibitWalkSrv = rospy.ServiceProxy("uninhibit_walk", std_srvs.srv.Empty) 00021 00022 client = actionlib.SimpleActionClient("joint_trajectory", nao_msgs.msg.JointTrajectoryAction) 00023 stiffness_client = actionlib.SimpleActionClient("joint_stiffness_trajectory", nao_msgs.msg.JointTrajectoryAction) 00024 angle_client = actionlib.SimpleActionClient("joint_angles_action", nao_msgs.msg.JointAnglesWithSpeedAction) 00025 00026 rospy.loginfo("Waiting for joint_trajectory and joint_stiffness servers...") 00027 client.wait_for_server() 00028 stiffness_client.wait_for_server() 00029 angle_client.wait_for_server() 00030 rospy.loginfo("Done.") 00031 00032 #inhibitWalkSrv() 00033 try: 00034 goal = nao_msgs.msg.JointTrajectoryGoal() 00035 00036 # move head: single joint, multiple keypoints 00037 goal.trajectory.joint_names = ["HeadYaw"] 00038 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.0), positions = [1.0])) 00039 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(2.0), positions = [-1.0])) 00040 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(2.5), positions = [0.0])) 00041 00042 00043 rospy.loginfo("Sending goal...") 00044 client.send_goal(goal) 00045 client.wait_for_result() 00046 result = client.get_result() 00047 rospy.loginfo("Results: %s", str(result.goal_position.position)) 00048 00049 # crouching pose: single keypoint, multiple joints: 00050 goal.trajectory.joint_names = ["Body"] 00051 point = JointTrajectoryPoint() 00052 point.time_from_start = Duration(1.5) 00053 point.positions = [0.0,0.0, # head 00054 1.545, 0.33, -1.57, -0.486, 0.0, 0.0, # left arm 00055 -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # left leg 00056 -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # right leg 00057 1.545, -0.33, 1.57, 0.486, 0.0, 0.0] # right arm 00058 goal.trajectory.points = [point] 00059 00060 rospy.loginfo("Sending goal...") 00061 client.send_goal(goal) 00062 client.wait_for_result() 00063 rospy.loginfo("Getting results...") 00064 result = client.get_result() 00065 print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 00066 00067 00068 # multiple joints, multiple keypoints: 00069 goal.trajectory.joint_names = ["HeadYaw", "HeadPitch"] 00070 goal.trajectory.points = [] 00071 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), 00072 positions = [1.0, 1.0])) 00073 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.0), 00074 positions = [1.0, 0.0])) 00075 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.5), 00076 positions = [0.0, 0.0])) 00077 00078 rospy.loginfo("Sending goal...") 00079 client.send_goal(goal) 00080 client.wait_for_result() 00081 rospy.loginfo("Getting results...") 00082 result = client.get_result() 00083 print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 00084 00085 00086 # multiple joints, single keypoint: 00087 goal.trajectory.joint_names = ["HeadYaw", "HeadPitch"] 00088 goal.trajectory.points = [] 00089 goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), 00090 positions = [0.5, 0.5])) 00091 00092 rospy.loginfo("Sending goal...") 00093 client.send_goal(goal) 00094 client.wait_for_result() 00095 rospy.loginfo("Getting results...") 00096 result = client.get_result() 00097 print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 00098 00099 00100 angle_goal = nao_msgs.msg.JointAnglesWithSpeedGoal() 00101 angle_goal.joint_angles.relative = False 00102 angle_goal.joint_angles.joint_names = ["HeadYaw", "HeadPitch"] 00103 angle_goal.joint_angles.joint_angles = [1.0, 0.0] 00104 angle_goal.joint_angles.speed = 0.2 00105 angle_client.send_goal_and_wait(angle_goal) 00106 result = angle_client.get_result() 00107 rospy.loginfo("Angle results: %s", str(result.goal_position.position)) 00108 00109 stiffness_goal = nao_msgs.msg.JointTrajectoryGoal() 00110 stiffness_goal.trajectory.joint_names = ["Body"] 00111 stiffness_goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), positions = [1.0])) 00112 rospy.loginfo("Sending stiffness goal...") 00113 stiffness_client.send_goal(stiffness_goal) 00114 stiffness_client.wait_for_result() 00115 result = stiffness_client.get_result() 00116 rospy.loginfo("Stiffness results: %s", str(result.goal_position.position)) 00117 00118 finally: 00119 uninhibitWalkSrv() 00120 00121 00122 00123 if __name__ == '__main__': 00124 try: 00125 rospy.init_node('joint_angle_client') 00126 joint_angle_client() 00127 00128 except rospy.ROSInterruptException: 00129 print "program interrupted before completion" 00130