Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
collision_box_capsule_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_COLLISION_BOX_CAPSULE_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_BOX_CAPSULE_UNIT_HPP
3
6
8{
9namespace detail
10{
12{
14 // Add box to checker
16 CollisionShapePtr box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
17 Eigen::Isometry3d box_pose;
18 box_pose.setIdentity();
19
20 CollisionShapesConst obj1_shapes;
22 obj1_shapes.push_back(box);
23 obj1_poses.push_back(box_pose);
24
25 checker.addCollisionObject("box_link", 0, obj1_shapes, obj1_poses);
26
28 // Add thin box to checker which is disabled
30 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
31 Eigen::Isometry3d thin_box_pose;
32 thin_box_pose.setIdentity();
33
34 CollisionShapesConst obj2_shapes;
36 obj2_shapes.push_back(thin_box);
37 obj2_poses.push_back(thin_box_pose);
38
39 checker.addCollisionObject("thin_box_link", 0, obj2_shapes, obj2_poses, false);
40
42 // Add capsule to checker.
44 CollisionShapePtr capsule = std::make_shared<tesseract_geometry::Capsule>(0.25, 0.25);
45 Eigen::Isometry3d capsule_pose;
46 capsule_pose.setIdentity();
47
48 CollisionShapesConst obj3_shapes;
50 obj3_shapes.push_back(capsule);
51 obj3_poses.push_back(capsule_pose);
52
53 checker.addCollisionObject("capsule_link", 0, obj3_shapes, obj3_poses);
54
56 // Add box and remove
58 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
59 Eigen::Isometry3d remove_box_pose;
60 thin_box_pose.setIdentity();
61
62 CollisionShapesConst obj4_shapes;
64 obj4_shapes.push_back(remove_box);
65 obj4_poses.push_back(remove_box_pose);
66
67 checker.addCollisionObject("remove_box_link", 0, obj4_shapes, obj4_poses);
68 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
69 EXPECT_TRUE(checker.hasCollisionObject("remove_box_link"));
70 checker.removeCollisionObject("remove_box_link");
71 EXPECT_FALSE(checker.hasCollisionObject("remove_box_link"));
72
74 // Try functions on a link that does not exist
76 EXPECT_FALSE(checker.removeCollisionObject("link_does_not_exist"));
77 EXPECT_FALSE(checker.enableCollisionObject("link_does_not_exist"));
78 EXPECT_FALSE(checker.disableCollisionObject("link_does_not_exist"));
79
81 // Try to add empty Collision Object
85
87 // Check sizes
89 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
90 for (const auto& co : checker.getCollisionObjects())
91 {
92 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
94 for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
95 {
96 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
97 }
98 }
99}
100} // namespace detail
101
102inline void runTest(DiscreteContactManager& checker)
103{
104 // Add collision objects
106
107 // Call it again to test adding same object
109
111 // Test when object is in collision
113 std::vector<std::string> active_links{ "box_link", "capsule_link" };
115 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
117
118 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
119
122
123 // Set the collision object transforms
125 location["box_link"] = Eigen::Isometry3d::Identity();
126 location["capsule_link"] = Eigen::Isometry3d::Identity();
127 location["capsule_link"].translation()(0) = 0.2;
128 checker.setCollisionObjectsTransform(location);
129
130 // Perform collision check
131 ContactResultMap result;
133
136
137 EXPECT_TRUE(!result_vector.empty());
138 EXPECT_NEAR(result_vector[0].distance, -0.55, 0.0001);
141
142 std::vector<int> idx = { 0, 1, 1 };
143 if (result_vector[0].link_names[0] != "box_link")
144 idx = { 1, 0, -1 };
145
147 {
149 EXPECT_FALSE(std::abs(result_vector[0].nearest_points[0][0] - (0.5)) > 0.001 &&
150 std::abs(result_vector[0].nearest_points[0][0] - (-0.05)) > 0.001);
151 }
152 else
153 {
154 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][0], 0.5, 0.001);
155 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][0], -0.05, 0.001);
156 }
157
158 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 1.0, 0.001);
159 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.001);
160 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 0.0, 0.001);
161
163 // Test object is out side the contact distance
165 location["capsule_link"].translation() = Eigen::Vector3d(0, 0, 1);
166 result.clear();
167 result_vector.clear();
168 checker.setCollisionObjectsTransform(location);
169
172
173 EXPECT_TRUE(result_vector.empty());
174
176 // Test object inside the contact distance
178 result.clear();
179 result_vector.clear();
180
185
186 EXPECT_TRUE(!result_vector.empty());
187 EXPECT_NEAR(result_vector[0].distance, 0.125, 0.001);
190
191 idx = { 0, 1, 1 };
192 if (result_vector[0].link_names[0] != "box_link")
193 idx = { 1, 0, -1 };
194
196 {
198 EXPECT_FALSE(std::abs(result_vector[0].nearest_points[0][2] - (0.5)) > 0.001 &&
199 std::abs(result_vector[0].nearest_points[0][2] - (0.625)) > 0.001);
200 }
201 else
202 {
203 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[0])][2], 0.5, 0.001);
204 EXPECT_NEAR(result_vector[0].nearest_points[static_cast<size_t>(idx[1])][2], 0.625, 0.001);
205 }
206
207 EXPECT_NEAR(result_vector[0].normal[0], idx[2] * 0.0, 0.0011); // FCL Required the bump in tolerance
208 EXPECT_NEAR(result_vector[0].normal[1], idx[2] * 0.0, 0.0011); // FCL Required the bump in tolerance
209 EXPECT_NEAR(result_vector[0].normal[2], idx[2] * 1.0, 0.0011); // FCL Required the bump in tolerance
210}
211
212} // namespace tesseract_collision::test_suite
213
214#endif // TESSERACT_COLLISION_COLLISION_BOX_CAPSULE_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 void setDefaultCollisionMarginData(double default_collision_margin)=0
Set the default collision margin.
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.
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
results single_contact_point
Definition: collision_core_unit.cpp:161
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 box
Definition: tesseract_geometry_unit.cpp:18
auto capsule
Definition: tesseract_geometry_unit.cpp:21