collision_octomap_sphere_unit.hpp
Go to the documentation of this file.
1 #ifndef TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP
3 
6 #include <octomap/octomap.h>
7 #include <console_bridge/console.h>
8 #include <chrono>
10 
16 
18 {
19 namespace detail
20 {
21 inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex_mesh = false)
22 {
24  // Add Octomap
27  std::string path = locator.locateResource("package://tesseract_support/meshes/blender_monkey.bt")->getFilePath();
28  auto ot = std::make_shared<octomap::OcTree>(path);
29  CollisionShapePtr dense_octomap =
30  std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::BOX);
31  Eigen::Isometry3d octomap_pose;
32  octomap_pose.setIdentity();
33 
34  CollisionShapesConst obj1_shapes;
36  obj1_shapes.push_back(dense_octomap);
37  obj1_poses.push_back(octomap_pose);
38 
39  checker.addCollisionObject("octomap_link", 0, obj1_shapes, obj1_poses);
40 
42  // Add sphere to checker. If use_convex_mesh = true then this
43  // sphere will be added as a convex hull mesh.
45  CollisionShapePtr sphere;
46 
47  if (use_convex_mesh)
48  {
49  auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
50  auto mesh_faces = std::make_shared<Eigen::VectorXi>();
51  EXPECT_GT(
52  loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
53  *mesh_vertices,
54  *mesh_faces,
55  true),
56  0);
57 
58  auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
59  sphere = makeConvexMesh(*mesh);
60  }
61  else
62  {
63  sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
64  }
65 
66  Eigen::Isometry3d sphere_pose;
67  sphere_pose.setIdentity();
68 
69  CollisionShapesConst obj2_shapes;
71  obj2_shapes.push_back(sphere);
72  obj2_poses.push_back(sphere_pose);
73 
74  checker.addCollisionObject("sphere_link", 0, obj2_shapes, obj2_poses);
75 
76  EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
77  for (const auto& co : checker.getCollisionObjects())
78  {
79  EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
80  EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
81  for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
82  {
83  EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
84  }
85  }
86 }
87 
88 inline void runTestTyped(DiscreteContactManager& checker, double tol, ContactTestType test_type)
89 {
91  // Test when object is in collision
93  std::vector<std::string> active_links{ "octomap_link", "sphere_link" };
94  checker.setActiveCollisionObjects(active_links);
95  std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
96  EXPECT_TRUE(tesseract_common::isIdentical<std::string>(active_links, check_active_links, false));
97 
98  EXPECT_TRUE(checker.getContactAllowedValidator() == nullptr);
99 
100  checker.setDefaultCollisionMargin(0.1);
102 
103  // Set the collision object transforms
105  location["octomap_link"] = Eigen::Isometry3d::Identity();
106  location["sphere_link"] = Eigen::Isometry3d::Identity();
107  location["sphere_link"].translation() = Eigen::Vector3d(0, 0, 1);
108  checker.setCollisionObjectsTransform(location);
109 
110  // Perform collision check
111  ContactResultMap result;
112  checker.contactTest(result, ContactRequest(test_type));
113 
114  ContactResultVector result_vector;
115  result.flattenMoveResults(result_vector);
116 
117  EXPECT_TRUE(!result_vector.empty());
118  if (test_type == ContactTestType::CLOSEST)
119  {
120  EXPECT_TRUE(result_vector.size() == 1);
121  EXPECT_NEAR(result_vector[0].distance, -0.25, tol);
122  }
123  else if (test_type == ContactTestType::FIRST)
124  {
125  EXPECT_TRUE(result_vector.size() == 1);
126  EXPECT_TRUE(result_vector[0].distance < 0.1);
127  }
128  else
129  {
130  EXPECT_FALSE(result_vector.empty());
131  EXPECT_TRUE(result_vector[0].distance < 0.1);
132  }
133 }
134 } // namespace detail
135 
136 inline void runTest(DiscreteContactManager& checker, double tol, bool use_convex_mesh)
137 {
138  // Add collision objects
139  detail::addCollisionObjects(checker, use_convex_mesh);
140 
141  // Call it again to test adding same object
142  detail::addCollisionObjects(checker, use_convex_mesh);
143 
147 }
148 
149 } // namespace tesseract_collision::test_suite
150 
151 #endif // TESSERACT_COLLISION_COLLISION_OCTOMAP_SPHERE_UNIT_HPP
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_common::CollisionMarginData::getMaxCollisionMargin
double getMaxCollisionMargin() const
tesseract_collision::DiscreteContactManager::getActiveCollisionObjects
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
tesseract_collision::DiscreteContactManager::setDefaultCollisionMargin
virtual void setDefaultCollisionMargin(double default_collision_margin)=0
Set the default collision margin.
tesseract_collision::test_suite::detail::addCollisionObjects
void addCollisionObjects(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:11
resource_locator.h
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_collision::test_suite::detail::runTestTyped
void runTestTyped(DiscreteContactManager &checker, ContactTestType test_type)
Definition: collision_box_box_unit.hpp:128
discrete_contact_manager.h
This is the discrete contact manager base class.
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::ContactResultVector
tesseract_common::AlignedVector< ContactResult > ContactResultVector
Definition: types.h:136
tesseract_collision::DiscreteContactManager::getContactAllowedValidator
virtual std::shared_ptr< const tesseract_common::ContactAllowedValidator > getContactAllowedValidator() const =0
Get the active function for determining if two links are allowed to be in collision.
tesseract_collision::DiscreteContactManager
Definition: discrete_contact_manager.h:41
tesseract_collision::loadSimplePlyFile
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:289
convex_hull_utils.h
This is a collection of common methods.
EXPECT_TRUE
#define EXPECT_TRUE(args)
tesseract_collision::ContactResultMap::flattenMoveResults
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:270
geometries.h
tesseract_collision::makeConvexMesh
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh(const tesseract_geometry::Mesh &mesh)
Definition: convex_hull_utils.cpp:113
tesseract_collision::test_suite
Definition: large_dataset_benchmarks.hpp:17
tesseract_collision::ContactResultMap
This structure hold contact results for link pairs.
Definition: types.h:155
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
tesseract_collision::DiscreteContactManager::contactTest
virtual void contactTest(ContactResultMap &collisions, const ContactRequest &request)=0
Perform a contact test for all objects based.
tesseract_collision::DiscreteContactManager::setCollisionObjectsTransform
virtual void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)=0
Set a single collision object's transforms.
tesseract_collision::CollisionShapePtr
std::shared_ptr< tesseract_geometry::Geometry > CollisionShapePtr
Definition: types.h:50
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
tesseract_common::GeneralResourceLocator::locateResource
std::shared_ptr< Resource > locateResource(const std::string &url) const override
common.h
This is a collection of common methods.
tesseract_collision::ContactTestType::FIRST
@ FIRST
tesseract_collision::ContactTestType
ContactTestType
Definition: types.h:66
tesseract_collision::test_suite::runTest
void runTest(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:111
tesseract_collision::DiscreteContactManager::setActiveCollisionObjects
virtual void setActiveCollisionObjects(const std::vector< std::string > &names)=0
Set which collision objects can move.
octomap.h
tesseract_common::GeneralResourceLocator
tesseract_collision::DiscreteContactManager::getCollisionMarginData
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
macros.h
tesseract_collision::ContactTestType::ALL
@ ALL
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300
EXPECT_FALSE
#define EXPECT_FALSE(args)
tesseract_collision::ContactTestType::CLOSEST
@ CLOSEST
tesseract_geometry::OctreeSubType::BOX
@ BOX


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52