1#ifndef TESSERACT_COLLISION_CONTACT_MANAGER_CONFIG_UNIT_H
2#define TESSERACT_COLLISION_CONTACT_MANAGER_CONFIG_UNIT_H
20 Eigen::Isometry3d sphere_pose;
21 sphere_pose.setIdentity();
25 obj1_shapes.push_back(
sphere);
26 obj1_poses.push_back(sphere_pose);
28 checker.addCollisionObject(
"sphere_link", 0, obj1_shapes, obj1_poses);
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();
39 obj2_shapes.push_back(thin_box);
40 obj2_poses.push_back(thin_box_pose);
42 checker.addCollisionObject(
"thin_box_link", 0, obj2_shapes, obj2_poses);
50 Eigen::Isometry3d sphere1_pose;
51 sphere1_pose.setIdentity();
55 obj3_shapes.push_back(sphere1);
56 obj3_poses.push_back(sphere1_pose);
58 checker.addCollisionObject(
"sphere1_link", 0, obj3_shapes, obj3_poses);
68 Eigen::Isometry3d sphere_pose;
69 sphere_pose.setIdentity();
70 sphere_pose.translation()[2] = 0.25;
74 obj1_shapes.push_back(
sphere);
75 obj1_poses.push_back(sphere_pose);
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"));
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();
91 obj2_shapes.push_back(thin_box);
92 obj2_poses.push_back(thin_box_pose);
94 checker.addCollisionObject(
"thin_box_link", 0, obj2_shapes, obj2_poses);
102 Eigen::Isometry3d sphere1_pose;
103 sphere1_pose.setIdentity();
104 sphere1_pose.translation()[2] = 0.25;
108 obj3_shapes.push_back(sphere1);
109 obj3_poses.push_back(sphere1_pose);
111 checker.addCollisionObject(
"sphere1_link", 0, obj3_shapes, obj3_poses);
112 EXPECT_TRUE(checker.isCollisionObjectEnabled(
"sphere1_link"));
117inline void runTest(DiscreteContactManager& checker)
125 std::vector<std::string>
active_links{
"sphere_link",
"sphere1_link" };
127 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
130 EXPECT_TRUE(checker.getIsContactAllowedFn() ==
nullptr);
132 checker.setDefaultCollisionMarginData(0.5);
133 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
134 EXPECT_TRUE(checker.isCollisionObjectEnabled(
"thin_box_link"));
136 ContactManagerConfig
config(0.1);
137 config.margin_data_override_type = CollisionMarginOverrideType::NONE;
138 config.modify_object_enabled[
"thin_box_link"] =
false;
140 checker.applyContactManagerConfig(
config);
141 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
142 EXPECT_FALSE(checker.isCollisionObjectEnabled(
"thin_box_link"));
144 config.margin_data_override_type = CollisionMarginOverrideType::OVERRIDE_DEFAULT_MARGIN;
145 checker.applyContactManagerConfig(
config);
146 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
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);
156 ContactResultMap result;
165 std::vector<int> idx = { 0, 1, 1 };
184 location[
"sphere1_link"].translation() = Eigen::Vector3d(1, 0, 0);
187 checker.setCollisionObjectsTransform(
"sphere1_link", location[
"sphere1_link"]);
200 config = ContactManagerConfig(0.52);
201 checker.applyContactManagerConfig(
config);
202 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.52, 1e-5);
225inline void runTest(ContinuousContactManager& checker)
233 std::vector<std::string>
active_links{
"sphere_link",
"sphere1_link" };
235 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
238 EXPECT_TRUE(checker.getIsContactAllowedFn() ==
nullptr);
240 checker.setDefaultCollisionMarginData(0.5);
241 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
242 EXPECT_TRUE(checker.isCollisionObjectEnabled(
"thin_box_link"));
244 ContactManagerConfig
config(0.1);
245 config.margin_data_override_type = CollisionMarginOverrideType::NONE;
246 config.modify_object_enabled[
"thin_box_link"] =
false;
248 checker.applyContactManagerConfig(
config);
249 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.5, 1e-5);
250 EXPECT_FALSE(checker.isCollisionObjectEnabled(
"thin_box_link"));
252 config.margin_data_override_type = CollisionMarginOverrideType::OVERRIDE_DEFAULT_MARGIN;
253 checker.applyContactManagerConfig(
config);
254 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
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;
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;
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;
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;
276 checker.setCollisionObjectsTransform(location_start, location_end);
279 ContactResultMap result;
288 std::vector<int> idx = { 0, 1, 1 };
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;
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;
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;
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;
347 checker.setCollisionObjectsTransform(location_start, location_end);
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.
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