1#ifndef TESSERACT_COLLISION_COLLISION_OCTOMAP_MESH_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_OCTOMAP_MESH_UNIT_HPP
6#include <octomap/octomap.h>
7#include <console_bridge/console.h>
24 std::string
path = std::string(TESSERACT_SUPPORT_DIR) +
"/meshes/box_2m.bt";
25 auto ot = std::make_shared<octomap::OcTree>(path);
27 Eigen::Isometry3d octomap_pose;
28 octomap_pose.setIdentity();
32 obj1_shapes.push_back(dense_octomap);
33 obj1_poses.push_back(octomap_pose);
35 checker.addCollisionObject(
"octomap_link", 0, obj1_shapes, obj1_poses);
41 std::string(TESSERACT_SUPPORT_DIR) +
"/meshes/plane_4m.stl", Eigen::Vector3d(1, 1, 1),
true)[0];
43 Eigen::Isometry3d sphere_pose;
44 sphere_pose.setIdentity();
48 obj2_shapes.push_back(
sphere);
49 obj2_poses.push_back(sphere_pose);
51 checker.addCollisionObject(
"plane_link", 0, obj2_shapes, obj2_poses);
53 EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
54 for (
const auto& co : checker.getCollisionObjects())
56 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
57 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
58 for (
const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
60 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
77 std::vector<std::string>
active_links{
"octomap_link",
"plane_link" };
91 location[
"octomap_link"] = Eigen::Isometry3d::Identity();
92 location[
"plane_link"] = Eigen::Isometry3d::Identity();
93 location[
"plane_link"].translation() = Eigen::Vector3d(0, 0, 0);
104 const auto&
mesh = std::static_pointer_cast<const tesseract_geometry::Mesh>(
geom.at(0));
105 const auto& mesh_vertices =
mesh->getVertices();
106 const auto& mesh_triangles =
mesh->getFaces();
109 std::vector<Eigen::Vector3i> mesh_vertices_color(mesh_vertices->size(), Eigen::Vector3i(0, 128, 0));
114 if (r.link_names[0] !=
"plane_link")
117 mesh_vertices_color[
static_cast<std::size_t
>(
118 (*mesh_triangles)[4 * r.subshape_id[
static_cast<std::size_t
>(idx)] + 1])] = Eigen::Vector3i(255, 0, 0);
119 mesh_vertices_color[
static_cast<std::size_t
>(
120 (*mesh_triangles)[4 * r.subshape_id[
static_cast<std::size_t
>(idx)] + 2])] = Eigen::Vector3i(255, 0, 0);
121 mesh_vertices_color[
static_cast<std::size_t
>(
122 (*mesh_triangles)[4 * r.subshape_id[
static_cast<std::size_t
>(idx)] + 3])] = Eigen::Vector3i(255, 0, 0);
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
@ BOX
Definition: octree.h:50
EXPECT_NEAR(config.contact_manager_config.margin_data.getDefaultCollisionMargin(), 5, 1e-6)
tesseract_collision::ContactResultVector result_vector
Definition: collision_core_unit.cpp:410
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
This is a collection of common methods.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
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
bool writeSimplePlyFile(const std::string &path, const tesseract_common::VectorVector3d &vertices, const std::vector< Eigen::Vector3i > &vectices_color, const Eigen::VectorXi &faces, int num_faces)
Write a simple ply file given vertices and faces.
Definition: common.cpp:170
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
tesseract_common::fs::path file_path(__FILE__)
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
auto geom
Definition: tesseract_geometry_unit.cpp:51
auto sphere
Definition: tesseract_geometry_unit.cpp:23
auto mesh
Definition: tesseract_geometry_unit.cpp:25
tesseract_common::fs::path path
Definition: tesseract_srdf_unit.cpp:1992