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
12 from helper
import Point
14 INLIER_THRESHOLD = 0.005
21 primitive = Primitive()
22 primitive.type = Primitive.CYLINDER
23 primitive.inlier_threshold = INLIER_THRESHOLD
25 primitive.inlier_fraction_in = 0.015
26 primitive.min_radius = 0.095
27 primitive.max_radius = 0.105
32 primitive = Primitive()
33 primitive.type = Primitive.SPHERE
34 primitive.inlier_threshold = INLIER_THRESHOLD
36 primitive.inlier_fraction_in = 0.03
37 primitive.min_radius = 0.048
38 primitive.max_radius = 0.055
43 primitive = Primitive()
44 primitive.type = Primitive.PLANE
45 primitive.inlier_threshold = INLIER_THRESHOLD
47 primitive.inlier_fraction_in = 0.015
73 self.fit_primitive_client.wait_for_server()
76 self.request_data_client.wait_for_server()
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()
83 result = self.request_data_client.get_result()
84 self.assertEqual(result.error.code, 0)
87 goal = FitPrimitiveGoal()
89 goal.primitives.append(primitive)
94 goal = FitPrimitiveGoal()
96 goal.primitives.append(primitive)
102 goal = FitPrimitiveGoal()
104 goal.primitives.append(primitive)
110 delta = INLIER_THRESHOLD * 2
111 for primitive
in result.primitives:
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)
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)
125 self.assertAlmostEqual(abs(primitive.normal.z), abs(plane.normal.z), delta=delta)
126 self.assertAlmostEqual(primitive.center.z, plane.center.z, delta=delta)
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)
137 if __name__ ==
"__main__":
139 rospy.init_node(
"test_fit_primitive")
140 rostest.rosrun(
"ensenso_camera_test",
"test_fit_primitive", TestFitPrimitive)
141 except rospy.ROSInterruptException:
def get_cylinder_fit_primitive()
def get_plane_fit_primitive()
def get_result(self, goal)
def get_sphere_fit_primitive()
def result_check(self, result)