Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('jaco_driver')
00004 import rospy
00005
00006 import actionlib
00007
00008 import jaco_msgs.msg
00009
00010 import sys
00011
00012
00013 def pose_client():
00014 client = actionlib.SimpleActionClient('/jaco/arm_joint_angles', jaco_msgs.msg.ArmJointAnglesAction)
00015
00016 goal = jaco_msgs.msg.ArmJointAnglesGoal()
00017
00018 if len(sys.argv) < 7:
00019 goal.angles.joint1 = 1.5285271406173706
00020 goal.angles.joint2 = -1.3800612688064575
00021 goal.angles.joint3 = -0.1439174860715866
00022 goal.angles.joint4 = 0.15510250627994537
00023 goal.angles.joint5 = 0.6960597634315491
00024 goal.angles.joint6 = 3.3098342418670654
00025
00026 rospy.logwarn("Using test goal: \n%s", goal)
00027 else:
00028 goal.angles.joint1 = float(sys.argv[1])
00029 goal.angles.joint2 = float(sys.argv[2])
00030 goal.angles.joint3 = float(sys.argv[3])
00031 goal.angles.joint4 = float(sys.argv[4])
00032 goal.angles.joint5 = float(sys.argv[5])
00033 goal.angles.joint6 = float(sys.argv[6])
00034
00035
00036 client.wait_for_server()
00037 rospy.loginfo("Connected to Pose server")
00038
00039 client.send_goal(goal)
00040
00041 try:
00042 client.wait_for_result()
00043 except KeyboardInterrupt:
00044 rospy.loginfo("Program interrupted, pre-empting goal")
00045 client.cancel_all_goals()
00046
00047 return client.get_result()
00048
00049 if __name__ == '__main__':
00050 try:
00051 rospy.init_node('arm_pose_client')
00052 result = pose_client()
00053 rospy.loginfo("Result: %s", result)
00054 except rospy.ROSInterruptException:
00055 rospy.loginfo("Program interrupted before completion")
00056