1#ifndef TESSERACT_COLLISION_COLLISION_MESH_MESH_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_MESH_MESH_UNIT_HPP
19 auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
20 auto faces = std::make_shared<Eigen::VectorXi>();
22 loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) +
"/meshes/sphere_p25m.ply", *vertices, *
faces,
true);
25 sphere = std::make_shared<tesseract_geometry::Mesh>(vertices,
faces);
28 Eigen::Isometry3d sphere_pose;
29 sphere_pose.setIdentity();
33 obj1_shapes.push_back(
sphere);
34 obj1_poses.push_back(sphere_pose);
36 checker.addCollisionObject(
"sphere_link", 0, obj1_shapes, obj1_poses,
false);
37 checker.enableCollisionObject(
"sphere_link");
42 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
43 Eigen::Isometry3d thin_box_pose;
44 thin_box_pose.setIdentity();
48 obj2_shapes.push_back(thin_box);
49 obj2_poses.push_back(thin_box_pose);
51 checker.addCollisionObject(
"thin_box_link", 0, obj2_shapes, obj2_poses);
52 checker.disableCollisionObject(
"thin_box_link");
59 Eigen::Isometry3d sphere1_pose;
60 sphere1_pose.setIdentity();
64 obj3_shapes.push_back(sphere1);
65 obj3_poses.push_back(sphere1_pose);
67 checker.addCollisionObject(
"sphere1_link", 0, obj3_shapes, obj3_poses);
72 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
73 Eigen::Isometry3d remove_box_pose;
74 thin_box_pose.setIdentity();
78 obj4_shapes.push_back(remove_box);
79 obj4_poses.push_back(remove_box_pose);
81 checker.addCollisionObject(
"remove_box_link", 0, obj4_shapes, obj4_poses);
82 EXPECT_TRUE(checker.getCollisionObjects().size() == 4);
83 EXPECT_TRUE(checker.hasCollisionObject(
"remove_box_link"));
84 checker.removeCollisionObject(
"remove_box_link");
85 EXPECT_FALSE(checker.hasCollisionObject(
"remove_box_link"));
90 EXPECT_FALSE(checker.removeCollisionObject(
"link_does_not_exist"));
91 EXPECT_FALSE(checker.enableCollisionObject(
"link_does_not_exist"));
92 EXPECT_FALSE(checker.disableCollisionObject(
"link_does_not_exist"));
103 EXPECT_TRUE(checker.getCollisionObjects().size() == 3);
104 for (
const auto& co : checker.getCollisionObjects())
106 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
107 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
108 for (
const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
110 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
116inline void runTest(DiscreteContactManager& checker)
127 std::vector<std::string>
active_links{
"sphere_link",
"sphere1_link" };
129 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
132 EXPECT_TRUE(checker.getIsContactAllowedFn() ==
nullptr);
134 checker.setDefaultCollisionMarginData(0);
135 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.0, 1e-5);
139 location[
"sphere_link"] = Eigen::Isometry3d::Identity();
140 location[
"sphere1_link"] = Eigen::Isometry3d::Identity();
141 location[
"sphere1_link"].translation()(0) = 0.2;
142 checker.setCollisionObjectsTransform(location);
145 ContactResultMap result;
156 location[
"sphere1_link"].translation() = Eigen::Vector3d(1, 0, 0);
159 checker.setCollisionObjectsTransform(location);
173 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.55, 1e-5);
180 std::vector<int> idx = { 0, 1, 1 };
189 EXPECT_LT(std::abs(std::acos((idx[2] *
result_vector[0].
normal).dot(Eigen::Vector3d(1, 0, 0)))), 0.00001);
194 location[
"sphere1_link"].translation() = Eigen::Vector3d(0, 1, 0);
200 checker.setCollisionObjectsTransform(
"sphere1_link", location[
"sphere1_link"]);
202 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.55, 1e-5);
218 EXPECT_LT(std::abs(std::acos((idx[2] *
result_vector[0].
normal).dot(Eigen::Vector3d(0, 1, 0)))), 0.00001);
std::shared_ptr< Mesh > Ptr
Definition: mesh.h:52
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 a collection of common methods.
EXPECT_GT(m.m.condition, 1e+20)
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
int loadSimplePlyFile(const std::string &path, tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, bool triangles_only=false)
Loads a simple ply file given a path.
Definition: common.cpp:285
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
std::shared_ptr< const Eigen::VectorXi > faces
Definition: tesseract_geometry_unit.cpp:16
auto sphere
Definition: tesseract_geometry_unit.cpp:23