fit_primitive.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 import rostest
4 
5 import unittest
6 
7 import actionlib
8 from actionlib_msgs.msg import GoalStatus
9 from ensenso_camera_msgs.msg import FitPrimitiveAction, FitPrimitiveGoal, Primitive
10 from ensenso_camera_msgs.msg import RequestDataAction, RequestDataGoal
11 
12 from helper import Point
13 
14 INLIER_THRESHOLD = 0.005
15 
16 
17 # All used parameters with a length unit use meters as unit
18 
19 # Input parameters for "fit_primitive" action
21  primitive = Primitive()
22  primitive.type = Primitive.CYLINDER
23  primitive.inlier_threshold = INLIER_THRESHOLD
24  primitive.count = 1
25  primitive.inlier_fraction_in = 0.015
26  primitive.min_radius = 0.095
27  primitive.max_radius = 0.105
28  return primitive
29 
30 
32  primitive = Primitive()
33  primitive.type = Primitive.SPHERE
34  primitive.inlier_threshold = INLIER_THRESHOLD
35  primitive.count = 1
36  primitive.inlier_fraction_in = 0.03
37  primitive.min_radius = 0.048
38  primitive.max_radius = 0.055
39  return primitive
40 
41 
43  primitive = Primitive()
44  primitive.type = Primitive.PLANE
45  primitive.inlier_threshold = INLIER_THRESHOLD
46  primitive.count = 1
47  primitive.inlier_fraction_in = 0.015
48  return primitive
49 
50 
51 # Exact values of objects in the test scene
53  def __init__(self):
54  self.center = Point(0, 0.1, -0.1)
55  self.radius = 0.05
56 
57 
59  def __init__(self):
60  self.center = Point(0.0, -0.1, -0.25)
61  self.radius = 0.1
62 
63 
65  def __init__(self):
66  self.normal = Point(0, 0, -1.0)
67  self.center = Point(0, 0, -0.06)
68 
69 
70 class TestFitPrimitive(unittest.TestCase):
71  def setUp(self):
72  self.fit_primitive_client = actionlib.SimpleActionClient("fit_primitive", FitPrimitiveAction)
73  self.fit_primitive_client.wait_for_server()
74 
75  self.request_data_client = actionlib.SimpleActionClient("request_data", RequestDataAction)
76  self.request_data_client.wait_for_server()
77 
78  request_data_goal = RequestDataGoal()
79  request_data_goal.request_point_cloud = True
80  self.request_data_client.send_goal(request_data_goal)
81  self.request_data_client.wait_for_result()
82 
83  result = self.request_data_client.get_result()
84  self.assertEqual(result.error.code, 0)
85 
86  def test_sphere(self):
87  goal = FitPrimitiveGoal()
88  primitive = get_sphere_fit_primitive()
89  goal.primitives.append(primitive)
90  result = self.get_result(goal)
91  self.result_check(result)
92 
93  def test_plane(self):
94  goal = FitPrimitiveGoal()
95  primitive = get_plane_fit_primitive()
96  goal.primitives.append(primitive)
97 
98  result = self.get_result(goal)
99  self.result_check(result)
100 
101  def test_cylinder(self):
102  goal = FitPrimitiveGoal()
103  primitive = get_cylinder_fit_primitive()
104  goal.primitives.append(primitive)
105 
106  result = self.get_result(goal)
107  self.result_check(result)
108 
109  def result_check(self, result):
110  delta = INLIER_THRESHOLD * 2
111  for primitive in result.primitives:
112  if primitive.type == get_sphere_fit_primitive().type:
113  sphere = SphereTestValues()
114  self.assertAlmostEqual(primitive.center.x, sphere.center.x, delta=delta)
115  self.assertAlmostEqual(primitive.center.y, sphere.center.y, delta=delta)
116  self.assertAlmostEqual(primitive.center.z, sphere.center.z, delta=delta)
117  self.assertAlmostEqual(primitive.radius, sphere.radius, delta=delta)
118  elif primitive.type == get_cylinder_fit_primitive().type:
119  cylinder = CylinderTestValues()
120  self.assertAlmostEqual(primitive.center.y, cylinder.center.y, delta=delta)
121  self.assertAlmostEqual(primitive.center.z, cylinder.center.y, delta=delta)
122  self.assertAlmostEqual(primitive.radius, cylinder.radius, delta=delta)
123  elif primitive.type == get_plane_fit_primitive().type:
124  plane = PlaneTestValues()
125  self.assertAlmostEqual(abs(primitive.normal.z), abs(plane.normal.z), delta=delta)
126  self.assertAlmostEqual(primitive.center.z, plane.center.z, delta=delta)
127 
128  def get_result(self, goal):
129  self.fit_primitive_client.send_goal(goal)
130  self.fit_primitive_client.wait_for_result()
131  self.assertEqual(self.fit_primitive_client.get_state(), GoalStatus.SUCCEEDED)
132  result = self.fit_primitive_client.get_result()
133  self.assertEqual(result.error.code, 0)
134  return result
135 
136 
137 if __name__ == "__main__":
138  try:
139  rospy.init_node("test_fit_primitive")
140  rostest.rosrun("ensenso_camera_test", "test_fit_primitive", TestFitPrimitive)
141  except rospy.ROSInterruptException:
142  pass
def get_cylinder_fit_primitive()
def get_plane_fit_primitive()
def get_sphere_fit_primitive()
def result_check(self, result)


ensenso_camera_test
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:10