4 import ensenso_camera.ros2
as ros2py
9 LocatePatternMono = ros2py.import_action(
"ensenso_camera_msgs",
"LocatePatternMono")
11 DATA_SET_FILEPATH = ros2py_testing.get_test_data_path(
"locate_pattern_mono/pattern_pose.json")
16 self.
node = ros2py.create_node(
"test_locate_pattern_mono")
22 result = response.get_result()
24 self.assertTrue(response.successful())
25 self.assertEqual(result.error.code, 0)
27 self.assertTrue(result.found_pattern)
28 self.assertEqual(len(result.mono_patterns), 1)
29 self.assertEqual(len(result.mono_pattern_poses), 1)
31 self.assertNotEqual(result.frame,
"")
33 pattern = result.mono_patterns[0]
35 self.assertEqual(pattern.grid_spacing, 0.03625)
36 self.assertEqual(pattern.grid_size_x, 7)
37 self.assertEqual(pattern.grid_size_y, 7)
38 self.assertEqual(len(pattern.points), 49)
40 self.assertNotEqual(result.mono_pattern_poses[0].header.stamp, 0)
41 self.assertNotEqual(result.mono_pattern_poses[0].header.frame_id,
"")
43 reference_pattern_pose = Pose.from_json(DATA_SET_FILEPATH)
44 estimated_pattern_pose = Pose.from_message(result.mono_pattern_poses[0].pose)
45 self.assertTrue(reference_pattern_pose.equals(estimated_pattern_pose))
49 ros2py_testing.run_ros1_test(
"test_locate_pattern_mono", TestLocatePatternMono)
52 if __name__ ==
"__main__":