1#ifndef TESSERACT_COLLISION_COLLISION_BOX_CYLINDER_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_BOX_CYLINDER_UNIT_HPP
17 Eigen::Isometry3d box_pose;
18 box_pose.setIdentity();
22 obj1_shapes.push_back(
box);
23 obj1_poses.push_back(box_pose);
25 checker.addCollisionObject(
"box_link", 0, obj1_shapes, obj1_poses);
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();
36 obj2_shapes.push_back(thin_box);
37 obj2_poses.push_back(thin_box_pose);
39 checker.addCollisionObject(
"thin_box_link", 0, obj2_shapes, obj2_poses,
false);
46 Eigen::Isometry3d cylinder_pose;
47 cylinder_pose.setIdentity();
52 obj3_poses.push_back(cylinder_pose);
54 checker.addCollisionObject(
"cylinder_link", 0, obj3_shapes, obj3_poses);
59 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
60 Eigen::Isometry3d remove_box_pose;
61 thin_box_pose.setIdentity();
65 obj4_shapes.push_back(remove_box);
66 obj4_poses.push_back(remove_box_pose);
68 checker.addCollisionObject(
"remove_box_link", 0, obj4_shapes, obj4_poses);
69 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
70 EXPECT_TRUE(checker.hasCollisionObject(
"remove_box_link"));
71 checker.removeCollisionObject(
"remove_box_link");
72 EXPECT_FALSE(checker.hasCollisionObject(
"remove_box_link"));
77 EXPECT_FALSE(checker.removeCollisionObject(
"link_does_not_exist"));
78 EXPECT_FALSE(checker.enableCollisionObject(
"link_does_not_exist"));
79 EXPECT_FALSE(checker.disableCollisionObject(
"link_does_not_exist"));
90 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
91 for (
const auto& co : checker.getCollisionObjects())
93 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
94 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
95 for (
const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
97 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
103inline void runTest(DiscreteContactManager& checker)
114 std::vector<std::string>
active_links{
"box_link",
"cylinder_link" };
116 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
119 EXPECT_TRUE(checker.getIsContactAllowedFn() ==
nullptr);
122 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
126 location[
"box_link"] = Eigen::Isometry3d::Identity();
127 location[
"cylinder_link"] = Eigen::Isometry3d::Identity();
128 location[
"cylinder_link"].translation()(0) = 0.2;
129 checker.setCollisionObjectsTransform(location);
132 ContactResultMap result;
143 std::vector<int> idx = { 0, 1, 1 };
166 location[
"cylinder_link"].translation() = Eigen::Vector3d(1, 0, 0);
171 std::vector<std::string> names = {
"cylinder_link" };
173 checker.setCollisionObjectsTransform(names, transforms);
186 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.251, 1e-5);
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))
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
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
auto cylinder
Definition: tesseract_geometry_unit.cpp:20
auto box
Definition: tesseract_geometry_unit.cpp:18