pose_action_client.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import roslib; roslib.load_manifest('jaco_driver')
00004 import rospy
00005 
00006 import actionlib
00007 
00008 import jaco_driver.msg
00009 
00010 import sys
00011 
00012 
00013 def pose_client():
00014     client = actionlib.SimpleActionClient('/jaco/arm_pose', jaco_driver.msg.ArmPoseAction)
00015 
00016     goal = jaco_driver.msg.ArmPoseGoal()
00017 
00018     goal.pose.header.frame_id = "/jaco_api_origin"
00019     pose = goal.pose.pose
00020 
00021     if len(sys.argv) < 8: # default pose
00022         pose.position.x = -0.314269423485
00023         pose.position.y = -0.339179039001
00024         pose.position.z = 0.600132465363
00025 
00026         pose.orientation.x = -0.590686044496
00027         pose.orientation.y = -0.519369415388
00028         pose.orientation.z = 0.324703360925
00029         pose.orientation.w = 0.525274342226
00030 
00031         rospy.logwarn("Using test goal: \n%s", goal)
00032     else: # use pose from command line
00033         pose.position.x = float(sys.argv[1])
00034         pose.position.y = float(sys.argv[2])
00035         pose.position.z = float(sys.argv[3])
00036 
00037         pose.orientation.x = float(sys.argv[4])
00038         pose.orientation.y = float(sys.argv[5])
00039         pose.orientation.z = float(sys.argv[6])
00040         pose.orientation.w = float(sys.argv[7])
00041 
00042     client.wait_for_server()
00043     rospy.loginfo("Connected to Pose server")
00044 
00045     client.send_goal(goal)
00046 
00047     try:
00048         client.wait_for_result()
00049     except KeyboardInterrupt:
00050         rospy.loginfo("Program interrupted, pre-empting goal")
00051         client.cancel_all_goals()
00052 
00053     return client.get_result()
00054 
00055 if __name__ == '__main__':
00056     try:
00057         rospy.init_node('arm_pose_client')
00058         result = pose_client()
00059         rospy.loginfo("Result: %s", result)
00060     except rospy.ROSInterruptException: 
00061         rospy.loginfo("Program interrupted before completion")
00062         


jaco_driver
Author(s): Jeff Schmidt (Clearpath), Alex Bencz (Clearpath), Matt DeDonato (WPI)
autogenerated on Mon Jan 6 2014 11:23:43