6 from sr_utilities.arm_finder
import ArmFinder
12 if rospy.has_param(
"arm"):
13 rospy.delete_param(
"arm")
15 if rospy.has_param(
"hand"):
16 rospy.delete_param(
"hand")
18 if rospy.has_param(
"robot_description"):
19 rospy.delete_param(
"robot_description")
21 arm_finder = ArmFinder()
22 self.assertIsNotNone(arm_finder.get_arm_parameters(),
"Parameters extracted.")
23 self.assertIsNotNone(arm_finder.get_arm_joints(),
"Joints extracted.")
25 self.assertEqual(len(arm_finder.get_arm_parameters().mapping), 0,
"It should be zero mapping")
26 self.assertEqual(len(arm_finder.get_arm_parameters().joint_prefix), 0,
"It should be zero joint_prefix")
27 self.assertEqual(len(arm_finder.get_arm_joints().keys()), 0,
"It should be zero arm joints")
30 if rospy.has_param(
"arm"):
31 rospy.delete_param(
"arm")
33 if rospy.has_param(
"hand"):
34 rospy.delete_param(
"hand")
36 if rospy.has_param(
"robot_description"):
37 rospy.delete_param(
"robot_description")
39 arm_finder = ArmFinder()
40 self.assertIsNotNone(arm_finder.get_arm_parameters(),
"Parameters extracted.")
41 self.assertIsNotNone(arm_finder.get_arm_joints(),
"Joints extracted.")
43 self.assertEqual(len(arm_finder.get_arm_parameters().mapping), 0,
"It should be zero mapping")
44 self.assertEqual(len(arm_finder.get_arm_parameters().joint_prefix), 0,
"It should be zero joint_prefix")
45 self.assertEqual(len(arm_finder.get_arm_joints().keys()), 0,
"It should be zero arm joints")
48 if rospy.has_param(
"arm"):
49 rospy.delete_param(
"arm")
51 if rospy.has_param(
"hand"):
52 rospy.delete_param(
"hand")
54 if rospy.has_param(
"robot_description"):
55 rospy.delete_param(
"robot_description")
57 rospy.set_param(
"robot_description", rospy.get_param(
"no_hand_one_arm_description"))
59 rospy.set_param(
"arm/joint_prefix/1",
"la_")
60 rospy.set_param(
"arm/mapping/1",
"la")
62 arm_finder = ArmFinder()
64 self.assertIsNotNone(arm_finder.get_arm_parameters(),
"Parameters extracted.")
65 self.assertIsNotNone(arm_finder.get_arm_joints(),
"Joints extracted.")
67 self.assertEqual(len(arm_finder.get_arm_parameters().mapping), 1,
"It should be one mapping")
68 self.assertEqual(len(arm_finder.get_arm_parameters().joint_prefix), 1,
"It should be one joint_prefix")
69 self.assertEqual(len(arm_finder.get_arm_joints().keys()), 1,
"It should be one arm joints")
71 self.assertIn(
"la", arm_finder.get_arm_parameters().mapping.values(),
"It should be la mapping")
72 self.assertIn(
"la_", arm_finder.get_arm_parameters().joint_prefix.values(),
"It should be la_ prefix")
73 self.assertIn(
"la", arm_finder.get_arm_joints(),
"Maping should be in the joints result")
76 if rospy.has_param(
"arm"):
77 rospy.delete_param(
"arm")
79 if rospy.has_param(
"hand"):
80 rospy.delete_param(
"hand")
82 if rospy.has_param(
"robot_description"):
83 rospy.delete_param(
"robot_description")
85 rospy.set_param(
"robot_description", rospy.get_param(
"right_hand_two_arms"))
87 rospy.set_param(
"hand/joint_prefix/1",
"rh_")
88 rospy.set_param(
"hand/mapping/1",
"rh")
90 rospy.set_param(
"arm/joint_prefix/1",
"la_")
91 rospy.set_param(
"arm/mapping/1",
"la")
93 rospy.set_param(
"arm/joint_prefix/2",
"ra_")
94 rospy.set_param(
"arm/mapping/2",
"ra")
96 arm_finder = ArmFinder()
98 self.assertIsNotNone(arm_finder.get_arm_parameters(),
"Parameters extracted.")
99 self.assertIsNotNone(arm_finder.get_arm_joints(),
"Joints extracted.")
101 self.assertEqual(len(arm_finder.get_arm_parameters().mapping), 2,
"It should be two mappings")
102 self.assertEqual(len(arm_finder.get_arm_parameters().joint_prefix), 2,
"It should be two joint_prefixes")
103 self.assertEqual(len(arm_finder.get_arm_joints().keys()), 2,
"It should be two arm joints mappings")
105 self.assertIn(
"ra", arm_finder.get_arm_parameters().mapping.values(),
"It should be ra mapping")
106 self.assertIn(
"ra_", arm_finder.get_arm_parameters().joint_prefix.values(),
"It should be ra_ prefix")
107 self.assertIn(
"ra", arm_finder.get_arm_joints(),
"Maping should be in the joints result")
108 self.assertEqual(len(arm_finder.get_arm_joints()[
"ra"]), 1,
"It should be one arm joint for mapping")
110 self.assertIn(
"la", arm_finder.get_arm_parameters().mapping.values(),
"It should be la mapping")
111 self.assertIn(
"la_", arm_finder.get_arm_parameters().joint_prefix.values(),
"It should be la_ prefix")
112 self.assertIn(
"la", arm_finder.get_arm_joints(),
"Maping should be in the joints result")
113 self.assertEqual(len(arm_finder.get_arm_joints()[
"la"]), 1,
"It should be one arm joint for mapping")
116 if rospy.has_param(
"arm"):
117 rospy.delete_param(
"arm")
119 if rospy.has_param(
"hand"):
120 rospy.delete_param(
"hand")
122 if rospy.has_param(
"robot_description"):
123 rospy.delete_param(
"robot_description")
125 rospy.set_param(
"robot_description", rospy.get_param(
"two_hands_left_arm"))
127 rospy.set_param(
"hand/joint_prefix/1",
"rh_")
128 rospy.set_param(
"hand/mapping/1",
"rh")
130 rospy.set_param(
"hand/joint_prefix/2",
"lh_")
131 rospy.set_param(
"hand/mapping/2",
"lh")
133 rospy.set_param(
"arm/joint_prefix/1",
"la_")
134 rospy.set_param(
"arm/mapping/1",
"la")
136 arm_finder = ArmFinder()
138 self.assertEqual(len(arm_finder.get_arm_parameters().mapping), 1,
"It should be one mapping")
139 self.assertEqual(len(arm_finder.get_arm_parameters().joint_prefix), 1,
"It should be one joint_prefix")
140 self.assertEqual(len(arm_finder.get_arm_joints().keys()), 1,
"It should be one arm joints")
142 self.assertIn(
"la", arm_finder.get_arm_parameters().mapping.values(),
"It should be la mapping")
143 self.assertIn(
"la_", arm_finder.get_arm_parameters().joint_prefix.values(),
"It should be la_ prefix")
144 self.assertIn(
"la", arm_finder.get_arm_joints(),
"Maping should be in the joints result")
146 if __name__ ==
"__main__":
147 rospy.init_node(
"test_arm_finder")
148 rostest.rosrun(
"sr_utilities",
"test_arm_finder", TestArmFinder)
def test_one_hand_two_arms_finder(self)
def test_two_hands_one_arm_finder(self)
def test_no_hand_one_arm_finder(self)
def test_one_hand_no_arm_finder(self)
def test_no_hand_no_arm_finder(self)