Go to the documentation of this file.00001
00002
00003 import roslib
00004 roslib.load_manifest( 'rospy' )
00005 roslib.load_manifest( 'rospy' )
00006 roslib.load_manifest( 'kinematics_msgs' )
00007 roslib.load_manifest( 'geometry_msgs' )
00008
00009 import rospy
00010 from kinematics_msgs.srv import \
00011 GetPositionIK, GetPositionIKRequest
00012 from geometry_msgs.msg import \
00013 Pose, Point, Quaternion
00014
00015
00016
00017 import numpy as np
00018 import dynamics_utils as dynutils
00019
00020 if __name__== '__main__':
00021 node_name = "figure_8"
00022 rospy.loginfo( 'register node %s ...'%node_name )
00023 rospy.init_node( node_name )
00024 rospy.loginfo( 'node %s up and running!'%node_name )
00025
00026 joint_names = dynutils.get_joint_names( 'l_arm_controller' )
00027 ik_service_name = 'pr2_left_arm_kinematics/get_ik'
00028 rospy.loginfo( 'wait for service %s ...'%ik_service_name )
00029 rospy.wait_for_service( ik_service_name )
00030 ik_service = rospy.ServiceProxy( ik_service_name, GetPositionIK )
00031 rospy.loginfo( 'ik service %s is up and running!'%ik_service_name )
00032
00033
00034 time = 10.0;
00035 n = int(time * 200)
00036 dt = time / n;
00037 alphas = np.linspace( 0, 2 * np.pi, n + 1 )
00038 alphas = alphas[0:-1]
00039 ys = np.cos( alphas ) * 0.4
00040 zs = -np.sin( 2 * alphas ) * 0.2
00041
00042
00043 rospy.loginfo( 'creating trajectory ...' )
00044 trajectory = []
00045 req = GetPositionIKRequest()
00046 req.timeout = rospy.Duration(5.0)
00047 req.ik_request.ik_link_name = "l_wrist_roll_link"
00048 req.ik_request.pose_stamped.header.frame_id = "torso_lift_link"
00049 req.ik_request.ik_seed_state.joint_state.name = joint_names
00050 req.ik_request.ik_seed_state.joint_state.position = [0.61309537, 0.45494851, 0.03, -1.03480809, 2.23232079, -0.79696399, -2.44271129]
00051 joint_positions = []
00052
00053 for (y, z) in zip( ys, zs ):
00054 pose = Pose( position = Point( 0.6, 0.20 + y, 0.0 + z ),
00055 orientation = Quaternion( 0.0, 0.0, 0.0, 1.0 ) )
00056 req.ik_request.pose_stamped.pose = pose
00057
00058
00059 try:
00060
00061 res = ik_service( req )
00062
00063 if res.error_code.val == res.error_code.SUCCESS:
00064 joint_positions = np.asarray( res.solution.joint_state.position )
00065 else:
00066 print "IK failed, error code : ", res.error_code.val
00067 break
00068 except rospy.ServiceException, e:
00069 print "service call failed: %s"%e
00070 break
00071
00072 trajectory.append( joint_positions )
00073 req.ik_request.ik_seed_state.joint_state.position = joint_positions
00074
00075 rospy.loginfo( 'done!' )
00076
00077 t = np.cumsum( [dt] * n ) - dt
00078 pos = np.asarray( trajectory )
00079 dynutils.wrap_trajectory( pos )
00080
00081 vel = dynutils.compute_derivative( pos, dt )
00082 acc = dynutils.compute_derivative( vel, dt )
00083
00084 dynutils.save_motion( 'figure8.pkl', 'figure8', t, pos, vel, acc )