locate_pattern.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 import rostest
4 
5 import os
6 import unittest
7 
8 import actionlib
9 from actionlib_msgs.msg import GoalStatus
10 from ensenso_camera_msgs.msg import LocatePatternAction, LocatePatternGoal
11 
12 from helper import Pose
13 
14 DATA_SET_DIRECTORY = "../data/locate_pattern/"
15 
16 FRAMES_CONTAIN_PATTERN = [True, False]
17 
18 
19 class TestLocatePattern(unittest.TestCase):
20  def setUp(self):
21  self.locate_pattern_client = actionlib.SimpleActionClient("locate_pattern", LocatePatternAction)
22  self.locate_pattern_client.wait_for_server()
23 
25  for contains_pattern in FRAMES_CONTAIN_PATTERN:
26  self.locate_pattern_client.send_goal(LocatePatternGoal())
27  self.locate_pattern_client.wait_for_result()
28  self.assertEqual(self.locate_pattern_client.get_state(), GoalStatus.SUCCEEDED)
29  result = self.locate_pattern_client.get_result()
30  self.assertEqual(result.error.code, 0)
31 
32  if contains_pattern:
33  self.assertTrue(result.found_pattern)
34  self.assertEqual(len(result.patterns), 1)
35  self.assertEqual(len(result.pattern_poses), 1)
36 
37  self.assertNotEqual(result.frame, "")
38 
39  pattern = result.patterns[0]
40 
41  self.assertEqual(pattern.thickness, 0.001)
42  self.assertEqual(pattern.grid_spacing, 0.01875)
43  self.assertEqual(pattern.grid_size_x, 7)
44  self.assertEqual(pattern.grid_size_y, 7)
45  self.assertEqual(len(pattern.left_points), 49)
46  self.assertEqual(len(pattern.right_points), 49)
47 
48  self.assertNotEqual(result.pattern_poses[0].header.stamp, 0)
49  self.assertNotEqual(result.pattern_poses[0].header.frame_id, "")
50 
51  reference_pattern_pose = Pose.from_json(os.path.join(DATA_SET_DIRECTORY, "pattern_pose.json"))
52  estimated_pattern_pose = Pose.from_message(result.pattern_poses[0].pose)
53  self.assertTrue(reference_pattern_pose.equals(estimated_pattern_pose))
54  else:
55  self.assertFalse(result.found_pattern)
56  self.assertEqual(len(result.patterns), 0)
57  self.assertEqual(len(result.pattern_poses), 0)
58 
59 
60 if __name__ == "__main__":
61  try:
62  rospy.init_node("test_locate_pattern")
63  rostest.rosrun("ensenso_camera_test", "test_locate_pattern", TestLocatePattern)
64  except rospy.ROSInterruptException:
65  pass


ensenso_camera_test
Author(s): Ensenso
autogenerated on Thu May 16 2019 02:44:26