1#ifndef TESSERACT_COLLISION_COLLISION_COMPOUND_COMPOUND_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_COMPOUND_COMPOUND_UNIT_HPP
6#include <octomap/octomap.h>
23 std::string
path = std::string(TESSERACT_SUPPORT_DIR) +
"/meshes/box_2m.bt";
24 auto ot = std::make_shared<octomap::OcTree>(
path);
26 Eigen::Isometry3d octomap_pose;
27 octomap_pose.setIdentity();
28 octomap_pose.translation() = Eigen::Vector3d(1.1, 0, 0);
32 obj1_shapes.push_back(dense_octomap);
33 obj1_poses.push_back(octomap_pose);
35 checker.addCollisionObject(
"octomap1_link", 0, obj1_shapes, obj1_poses);
40 auto ot_b = std::make_shared<octomap::OcTree>(
path);
43 Eigen::Isometry3d octomap_pose_b;
44 octomap_pose_b.setIdentity();
45 octomap_pose_b.translation() = Eigen::Vector3d(-1.1, 0, 0);
49 obj2_shapes.push_back(dense_octomap_b);
50 obj2_poses.push_back(octomap_pose_b);
52 checker.addCollisionObject(
"octomap2_link", 0, obj2_shapes, obj2_poses);
54 EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
55 const auto& co = checker.getCollisionObjects();
56 for (std::size_t i = 0; i < co.size(); ++i)
58 EXPECT_TRUE(checker.getCollisionObjectGeometries(co[i]).size() == 1);
59 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co[i]).size() == 1);
60 const auto& cgt = checker.getCollisionObjectGeometriesTransforms(co[i]);
77 std::vector<std::string>
active_links{
"octomap1_link",
"octomap2_link" };
89 location[
"octomap1_link"] = Eigen::Isometry3d::Identity();
90 location[
"octomap2_link"] = Eigen::Isometry3d::Identity();
112 std::vector<std::string>
active_links{
"octomap1_link" };
127 location[
"octomap2_link"] = Eigen::Isometry3d::Identity();
131 Eigen::Isometry3d start_pos, end_pos;
132 start_pos = Eigen::Isometry3d::Identity();
133 end_pos = Eigen::Isometry3d::Identity();
134 start_pos.translation() = Eigen::Vector3d(0, -2.0, 0);
135 end_pos.translation() = Eigen::Vector3d(0, 2.0, 0);
155 detail::addCollisionObjects<ContinuousContactManager>(checker);
158 detail::addCollisionObjects<ContinuousContactManager>(checker);
166inline void runTest(DiscreteContactManager& checker)
168 detail::addCollisionObjects<DiscreteContactManager>(checker);
171 detail::addCollisionObjects<DiscreteContactManager>(checker);
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
@ BOX
Definition: octree.h:50
Definition: polygon_mesh.h:46
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))
#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
void runTestCompound(DiscreteContactManager &checker)
Definition: collision_compound_compound_unit.hpp:72
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
tesseract_common::fs::path path
Definition: tesseract_srdf_unit.cpp:1992