reaching.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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 roslib.load_manifest( 'trajectory_msgs' )
00009 roslib.load_manifest( 'pr2_controllers_msgs' )
00010 roslib.load_manifest( 'motion_planning_msgs' )
00011 
00012 import rospy
00013 from kinematics_msgs.srv import \
00014     GetPositionIK, GetPositionIKRequest
00015 from geometry_msgs.msg import \
00016     Pose, Point, Quaternion
00017 
00018 from trajectory_msgs.msg import \
00019     JointTrajectory, JointTrajectoryPoint
00020 from pr2_controllers_msgs.msg import \
00021     JointTrajectoryAction, JointTrajectoryGoal
00022 from motion_planning_msgs.srv import \
00023     FilterJointTrajectoryWithConstraints, FilterJointTrajectoryWithConstraintsRequest
00024 
00025 import numpy as np
00026 import dynamics_utils as dynutils
00027 
00028 
00029 class TrajectoryFilter:
00030     
00031     def __init__( self, service_name ):
00032         rospy.loginfo( 'waiting for service: %s'%service_name )
00033         rospy.wait_for_service( service_name )
00034         self.proxy = rospy.ServiceProxy( service_name, FilterJointTrajectoryWithConstraints )
00035 
00036     def filter( self, trajectory ):
00037         # rospy.loginfo( 'filtering trajectory:\n %s'%trajectory )
00038         request = FilterJointTrajectoryWithConstraintsRequest()
00039         request.allowed_time = rospy.Duration.from_sec(5.0);
00040         request.trajectory = trajectory
00041         try:
00042             response = self.proxy( request )
00043             
00044             if response.error_code.val == response.error_code.SUCCESS:
00045                 return response.trajectory
00046             else:
00047                 rospy.logerr( 'Trajectory was not filtered! (error: %s)'%response.error_code.val )
00048                 return None
00049 
00050         except rospy.ServiceException, e:
00051             rospy.logerr( 'service call failed: %s'%e)
00052             return None
00053         
00054 
00055 if __name__== '__main__':
00056     node_name = "reaching_node"
00057     rospy.loginfo( 'register node %s ...'%node_name )
00058     rospy.init_node( node_name )
00059     rospy.loginfo( 'node %s up and running!'%node_name )
00060 
00061     joint_names = dynutils.get_joint_names( 'l_arm_controller' )
00062     ik_service_name = 'pr2_left_arm_kinematics/get_ik'
00063     rospy.loginfo( 'wait for service %s ...'%ik_service_name )
00064     rospy.wait_for_service( ik_service_name )
00065     ik_service = rospy.ServiceProxy( ik_service_name, GetPositionIK )
00066     rospy.loginfo( 'ik service %s is up and running!'%ik_service_name )
00067 
00068     traj_filter = TrajectoryFilter( 'trajectory_filter/filter_trajectory_with_constraints' )
00069 
00070     neutral = [ np.pi / 3, 
00071                  np.pi / 3, 
00072                  0,
00073                  -3 * np.pi/4,
00074                  0, 
00075                  0, 
00076                  0]
00077 
00078     # creating way points in joint space
00079     rospy.loginfo( 'creating trajectory ...' )
00080     req = GetPositionIKRequest()
00081     req.timeout = rospy.Duration(5.0)
00082     req.ik_request.ik_link_name = "l_wrist_roll_link"
00083     req.ik_request.pose_stamped.header.frame_id = "torso_lift_link"
00084     req.ik_request.ik_seed_state.joint_state.name = joint_names
00085     req.ik_request.ik_seed_state.joint_state.position =  neutral
00086 
00087     joint_positions = []
00088     
00089     center = Pose( position = Point( 0.4, 0.2, 0.0 ), 
00090                    orientation = Quaternion( 0.0, 0.0, 0.0, 1.0 ) )
00091 
00092     home_pose = Pose( position = Point( 0.25, 0.55, 0.0 ), 
00093                    orientation = Quaternion( 0.0, 0.0, 0.0, 1.0 ) )
00094 
00095     req.ik_request.pose_stamped.pose = home_pose
00096     try:
00097         # print "send request :" #, req
00098         res = ik_service( req )
00099         if res.error_code.val == res.error_code.SUCCESS:
00100                 joint_positions = np.asarray( res.solution.joint_state.position )
00101                 req.ik_request.ik_seed_state.joint_state.position = joint_positions
00102         else:
00103             print "IK failed, error code : ", res.error_code.val
00104     except rospy.ServiceException, e:
00105         print "service call failed: %s"%e
00106 
00107     home_joint_positions = joint_positions
00108 
00109     arm = 'l'
00110     l_arm_client = dynutils.init_jt_client( arm )
00111 
00112     n_points = 50;
00113     i = 0;
00114     home = True;
00115 
00116     while i < n_points:
00117 
00118         if not home:
00119 
00120             x = center.position.x + abs(np.random.rand() / 5)
00121             y = center.position.y + np.random.rand() / 2
00122             z = center.position.z + np.random.rand() / 10.0
00123             
00124             pose = Pose( position = Point( x, y, z ),
00125                          orientation = Quaternion( 0.0, 0.0, 0.0, 1.0 ) )
00126             
00127             i = i + 1
00128 
00129             req.ik_request.pose_stamped.pose = pose
00130             # make the call
00131             try:
00132                 # print "send request :" #, req
00133                 res = ik_service( req )
00134                 if res.error_code.val == res.error_code.SUCCESS:
00135                     joint_positions = np.asarray( res.solution.joint_state.position )
00136                     req.ik_request.ik_seed_state.joint_state.position = joint_positions
00137                 else:
00138                     print "IK failed, error code : ", res.error_code.val
00139                     break
00140             except rospy.ServiceException, e:
00141                 print "service call failed: %s"%e
00142                 break
00143             
00144             dynutils.move_arm(joint_positions, time_from_start = 1.0, client = l_arm_client)
00145         else:
00146             dynutils.move_arm(home_joint_positions, time_from_start = 1.0, client = l_arm_client)
00147 
00148         home = not home
00149    
00150     dynutils.move_arm(home_joint_positions, time_from_start = 1.0, client = l_arm_client)     
00151         
00152 
00153     # waypoints = []
00154 
00155     # while len( waypoints ) < n_points:
00156     #     x = center.position.x;
00157     #     y = center.position.y + np.random.rand() / 5.0;
00158     #     z = center.position.z + np.random.rand() / 5.0;
00159 
00160     #     pose = Pose( position = Point( x, y, z ),
00161     #                  orientation = Quaternion( 0.0, 0.0, 0.0, 1.0 ) )
00162     #     req.ik_request.pose_stamped.pose = pose
00163     #     # make the call
00164     #     try:
00165     #         # print "send request :" #, req
00166     #         res = ik_service( req )
00167     #         if res.error_code.val == res.error_code.SUCCESS:
00168     #             joint_positions = np.asarray( res.solution.joint_state.position )
00169     #             waypoints.append( joint_positions )
00170     #             req.ik_request.ik_seed_state.joint_state.position = joint_positions
00171     #         else:
00172     #             print "IK failed, error code : ", res.error_code.val
00173     #             break
00174     #     except rospy.ServiceException, e:
00175     #         print "service call failed: %s"%e
00176     #         break
00177     #     pass
00178 
00179     # tmp_points = np.asarray( waypoints )
00180     # waypoints = []
00181     # for i in range(n_points ):
00182     #     waypoints.append( neutral )
00183     #     waypoints.append( tmp_points[i,:] )
00184     #     waypoints.append( neutral )
00185     # print( waypoints )
00186 
00187     # # creating trajectory
00188     # time = 3.0;
00189     # time_step = 2.0;
00190 
00191     # arm = 'l'
00192     # client = dynutils.init_jt_client( arm )
00193     # joint_names = dynutils.get_joint_names( ''.join( ( arm, '_arm_controller' ) ) )
00194 
00195 
00196     # jt = JointTrajectory()
00197     # jt.joint_names = joint_names
00198     # jt.points = []
00199     
00200     # for i in range( len( waypoints ) ):
00201     #     jp = JointTrajectoryPoint()
00202     #     jp.time_from_start = rospy.Time.from_seconds( time )
00203     #     jp.positions = waypoints[i]
00204     #     jt.points.append( jp )
00205     #     time = time + time_step;
00206 
00207     # print( len( jt.points ) )
00208     # jt.header.stamp = rospy.Time.now()
00209     # # jt = traj_filter.filter( jt )
00210     # print( len( jt.points ) )
00211 
00212 
00213     # # push trajectory goal to ActionServer
00214     # jt_goal = JointTrajectoryGoal()
00215     # jt_goal.trajectory = jt
00216     # jt_goal.trajectory.header.stamp = rospy.Time.now()
00217     # client.send_goal( jt_goal )
00218     # client.wait_for_result()    
00219 
00220 
00221 
00222     
00223 # #    dynutils.save_motion( 'reaching.pkl', 'reaching', t, pos, vel, acc )


kelsey_sandbox
Author(s): kelsey
autogenerated on Wed Nov 27 2013 11:52:04