Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
collision_clone_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_COLLISION_CLONE_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_CLONE_UNIT_HPP
3
6
8{
9namespace detail
10{
11inline void addCollisionObjects(DiscreteContactManager& checker)
12{
14 // Add sphere to checker
16 CollisionShapePtr sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
17
18 Eigen::Isometry3d sphere_pose;
19 sphere_pose.setIdentity();
20
21 CollisionShapesConst obj1_shapes;
23 obj1_shapes.push_back(sphere);
24 obj1_poses.push_back(sphere_pose);
25
26 checker.addCollisionObject("sphere_link", 0, obj1_shapes, obj1_poses);
27 EXPECT_TRUE(checker.isCollisionObjectEnabled("sphere_link"));
28
30 // Add thin box to checker which is disabled
32 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
33 Eigen::Isometry3d thin_box_pose;
34 thin_box_pose.setIdentity();
35
36 CollisionShapesConst obj2_shapes;
38 obj2_shapes.push_back(thin_box);
39 obj2_poses.push_back(thin_box_pose);
40
41 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses, false);
42 EXPECT_FALSE(checker.isCollisionObjectEnabled("thin_box_link"));
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 EXPECT_TRUE(checker.isCollisionObjectEnabled("sphere1_link"));
60
62 // Add box and remove
64 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
65 Eigen::Isometry3d remove_box_pose;
66 thin_box_pose.setIdentity();
67
68 CollisionShapesConst obj4_shapes;
70 obj4_shapes.push_back(remove_box);
71 obj4_poses.push_back(remove_box_pose);
72
73 checker.addCollisionObject("remove_box_link", 0, obj4_shapes, obj4_poses);
74 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
75 EXPECT_TRUE(checker.hasCollisionObject("remove_box_link"));
76 EXPECT_TRUE(checker.isCollisionObjectEnabled("remove_box_link"));
77 checker.removeCollisionObject("remove_box_link");
78 EXPECT_FALSE(checker.hasCollisionObject("remove_box_link"));
79
81 // Try functions on a link that does not exist
83 EXPECT_FALSE(checker.removeCollisionObject("link_does_not_exist"));
84 EXPECT_FALSE(checker.enableCollisionObject("link_does_not_exist"));
85 EXPECT_FALSE(checker.disableCollisionObject("link_does_not_exist"));
86 EXPECT_FALSE(checker.isCollisionObjectEnabled("link_does_not_exist"));
87
89 // Try to add empty Collision Object
92 checker.addCollisionObject("empty_link", 0, CollisionShapesConst(), tesseract_common::VectorIsometry3d()));
93
95 // Check sizes
97 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
98 for (const auto& co : checker.getCollisionObjects())
99 {
100 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
101 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
102 for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
103 {
104 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
105 }
106 }
107}
108} // namespace detail
109
110inline void
111runTest(DiscreteContactManager& checker, double dist_tol = 0.001, double nearest_tol = 0.001, double normal_tol = 0.001)
112{
113 // Check name which should not be empty
114 EXPECT_FALSE(checker.getName().empty());
115
116 // Add collision objects
118
119 // Call it again to test adding same object
121
123 // Test when object is in collision
125 std::vector<std::string> active_links{ "sphere_link", "sphere1_link" };
127 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
129
130 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
131
134 EXPECT_FALSE(checker.isCollisionObjectEnabled("thin_box_link"));
135
136 checker.setPairCollisionMarginData("sphere_link", "sphere1_link", 0.1);
137
138 // Test when object is inside another
140 location["sphere_link"] = Eigen::Isometry3d::Identity();
141 location["sphere1_link"] = Eigen::Isometry3d::Identity();
142 location["sphere1_link"].translation()(0) = 0.2;
143 checker.setCollisionObjectsTransform(location);
144
145 // Perform collision check
146 ContactResultMap result;
148
151
152 std::vector<int> idx = { 0, 1, 1 };
153 if (result_vector[0].link_names[0] != "sphere_link")
154 idx = { 1, 0, -1 };
155
156 // Clone and perform collision check
157 ContactResultMap cloned_result;
158 DiscreteContactManager::Ptr cloned_checker = checker.clone();
159
160 cloned_checker->contactTest(cloned_result, ContactRequest(ContactTestType::CLOSEST));
161
162 ContactResultVector cloned_result_vector;
163 cloned_result.flattenMoveResults(cloned_result_vector);
164
165 std::vector<int> cloned_idx = { 0, 1, 1 };
166 if (cloned_result_vector[0].link_names[0] != "sphere_link")
167 cloned_idx = { 1, 0, -1 };
168
169 EXPECT_FALSE(cloned_checker->isCollisionObjectEnabled("thin_box_link"));
170 EXPECT_TRUE(!result_vector.empty() && !cloned_result_vector.empty());
171 EXPECT_NEAR(result_vector[0].distance, cloned_result_vector[0].distance, dist_tol);
172 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0],
173 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[0])][0],
174 nearest_tol);
175 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][1],
176 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[0])][1],
177 nearest_tol);
178 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2],
179 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[0])][2],
180 nearest_tol);
181 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0],
182 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[1])][0],
183 nearest_tol);
184 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][1],
185 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[1])][1],
186 nearest_tol);
187 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2],
188 cloned_result_vector[0].nearest_points[static_cast<size_t>(cloned_idx[1])][2],
189 nearest_tol);
190 EXPECT_NEAR(result_vector[0].normal[0] * idx[2], cloned_result_vector[0].normal[0] * cloned_idx[2], normal_tol);
191 EXPECT_NEAR(result_vector[0].normal[1] * idx[2], cloned_result_vector[0].normal[1] * cloned_idx[2], normal_tol);
192 EXPECT_NEAR(result_vector[0].normal[2] * idx[2], cloned_result_vector[0].normal[2] * cloned_idx[2], normal_tol);
193}
194} // namespace tesseract_collision::test_suite
195#endif // TESSERACT_COLLISION_COLLISION_CLONE_UNIT_HPP
This structure hold contact results for link pairs.
Definition: types.h:154
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:215
Definition: discrete_contact_manager.h:41
virtual bool isCollisionObjectEnabled(const std::string &name) const =0
Check if collision object is enabled.
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:47
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 std::string getName() const =0
Get the name of the contact manager.
virtual void setPairCollisionMarginData(const std::string &name1, const std::string &name2, double collision_margin)=0
Set the margin for a given contact pair.
virtual DiscreteContactManager::UPtr clone() const =0
Clone the manager.
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.
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
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 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_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
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 sphere
Definition: tesseract_geometry_unit.cpp:23