Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
contact_manager_config_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_CONTACT_MANAGER_CONFIG_UNIT_H
2#define TESSERACT_COLLISION_CONTACT_MANAGER_CONFIG_UNIT_H
3
8
10{
11namespace detail
12{
13inline void addCollisionObjects(DiscreteContactManager& checker)
14{
16 // Add sphere to checker
18 CollisionShapePtr sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
19
20 Eigen::Isometry3d sphere_pose;
21 sphere_pose.setIdentity();
22
23 CollisionShapesConst obj1_shapes;
25 obj1_shapes.push_back(sphere);
26 obj1_poses.push_back(sphere_pose);
27
28 checker.addCollisionObject("sphere_link", 0, obj1_shapes, obj1_poses);
29
31 // Add thin box to checker which is disabled
33 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
34 Eigen::Isometry3d thin_box_pose;
35 thin_box_pose.setIdentity();
36
37 CollisionShapesConst obj2_shapes;
39 obj2_shapes.push_back(thin_box);
40 obj2_poses.push_back(thin_box_pose);
41
42 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses);
43
45 // Add second sphere to checker. If use_convex_mesh = true
46 // then this sphere will be added as a convex hull mesh.
48 CollisionShapePtr sphere1 = std::make_shared<tesseract_geometry::Sphere>(0.25);
49
50 Eigen::Isometry3d sphere1_pose;
51 sphere1_pose.setIdentity();
52
53 CollisionShapesConst obj3_shapes;
55 obj3_shapes.push_back(sphere1);
56 obj3_poses.push_back(sphere1_pose);
57
58 checker.addCollisionObject("sphere1_link", 0, obj3_shapes, obj3_poses);
59}
60
61inline void addCollisionObjects(ContinuousContactManager& checker)
62{
64 // Add sphere to checker
66 CollisionShapePtr sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
67
68 Eigen::Isometry3d sphere_pose;
69 sphere_pose.setIdentity();
70 sphere_pose.translation()[2] = 0.25;
71
72 CollisionShapesConst obj1_shapes;
74 obj1_shapes.push_back(sphere);
75 obj1_poses.push_back(sphere_pose);
76
77 checker.addCollisionObject("sphere_link", 0, obj1_shapes, obj1_poses, false);
78 EXPECT_FALSE(checker.isCollisionObjectEnabled("sphere_link"));
79 checker.enableCollisionObject("sphere_link");
80 EXPECT_TRUE(checker.isCollisionObjectEnabled("sphere_link"));
81
83 // Add thin box to checker which is disabled
85 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
86 Eigen::Isometry3d thin_box_pose;
87 thin_box_pose.setIdentity();
88
89 CollisionShapesConst obj2_shapes;
91 obj2_shapes.push_back(thin_box);
92 obj2_poses.push_back(thin_box_pose);
93
94 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses);
95
97 // Add second sphere to checker. If use_convex_mesh = true
98 // then this sphere will be added as a convex hull mesh.
100 CollisionShapePtr sphere1 = std::make_shared<tesseract_geometry::Sphere>(0.25);
101
102 Eigen::Isometry3d sphere1_pose;
103 sphere1_pose.setIdentity();
104 sphere1_pose.translation()[2] = 0.25;
105
106 CollisionShapesConst obj3_shapes;
108 obj3_shapes.push_back(sphere1);
109 obj3_poses.push_back(sphere1_pose);
110
111 checker.addCollisionObject("sphere1_link", 0, obj3_shapes, obj3_poses);
112 EXPECT_TRUE(checker.isCollisionObjectEnabled("sphere1_link"));
113}
114
115} // namespace detail
116
117inline void runTest(DiscreteContactManager& checker)
118{
119 // Add collision objects
121
123 // Test when object is in collision
125 std::vector<std::string> active_links{ "sphere_link", "sphere1_link" };
126 checker.setActiveCollisionObjects(active_links);
127 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
129
130 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
131
132 checker.setDefaultCollisionMarginData(0.5);
133 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
134 EXPECT_TRUE(checker.isCollisionObjectEnabled("thin_box_link"));
135
136 ContactManagerConfig config(0.1);
137 config.margin_data_override_type = CollisionMarginOverrideType::NONE;
138 config.modify_object_enabled["thin_box_link"] = false;
139
140 checker.applyContactManagerConfig(config);
141 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
142 EXPECT_FALSE(checker.isCollisionObjectEnabled("thin_box_link"));
143
144 config.margin_data_override_type = CollisionMarginOverrideType::OVERRIDE_DEFAULT_MARGIN;
145 checker.applyContactManagerConfig(config);
146 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
147
148 // Test when object is inside another
150 location["sphere_link"] = Eigen::Isometry3d::Identity();
151 location["sphere1_link"] = Eigen::Isometry3d::Identity();
152 location["sphere1_link"].translation()(0) = 0.2;
153 checker.setCollisionObjectsTransform(location);
154
155 // Perform collision check
156 ContactResultMap result;
157 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
158
160 result.flattenMoveResults(result_vector);
161
162 EXPECT_TRUE(!result_vector.empty());
163 EXPECT_NEAR(result_vector[0].distance, -0.30, 0.0001);
164
165 std::vector<int> idx = { 0, 1, 1 };
166 if (result_vector[0].link_names[0] != "sphere_link")
167 idx = { 1, 0, -1 };
168
169 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.25, 0.001);
170 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
171 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2], 0.0, 0.001);
172 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], -0.05, 0.001);
173 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
174 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2], 0.0, 0.001);
175
176 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 1.0, 0.001);
177 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
178 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.0016); // TODO LEVI: This was increased due to FLC
179 // calculation because it is using GJK
180
182 // Test object is out side the contact distance
184 location["sphere1_link"].translation() = Eigen::Vector3d(1, 0, 0);
185 result.clear();
186 result_vector.clear();
187 checker.setCollisionObjectsTransform("sphere1_link", location["sphere1_link"]);
188
189 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
190 result.flattenCopyResults(result_vector);
191
192 EXPECT_TRUE(result_vector.empty());
193
195 // Test object inside the contact distance
197 result.clear();
198 result_vector.clear();
199
200 config = ContactManagerConfig(0.52);
201 checker.applyContactManagerConfig(config);
202 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.52, 1e-5);
203 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
204 result.flattenMoveResults(result_vector);
205
206 EXPECT_TRUE(!result_vector.empty());
207 EXPECT_NEAR(result_vector[0].distance, 0.5, 0.0001);
208
209 idx = { 0, 1, 1 };
210 if (result_vector[0].link_names[0] != "sphere_link")
211 idx = { 1, 0, -1 };
212
213 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.25, 0.001);
214 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
215 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2], 0.0, 0.001);
216 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], 0.75, 0.001);
217 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
218 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2], 0.0, 0.001);
219
220 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 1.0, 0.001);
221 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
222 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
223}
224
225inline void runTest(ContinuousContactManager& checker)
226{
227 // Add collision objects
229
231 // Test when object is in collision at cc_time 0.5
233 std::vector<std::string> active_links{ "sphere_link", "sphere1_link" };
234 checker.setActiveCollisionObjects(active_links);
235 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
237
238 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
239
240 checker.setDefaultCollisionMarginData(0.5);
241 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
242 EXPECT_TRUE(checker.isCollisionObjectEnabled("thin_box_link"));
243
244 ContactManagerConfig config(0.1);
245 config.margin_data_override_type = CollisionMarginOverrideType::NONE;
246 config.modify_object_enabled["thin_box_link"] = false;
247
248 checker.applyContactManagerConfig(config);
249 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
250 EXPECT_FALSE(checker.isCollisionObjectEnabled("thin_box_link"));
251
252 config.margin_data_override_type = CollisionMarginOverrideType::OVERRIDE_DEFAULT_MARGIN;
253 checker.applyContactManagerConfig(config);
254 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
255
256 // Set the start location
257 tesseract_common::TransformMap location_start;
258 location_start["sphere_link"] = Eigen::Isometry3d::Identity();
259 location_start["sphere_link"].translation()(0) = -0.2;
260 location_start["sphere_link"].translation()(1) = -1.0;
261
262 location_start["sphere1_link"] = Eigen::Isometry3d::Identity();
263 location_start["sphere1_link"].translation()(0) = 0.2;
264 location_start["sphere1_link"].translation()(2) = -1.0;
265
266 // Set the end location
268 location_end["sphere_link"] = Eigen::Isometry3d::Identity();
269 location_end["sphere_link"].translation()(0) = -0.2;
270 location_end["sphere_link"].translation()(1) = 1.0;
271
272 location_end["sphere1_link"] = Eigen::Isometry3d::Identity();
273 location_end["sphere1_link"].translation()(0) = 0.2;
274 location_end["sphere1_link"].translation()(2) = 1.0;
275
276 checker.setCollisionObjectsTransform(location_start, location_end);
277
278 // Perform collision check
279 ContactResultMap result;
280 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
281
283 result.flattenCopyResults(result_vector);
284
285 EXPECT_TRUE(!result_vector.empty());
286 EXPECT_NEAR(result_vector[0].distance, -0.1, 0.0001);
287
288 std::vector<int> idx = { 0, 1, 1 };
289 if (result_vector[0].link_names[0] != "sphere_link")
290 idx = { 1, 0, -1 };
291
292 EXPECT_NEAR(result_vector[0].cc_time[static_cast<size_t>(idx[0])], 0.5, 0.001);
293 EXPECT_NEAR(result_vector[0].cc_time[static_cast<size_t>(idx[1])], 0.5, 0.001);
294
295 EXPECT_TRUE(result_vector[0].cc_type[static_cast<size_t>(static_cast<size_t>(idx[0]))] ==
297 EXPECT_TRUE(result_vector[0].cc_type[static_cast<size_t>(static_cast<size_t>(idx[0]))] ==
299
300 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.05, 0.001);
301 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
302 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2], 0.25, 0.001);
303
304 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], -0.05, 0.001);
305 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
306 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2], 0.25, 0.001);
307
308 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][0], 0.25, 0.001);
309 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
310 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][2], 0.25, 0.001);
311 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][0], -0.25, 0.001);
312 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
313 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][2], 0.25, 0.001);
314
315 EXPECT_TRUE(result_vector[0].transform[static_cast<size_t>(idx[0])].isApprox(location_start["sphere_link"], 0.0001));
316 EXPECT_TRUE(result_vector[0].transform[static_cast<size_t>(idx[1])].isApprox(location_start["sphere1_link"], 0.0001));
317 EXPECT_TRUE(result_vector[0].cc_transform[static_cast<size_t>(idx[0])].isApprox(location_end["sphere_link"], 0.0001));
319 result_vector[0].cc_transform[static_cast<size_t>(idx[1])].isApprox(location_end["sphere1_link"], 0.0001));
320
321 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 1.0, 0.001);
322 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
323 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
324
326 // Test when object is in collision at cc_time 0.333 and 0.5
328
329 // Set the start location
330 location_start["sphere_link"] = Eigen::Isometry3d::Identity();
331 location_start["sphere_link"].translation()(0) = -0.2;
332 location_start["sphere_link"].translation()(1) = -0.5;
333
334 location_start["sphere1_link"] = Eigen::Isometry3d::Identity();
335 location_start["sphere1_link"].translation()(0) = 0.2;
336 location_start["sphere1_link"].translation()(2) = -1.0;
337
338 // Set the end location
339 location_end["sphere_link"] = Eigen::Isometry3d::Identity();
340 location_end["sphere_link"].translation()(0) = -0.2;
341 location_end["sphere_link"].translation()(1) = 1.0;
342
343 location_end["sphere1_link"] = Eigen::Isometry3d::Identity();
344 location_end["sphere1_link"].translation()(0) = 0.2;
345 location_end["sphere1_link"].translation()(2) = 1.0;
346
347 checker.setCollisionObjectsTransform(location_start, location_end);
348
349 // Perform collision check
350 result.clear();
351 result_vector.clear();
352 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
353
354 result.flattenMoveResults(result_vector);
355
356 EXPECT_TRUE(!result_vector.empty());
357 EXPECT_NEAR(result_vector[0].distance, -0.1, 0.0001);
358
359 idx = { 0, 1, 1 };
360 if (result_vector[0].link_names[0] != "sphere_link")
361 idx = { 1, 0, -1 };
362
363 EXPECT_NEAR(result_vector[0].cc_time[static_cast<size_t>(idx[0])], 0.3333, 0.001);
364 EXPECT_NEAR(result_vector[0].cc_time[static_cast<size_t>(idx[1])], 0.5, 0.001);
365
366 EXPECT_TRUE(result_vector[0].cc_type[static_cast<size_t>(static_cast<size_t>(idx[0]))] ==
368 EXPECT_TRUE(result_vector[0].cc_type[static_cast<size_t>(static_cast<size_t>(idx[1]))] ==
370
371 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.05, 0.001);
372 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
373 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2], 0.25, 0.001);
374
375 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], -0.05, 0.001);
376 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
377 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2], 0.25, 0.001);
378
379 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][0], 0.25, 0.001);
380 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][1], 0.0, 0.001);
381 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[0])][2], 0.25, 0.001);
382 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][0], -0.25, 0.001);
383 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][1], 0.0, 0.001);
384 EXPECT_NEAR(result_vector[0].nearest_points_local[static_cast<size_t>(idx[1])][2], 0.25, 0.001);
385
386 EXPECT_TRUE(result_vector[0].transform[static_cast<size_t>(idx[0])].isApprox(location_start["sphere_link"], 0.0001));
387 EXPECT_TRUE(result_vector[0].transform[static_cast<size_t>(idx[1])].isApprox(location_start["sphere1_link"], 0.0001));
388 EXPECT_TRUE(result_vector[0].cc_transform[static_cast<size_t>(idx[0])].isApprox(location_end["sphere_link"], 0.0001));
390 result_vector[0].cc_transform[static_cast<size_t>(idx[1])].isApprox(location_end["sphere1_link"], 0.0001));
391
392 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 1.0, 0.001);
393 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
394 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
395}
396} // namespace tesseract_collision::test_suite
397#endif // TESSERACT_COLLISION_CONTACT_MANAGER_CONFIG_UNIT_H
results transform[0]
Definition: collision_core_unit.cpp:144
EXPECT_NEAR(config.contact_manager_config.margin_data.getDefaultCollisionMargin(), 5, 1e-6)
tesseract_collision::ContactResultVector result_vector
Definition: collision_core_unit.cpp:410
results distance
Definition: collision_core_unit.cpp:139
tesseract_collision::CollisionCheckConfig config(5, request, tesseract_collision::CollisionEvaluatorType::LVS_DISCRETE, 0.5)
Definition: tesseract_common_serialization_unit.cpp:154
results link_names[0]
Definition: collision_core_unit.cpp:146
results normal
Definition: collision_core_unit.cpp:154
results cc_type[0]
Definition: collision_core_unit.cpp:157
results cc_time[0]
Definition: collision_core_unit.cpp:155
EXPECT_FALSE(tesseract_collision::isContactAllowed("base_link", "link_2", acm, false))
results nearest_points[0]
Definition: collision_core_unit.cpp:140
results cc_transform[0]
Definition: collision_core_unit.cpp:159
results nearest_points_local[0]
Definition: collision_core_unit.cpp:142
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
This is a collection of common methods.
This is the continuous contact manager base class.
This is the discrete contact manager base class.
Tesseract Geometries.
void addCollisionObjects(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:11
Definition: large_dataset_benchmarks.hpp:17
void runTest(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:111
tesseract_geometry::Geometry::Ptr CollisionShapePtr
Definition: types.h:49
std::vector< tesseract_geometry::Geometry::ConstPtr > CollisionShapesConst
Definition: types.h:47
tesseract_common::AlignedVector< ContactResult > ContactResultVector
Definition: types.h:134
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
template bool isIdentical< std::string >(const std::vector< std::string > &, const std::vector< std::string > &, bool, const std::function< bool(const std::string &, const std::string &)> &, const std::function< bool(const std::string &, const std::string &)> &)
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
Definition: types.h:62
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
auto sphere
Definition: tesseract_geometry_unit.cpp:23