Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
collision_mesh_mesh_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_COLLISION_MESH_MESH_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_MESH_MESH_UNIT_HPP
3
7
9{
10namespace detail
11{
12inline void addCollisionObjects(DiscreteContactManager& checker)
13{
15 // Add sphere to checker
18
19 auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
20 auto faces = std::make_shared<Eigen::VectorXi>();
21 int num_faces =
22 loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *vertices, *faces, true);
23 EXPECT_GT(num_faces, 0);
24
25 sphere = std::make_shared<tesseract_geometry::Mesh>(vertices, faces);
26 EXPECT_TRUE(num_faces == sphere->getFaceCount());
27
28 Eigen::Isometry3d sphere_pose;
29 sphere_pose.setIdentity();
30
31 CollisionShapesConst obj1_shapes;
33 obj1_shapes.push_back(sphere);
34 obj1_poses.push_back(sphere_pose);
35
36 checker.addCollisionObject("sphere_link", 0, obj1_shapes, obj1_poses, false);
37 checker.enableCollisionObject("sphere_link");
38
40 // Add thin box to checker which is disabled
42 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
43 Eigen::Isometry3d thin_box_pose;
44 thin_box_pose.setIdentity();
45
46 CollisionShapesConst obj2_shapes;
48 obj2_shapes.push_back(thin_box);
49 obj2_poses.push_back(thin_box_pose);
50
51 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses);
52 checker.disableCollisionObject("thin_box_link");
53
55 // Add second sphere to checker. If use_convex_mesh = true
56 // then this sphere will be added as a convex hull mesh.
58 CollisionShapePtr sphere1 = std::make_shared<tesseract_geometry::Mesh>(vertices, faces);
59 Eigen::Isometry3d sphere1_pose;
60 sphere1_pose.setIdentity();
61
62 CollisionShapesConst obj3_shapes;
64 obj3_shapes.push_back(sphere1);
65 obj3_poses.push_back(sphere1_pose);
66
67 checker.addCollisionObject("sphere1_link", 0, obj3_shapes, obj3_poses);
68
70 // Add box and remove
72 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
73 Eigen::Isometry3d remove_box_pose;
74 thin_box_pose.setIdentity();
75
76 CollisionShapesConst obj4_shapes;
78 obj4_shapes.push_back(remove_box);
79 obj4_poses.push_back(remove_box_pose);
80
81 checker.addCollisionObject("remove_box_link", 0, obj4_shapes, obj4_poses);
82 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
83 EXPECT_TRUE(checker.hasCollisionObject("remove_box_link"));
84 checker.removeCollisionObject("remove_box_link");
85 EXPECT_FALSE(checker.hasCollisionObject("remove_box_link"));
86
88 // Try functions on a link that does not exist
90 EXPECT_FALSE(checker.removeCollisionObject("link_does_not_exist"));
91 EXPECT_FALSE(checker.enableCollisionObject("link_does_not_exist"));
92 EXPECT_FALSE(checker.disableCollisionObject("link_does_not_exist"));
93
95 // Try to add empty Collision Object
98 checker.addCollisionObject("empty_link", 0, CollisionShapesConst(), tesseract_common::VectorIsometry3d()));
99
101 // Check sizes
103 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
104 for (const auto& co : checker.getCollisionObjects())
105 {
106 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
107 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
108 for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
109 {
110 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
111 }
112 }
113}
114} // namespace detail
115
116inline void runTest(DiscreteContactManager& checker)
117{
118 // Add collision objects
120
121 // Call it again to test adding same object
123
125 // Test when object is in collision (Closest Feature Edge to Edge)
127 std::vector<std::string> active_links{ "sphere_link", "sphere1_link" };
128 checker.setActiveCollisionObjects(active_links);
129 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
131
132 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
133
134 checker.setDefaultCollisionMarginData(0);
135 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.0, 1e-5);
136
137 // Test when object is inside another
139 location["sphere_link"] = Eigen::Isometry3d::Identity();
140 location["sphere1_link"] = Eigen::Isometry3d::Identity();
141 location["sphere1_link"].translation()(0) = 0.2;
142 checker.setCollisionObjectsTransform(location);
143
144 // Perform collision check
145 ContactResultMap result;
146 checker.contactTest(result, ContactRequest(ContactTestType::ALL));
147
149 result.flattenMoveResults(result_vector);
150
151 EXPECT_TRUE(result_vector.size() >= 37);
152
154 // Test object is out side the contact distance
156 location["sphere1_link"].translation() = Eigen::Vector3d(1, 0, 0);
157 result.clear();
158 result_vector.clear();
159 checker.setCollisionObjectsTransform(location);
160
161 checker.contactTest(result, ContactRequest(ContactTestType::ALL));
162 result.flattenCopyResults(result_vector);
163
164 EXPECT_TRUE(result_vector.empty());
165
167 // Test object inside the contact distance (Closest Feature Edge to Edge)
169 result.clear();
170 result_vector.clear();
171
172 checker.setCollisionMarginData(CollisionMarginData(0.55));
173 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.55, 1e-5);
174 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
175 result.flattenMoveResults(result_vector);
176
177 EXPECT_TRUE(!result_vector.empty());
178 EXPECT_NEAR(result_vector[0].distance, 0.52448, 0.001);
179
180 std::vector<int> idx = { 0, 1, 1 };
181 if (result_vector[0].link_names[0] != "sphere_link")
182 idx = { 1, 0, -1 };
183
184 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.23776, 0.001);
185 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], 0.76224, 0.001);
188 EXPECT_GT((idx[2] * result_vector[0].normal).dot(Eigen::Vector3d(1, 0, 0)), 0.0);
189 EXPECT_LT(std::abs(std::acos((idx[2] * result_vector[0].normal).dot(Eigen::Vector3d(1, 0, 0)))), 0.00001);
190
192 // Test object inside the contact distance (Closest Feature Vertex to Vertex)
194 location["sphere1_link"].translation() = Eigen::Vector3d(0, 1, 0);
195 result.clear();
196 result_vector.clear();
197
198 // The closest feature of the mesh should be edge to edge
199 // Use different method for setting transforms
200 checker.setCollisionObjectsTransform("sphere1_link", location["sphere1_link"]);
201 checker.setCollisionMarginData(CollisionMarginData(0.55));
202 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.55, 1e-5);
203 checker.contactTest(result, ContactRequest(ContactTestType::CLOSEST));
204 result.flattenCopyResults(result_vector);
205
206 EXPECT_TRUE(!result_vector.empty());
207 EXPECT_NEAR(result_vector[0].distance, 0.5, 0.001);
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])][1], 0.25, 0.001);
214 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1], 0.75, 0.001);
217 EXPECT_GT((idx[2] * result_vector[0].normal).dot(Eigen::Vector3d(0, 1, 0)), 0.0);
218 EXPECT_LT(std::abs(std::acos((idx[2] * result_vector[0].normal).dot(Eigen::Vector3d(0, 1, 0)))), 0.00001);
219}
220} // namespace tesseract_collision::test_suite
221#endif // TESSERACT_COLLISION_COLLISION_MESH_MESH_UNIT_HPP
std::shared_ptr< Mesh > Ptr
Definition: mesh.h:52
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
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
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
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 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
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
std::shared_ptr< const Eigen::VectorXi > faces
Definition: tesseract_geometry_unit.cpp:16
auto sphere
Definition: tesseract_geometry_unit.cpp:23