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 import rospy
00019 import actionlib
00020
00021 from cob_cartesian_controller.msg import CartesianControllerAction, CartesianControllerGoal
00022 from cob_cartesian_controller.msg import Profile
00023
00024 if __name__ == '__main__':
00025 rospy.init_node('test_move_lin')
00026 action_name = rospy.get_namespace()+'cartesian_trajectory_action'
00027 client = actionlib.SimpleActionClient(action_name, CartesianControllerAction)
00028 rospy.logwarn("Waiting for ActionServer: %s", action_name)
00029 client.wait_for_server()
00030 rospy.logwarn("...done")
00031
00032
00033 goal = CartesianControllerGoal()
00034
00035 goal.move_type = CartesianControllerGoal.LIN
00036 goal.move_lin.pose_goal.position.x = -0.9
00037 goal.move_lin.pose_goal.position.y = 0.0
00038 goal.move_lin.pose_goal.position.z = 0.0
00039 goal.move_lin.pose_goal.orientation.x = 0.0
00040 goal.move_lin.pose_goal.orientation.y = 0.0
00041 goal.move_lin.pose_goal.orientation.z = 0.0
00042 goal.move_lin.pose_goal.orientation.w = 1.0
00043 goal.move_lin.frame_id = 'world'
00044
00045 goal.profile.vel = 0.2
00046 goal.profile.accl = 0.1
00047 goal.profile.profile_type = Profile.SINOID
00048
00049
00050
00051
00052 client.send_goal(goal)
00053 client.wait_for_result()