ptp_arm_client.py
Go to the documentation of this file.
00001 import roslib; roslib.load_manifest('ptp_arm_action')
00002 import rospy
00003 import actionlib
00004 import ptp_arm_action.msg as ptp
00005 import numpy as np
00006 from object_manipulator.convert_functions import *
00007 import tf.transformations as tr
00008 
00009 rospy.init_node('ptp_client')
00010 client = actionlib.SimpleActionClient('right_ptp', ptp.LinearMovementAction)
00011 client.wait_for_server()
00012 
00013 #Construct goal
00014 goal = ptp.LinearMovementGoal()
00015 goal.relative = True
00016 goal.trans_vel = 0.02
00017 goal.rot_vel = 0.02
00018 motion = tr.identity_matrix()
00019 motion[0,3] = .1
00020 print motion
00021 goal.goal = stamp_pose(mat_to_pose(motion), 'base_link')
00022 print 'goal is\n', goal
00023 client.send_goal(goal)
00024 
00025 client.wait_for_result()
00026 r = client.get_result()
00027 print r
00028 #print r.__class__, r
00029 print 'done!'
00030 #rospy.spin()
00031 
00032 


ptp_arm_action
Author(s): Hai Nguyen
autogenerated on Thu Dec 12 2013 12:09:47