1 #ifndef TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP
7 #include <console_bridge/console.h>
21 inline void addCollisionObjects(DiscreteContactManager& checker,
bool use_convex_mesh =
false)
27 std::string path = locator.
locateResource(
"package://tesseract_support/meshes/blender_monkey.bt")->getFilePath();
28 auto ot = std::make_shared<octomap::OcTree>(path);
31 Eigen::Isometry3d octomap_pose;
32 octomap_pose.setIdentity();
36 obj1_shapes.push_back(dense_octomap);
37 obj1_poses.push_back(octomap_pose);
39 checker.addCollisionObject(
"octomap_link", 0, obj1_shapes, obj1_poses);
49 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
50 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
58 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
63 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
66 Eigen::Isometry3d sphere_pose;
67 sphere_pose.setIdentity();
71 obj2_shapes.push_back(sphere);
72 obj2_poses.push_back(sphere_pose);
74 checker.addCollisionObject(
"sphere_link", 0, obj2_shapes, obj2_poses);
76 EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
77 for (
const auto& co : checker.getCollisionObjects())
79 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
80 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
81 for (
const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
83 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
93 std::vector<std::string> active_links{
"octomap_link",
"sphere_link" };
96 EXPECT_TRUE(tesseract_common::isIdentical<std::string>(active_links, check_active_links,
false));
105 location[
"octomap_link"] = Eigen::Isometry3d::Identity();
106 location[
"sphere_link"] = Eigen::Isometry3d::Identity();
107 location[
"sphere_link"].translation() = Eigen::Vector3d(0, 0, 1);
151 #endif // TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP