Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
collision_box_box_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_COLLISION_BOX_BOX_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_BOX_BOX_UNIT_HPP
3
9
11{
12namespace detail
13{
14inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex_mesh = false)
15{
17 // Add box to checker
19 CollisionShapePtr box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
20 Eigen::Isometry3d box_pose;
21 box_pose.setIdentity();
22
23 CollisionShapesConst obj1_shapes;
25 obj1_shapes.push_back(box);
26 obj1_poses.push_back(box_pose);
27
28 checker.addCollisionObject("box_link", 0, obj1_shapes, obj1_poses, false);
29 checker.enableCollisionObject("box_link");
30
32 // Add thin box to checker which is disabled
34 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
35 Eigen::Isometry3d thin_box_pose;
36 thin_box_pose.setIdentity();
37
38 CollisionShapesConst obj2_shapes;
40 obj2_shapes.push_back(thin_box);
41 obj2_poses.push_back(thin_box_pose);
42
43 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses);
44 checker.disableCollisionObject("thin_box_link");
45
47 // Add second box to checker. If use_convex_mesh = true then this
48 // box will be added as a convex hull mesh.
50 CollisionShapePtr second_box;
51
52 if (use_convex_mesh)
53 {
54 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
55 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
56 // TODO: Need to figure out why this test not pass of bullet when using the box_2m.ply mesh
58 std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box2_2m.ply", *mesh_vertices, *mesh_faces, true),
59 0);
60
61 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
62 second_box = makeConvexMesh(*mesh);
63 }
64 else
65 {
66 second_box = std::make_shared<tesseract_geometry::Box>(2, 2, 2);
67 }
68
69 Eigen::Isometry3d second_box_pose;
70 second_box_pose.setIdentity();
71
72 CollisionShapesConst obj3_shapes;
74 obj3_shapes.push_back(second_box);
75 obj3_poses.push_back(second_box_pose);
76
77 checker.addCollisionObject("second_box_link", 0, obj3_shapes, obj3_poses);
78
80 // Add box and remove
82 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
83 Eigen::Isometry3d remove_box_pose;
84 thin_box_pose.setIdentity();
85
86 CollisionShapesConst obj4_shapes;
88 obj4_shapes.push_back(remove_box);
89 obj4_poses.push_back(remove_box_pose);
90
91 checker.addCollisionObject("remove_box_link", 0, obj4_shapes, obj4_poses);
92 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
93 EXPECT_TRUE(checker.hasCollisionObject("remove_box_link"));
94 checker.removeCollisionObject("remove_box_link");
95 EXPECT_FALSE(checker.hasCollisionObject("remove_box_link"));
96
98 // Try functions on a link that does not exist
100 EXPECT_FALSE(checker.removeCollisionObject("link_does_not_exist"));
101 EXPECT_FALSE(checker.enableCollisionObject("link_does_not_exist"));
102 EXPECT_FALSE(checker.disableCollisionObject("link_does_not_exist"));
103
105 // Try to add empty Collision Object
109
111 // Check sizes
113 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
114 for (const auto& co : checker.getCollisionObjects())
115 {
116 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
118 for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
119 {
120 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
121 }
122 }
123}
124
126{
128 // Test when object is inside another
130 std::vector<std::string> active_links{ "box_link", "second_box_link" };
132 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
134
135 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
136
138 EXPECT_NEAR(checker.getCollisionMarginData().getPairCollisionMargin("box_link", "second_box_link"), 0.1, 1e-5);
139
140 // Set the collision object transforms
142 location["box_link"] = Eigen::Isometry3d::Identity();
143 location["box_link"].translation()(0) = 0.2;
144 location["box_link"].translation()(1) = 0.1;
145 location["second_box_link"] = Eigen::Isometry3d::Identity();
146
147 checker.setCollisionObjectsTransform(location);
148
149 // Perform collision check
150 ContactResultMap result;
151 checker.contactTest(result, ContactRequest(test_type));
152
155
156 EXPECT_TRUE(!result_vector.empty());
157 EXPECT_NEAR(result_vector[0].distance, -1.30, 0.001);
160
161 std::vector<int> idx = { 0, 1, 1 };
162 if (result_vector[0].link_names[0] != "box_link")
163 idx = { 1, 0, -1 };
164
166 {
168 EXPECT_FALSE(std::abs(result_vector[0].nearest_points[0][0] - (-0.3)) > 0.001 &&
169 std::abs(result_vector[0].nearest_points[0][0] - (1.0)) > 0.001);
170 }
171 else
172 {
173 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], -0.3, 0.001);
174 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], 1.0, 0.001);
175 }
176
177 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * -1.0, 0.001);
178 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
179 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
180
182 // Test object is outside the contact distance
184 {
185 location["box_link"].translation() = Eigen::Vector3d(1.60, 0, 0);
186 result.clear();
187 result_vector.clear();
188
189 // Use different method for setting transforms
190 std::vector<std::string> names = { "box_link" };
191 tesseract_common::VectorIsometry3d transforms = { location["box_link"] };
192 checker.setCollisionObjectsTransform(names, transforms);
193 checker.contactTest(result, test_type);
195
196 EXPECT_TRUE(result_vector.empty());
197 }
199 // Test object is outside the contact distance only for this link pair
201 {
203 data.setPairCollisionMargin("not_box_link", "also_not_box_link", 1.7);
205
207 EXPECT_NEAR(checker.getCollisionMarginData().getPairCollisionMargin("box_link", "second_box_link"), 0.1, 1e-5);
208 location["box_link"].translation() = Eigen::Vector3d(1.60, 0, 0);
209 result.clear();
210 result_vector.clear();
211
212 // Use different method for setting transforms
213 std::vector<std::string> names = { "box_link" };
214 tesseract_common::VectorIsometry3d transforms = { location["box_link"] };
215 checker.setCollisionObjectsTransform(names, transforms);
216 checker.contactTest(result, test_type);
218
219 EXPECT_TRUE(result_vector.empty());
220 }
222 // Test object inside the contact distance only for this link pair
224 {
225 result.clear();
226 result_vector.clear();
227
229 data.setPairCollisionMargin("box_link", "second_box_link", 0.25);
230
232 EXPECT_NEAR(checker.getCollisionMarginData().getPairCollisionMargin("box_link", "second_box_link"), 0.25, 1e-5);
234 checker.contactTest(result, ContactRequest(test_type));
236
237 EXPECT_TRUE(!result_vector.empty());
238 EXPECT_NEAR(result_vector[0].distance, 0.1, 0.001);
241
242 idx = { 0, 1, 1 };
243 if (result_vector[0].link_names[0] != "box_link")
244 idx = { 1, 0, -1 };
245
247 {
249 EXPECT_FALSE(std::abs(result_vector[0].nearest_points[0][0] - (1.1)) > 0.001 &&
250 std::abs(result_vector[0].nearest_points[0][0] - (1.0)) > 0.001);
251 }
252 else
253 {
254 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 1.1, 0.001);
255 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], 1.0, 0.001);
256 }
257
258 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * -1.0, 0.001);
259 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
260 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
261 }
263 // Test object inside the contact distance
265 {
266 result.clear();
267 result_vector.clear();
268
271 checker.contactTest(result, ContactRequest(test_type));
273
274 EXPECT_TRUE(!result_vector.empty());
275 EXPECT_NEAR(result_vector[0].distance, 0.1, 0.001);
278
279 idx = { 0, 1, 1 };
280 if (result_vector[0].link_names[0] != "box_link")
281 idx = { 1, 0, -1 };
282
284 {
286 EXPECT_FALSE(std::abs(result_vector[0].nearest_points[0][0] - (1.1)) > 0.001 &&
287 std::abs(result_vector[0].nearest_points[0][0] - (1.0)) > 0.001);
288 }
289 else
290 {
291 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 1.1, 0.001);
292 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], 1.0, 0.001);
293 }
294
295 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * -1.0, 0.001);
296 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
297 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
298 }
299}
300} // namespace detail
301
302inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = false)
303{
304 // Add collision objects
305 detail::addCollisionObjects(checker, use_convex_mesh);
306
307 // Call it again to test adding same object
308 detail::addCollisionObjects(checker, use_convex_mesh);
309
313}
314
315} // namespace tesseract_collision::test_suite
316#endif // COLLISION_BOX_BOX_UNIT_HPP
This structure hold contact results for link pairs.
Definition: types.h:154
void clear()
This is a consurvative clear.
Definition: types.cpp:183
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:215
void flattenCopyResults(ContactResultVector &v) const
Definition: types.cpp:227
Definition: discrete_contact_manager.h:41
virtual void setActiveCollisionObjects(const std::vector< std::string > &names)=0
Set which collision objects can move.
virtual void contactTest(ContactResultMap &collisions, const ContactRequest &request)=0
Perform a contact test for all objects based.
virtual void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)=0
Set a single collision object's transforms.
virtual bool addCollisionObject(const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)=0
Add a object to the checker.
virtual bool enableCollisionObject(const std::string &name)=0
Enable an object.
virtual bool removeCollisionObject(const std::string &name)=0
Remove an object from the checker.
virtual const std::vector< std::string > & getCollisionObjects() const =0
Get all collision objects.
virtual bool hasCollisionObject(const std::string &name) const =0
Find if a collision object already exists.
virtual const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const =0
Get a collision objects collision geometries transforms.
virtual bool disableCollisionObject(const std::string &name)=0
Disable an object.
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE)=0
Set the contact distance thresholds for which collision should be considered on a per pair basis.
virtual IsContactAllowedFn getIsContactAllowedFn() const =0
Get the active function for determining if two links are allowed to be in collision.
virtual const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const =0
Get a collision objects collision geometries.
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:74
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
double getPairCollisionMargin(const std::string &obj1, const std::string &obj2) const
Get the pairs collision margin data.
Definition: collision_margin_data.h:140
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
results link_names[0]
Definition: collision_core_unit.cpp:146
EXPECT_EQ(results.distance, std::numeric_limits< double >::max())
results normal
Definition: collision_core_unit.cpp:154
EXPECT_FALSE(tesseract_collision::isContactAllowed("base_link", "link_2", acm, false))
results nearest_points[0]
Definition: collision_core_unit.cpp:140
results single_contact_point
Definition: collision_core_unit.cpp:161
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
CollisionMarginData data(default_margin)
Definition: collision_margin_data_unit.cpp:34
This is a collection of common methods.
This is the continuous contact manager base class.
This is a collection of common methods.
This is the discrete contact manager base class.
Tesseract Geometries.
EXPECT_GT(m.m.condition, 1e+20)
void runTestTyped(DiscreteContactManager &checker, ContactTestType test_type)
Definition: collision_box_box_unit.hpp:125
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_common::CollisionMarginData CollisionMarginData
Definition: types.h:50
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
int loadSimplePlyFile(const std::string &path, tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, bool triangles_only=false)
Loads a simple ply file given a path.
Definition: common.cpp:285
ContactTestType
Definition: types.h:70
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh(const tesseract_geometry::Mesh &mesh)
Definition: convex_hull_utils.cpp:114
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
The ContactRequest struct.
Definition: types.h:294
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
auto box
Definition: tesseract_geometry_unit.cpp:18
auto mesh
Definition: tesseract_geometry_unit.cpp:25