test_grasp.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright 2014 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 
18 import unittest
19 import rospy
20 import rostest
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
25 
26 PKG = 'sr_grasp'
27 NAME = 'test_grasp_object'
28 
29 
30 class TestGrasp(unittest.TestCase):
31  longMessage = True
32 
33  joint_names = [
34  'LFJ0', 'LFJ3', 'LFJ4', 'LFJ5',
35  'RFJ0', 'RFJ3', 'RFJ4',
36  'MFJ0', 'MFJ3', 'MFJ4',
37  'FFJ0', 'FFJ3', 'FFJ4',
38  'THJ1', 'THJ2', 'THJ3', 'THJ4', 'THJ5',
39  'WRJ1', 'WRJ2']
40 
41  def mk_grasp(self, joints):
42  grasp = Grasp()
43  # pre-grasp (just zero all for now)
44  grasp.pre_grasp_posture.joint_names = self.joint_names
45  jtp = JointTrajectoryPoint()
46  for jname in self.joint_names:
47  jtp.positions.append(0.0)
48  grasp.pre_grasp_posture.points.append(jtp)
49  # grasp
50  grasp.grasp_posture.joint_names = self.joint_names
51  jtp = JointTrajectoryPoint()
52  for jname in self.joint_names:
53  if jname in joints:
54  jtp.positions.append(joints[jname])
55  else:
56  jtp.positions.append(0.0)
57  grasp.grasp_posture.points.append(jtp)
58  return grasp
59 
60  # Tests
61  ########
62 
63  def test_grasp_action(self):
64  """Test sending a grasp."""
65  goal = GraspGoal()
66  goal.grasp = self.mk_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,
69  })
70 
71  # Get a action client
72  client = SimpleActionClient('grasp', GraspAction)
73  client.wait_for_server()
74 
75  # Send pre-grasp
76  goal.pre_grasp = True
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.")
81 
82  rospy.sleep(2)
83 
84  # Send grasp
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.")
90 
91 
92 if __name__ == '__main__':
93  rospy.init_node(NAME)
94  rostest.rosrun(PKG, NAME, TestGrasp)
def mk_grasp(self, joints)
Definition: test_grasp.py:41
def test_grasp_action(self)
Definition: test_grasp.py:63


sr_grasp
Author(s): Mark Pitchless
autogenerated on Wed Oct 14 2020 04:05:13