21 from actionlib
import SimpleActionClient, GoalStatus
22 from sr_robot_msgs.msg
import GraspAction, GraspGoal
23 from moveit_msgs.msg
import Grasp
24 from trajectory_msgs.msg
import JointTrajectoryPoint
27 NAME =
'test_grasp_object' 34 'LFJ0',
'LFJ3',
'LFJ4',
'LFJ5',
35 'RFJ0',
'RFJ3',
'RFJ4',
36 'MFJ0',
'MFJ3',
'MFJ4',
37 'FFJ0',
'FFJ3',
'FFJ4',
38 'THJ1',
'THJ2',
'THJ3',
'THJ4',
'THJ5',
44 grasp.pre_grasp_posture.joint_names = self.
joint_names 45 jtp = JointTrajectoryPoint()
47 jtp.positions.append(0.0)
48 grasp.pre_grasp_posture.points.append(jtp)
51 jtp = JointTrajectoryPoint()
54 jtp.positions.append(joints[jname])
56 jtp.positions.append(0.0)
57 grasp.grasp_posture.points.append(jtp)
64 """Test sending a grasp.""" 67 'LFJ3': 1.4,
'RFJ3': 1.4,
'MFJ3': 1.4,
'FFJ3': 1.4,
68 'LFJ0': 3.0,
'RFJ0': 3.0,
'MFJ0': 3.0,
'FFJ0': 3.0,
73 client.wait_for_server()
77 client.send_goal(goal)
78 client.wait_for_result(rospy.Duration.from_sec(20.0))
79 self.assertEqual(client.get_state(), GoalStatus.SUCCEEDED,
80 "Action did not return in SUCCEEDED state.")
85 goal.pre_grasp =
False 86 client.send_goal(goal)
87 client.wait_for_result(rospy.Duration.from_sec(20.0))
88 self.assertEqual(client.get_state(), GoalStatus.SUCCEEDED,
89 "Action did not return in SUCCEEDED state.")
92 if __name__ ==
'__main__':
94 rostest.rosrun(PKG, NAME, TestGrasp)
def mk_grasp(self, joints)
def test_grasp_action(self)