1#ifndef TESSERACT_COLLISION_COLLISION_CLONE_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_CLONE_UNIT_HPP
18 Eigen::Isometry3d sphere_pose;
19 sphere_pose.setIdentity();
23 obj1_shapes.push_back(
sphere);
24 obj1_poses.push_back(sphere_pose);
26 checker.addCollisionObject(
"sphere_link", 0, obj1_shapes, obj1_poses);
27 EXPECT_TRUE(checker.isCollisionObjectEnabled(
"sphere_link"));
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();
38 obj2_shapes.push_back(thin_box);
39 obj2_poses.push_back(thin_box_pose);
41 checker.addCollisionObject(
"thin_box_link", 0, obj2_shapes, obj2_poses,
false);
42 EXPECT_FALSE(checker.isCollisionObjectEnabled(
"thin_box_link"));
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);
59 EXPECT_TRUE(checker.isCollisionObjectEnabled(
"sphere1_link"));
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();
70 obj4_shapes.push_back(remove_box);
71 obj4_poses.push_back(remove_box_pose);
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"));
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"));
97 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
98 for (
const auto& co : checker.getCollisionObjects())
100 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
101 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
102 for (
const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
104 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
125 std::vector<std::string>
active_links{
"sphere_link",
"sphere1_link" };
140 location[
"sphere_link"] = Eigen::Isometry3d::Identity();
141 location[
"sphere1_link"] = Eigen::Isometry3d::Identity();
142 location[
"sphere1_link"].translation()(0) = 0.2;
152 std::vector<int> idx = { 0, 1, 1 };
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 };
169 EXPECT_FALSE(cloned_checker->isCollisionObjectEnabled(
"thin_box_link"));
173 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[0])][0],
176 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[0])][1],
179 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[0])][2],
182 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[1])][0],
185 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[1])][1],
188 cloned_result_vector[0].
nearest_points[
static_cast<size_t>(cloned_idx[1])][2],
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))
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 sphere
Definition: tesseract_geometry_unit.cpp:23