collision_compound_compound_unit.hpp
Go to the documentation of this file.
1 #ifndef TESSERACT_COLLISION_COLLISION_COMPOUND_COMPOUND_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_COMPOUND_COMPOUND_UNIT_HPP
3 
6 #include <octomap/octomap.h>
8 
13 
15 {
16 namespace detail
17 {
18 template <class T>
19 inline void addCollisionObjects(T& checker)
20 {
22  // Add Octomap
25  std::string path = locator.locateResource("package://tesseract_support/meshes/box_2m.bt")->getFilePath();
26  auto ot = std::make_shared<octomap::OcTree>(path);
27  CollisionShapePtr dense_octomap =
28  std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::BOX);
29  Eigen::Isometry3d octomap_pose;
30  octomap_pose.setIdentity();
31  octomap_pose.translation() = Eigen::Vector3d(1.1, 0, 0);
32 
33  CollisionShapesConst obj1_shapes;
35  obj1_shapes.push_back(dense_octomap);
36  obj1_poses.push_back(octomap_pose);
37 
38  checker.addCollisionObject("octomap1_link", 0, obj1_shapes, obj1_poses);
39 
41  // Add second octomap
43  auto ot_b = std::make_shared<octomap::OcTree>(path);
44  CollisionShapePtr dense_octomap_b =
45  std::make_shared<tesseract_geometry::Octree>(ot_b, tesseract_geometry::OctreeSubType::BOX);
46  Eigen::Isometry3d octomap_pose_b;
47  octomap_pose_b.setIdentity();
48  octomap_pose_b.translation() = Eigen::Vector3d(-1.1, 0, 0);
49 
50  CollisionShapesConst obj2_shapes;
52  obj2_shapes.push_back(dense_octomap_b);
53  obj2_poses.push_back(octomap_pose_b);
54 
55  checker.addCollisionObject("octomap2_link", 0, obj2_shapes, obj2_poses);
56 
57  EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
58  const auto& co = checker.getCollisionObjects();
59  for (std::size_t i = 0; i < co.size(); ++i)
60  {
61  EXPECT_TRUE(checker.getCollisionObjectGeometries(co[i]).size() == 1);
62  EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co[i]).size() == 1);
63  const auto& cgt = checker.getCollisionObjectGeometriesTransforms(co[i]);
64  if (i == 0)
65  {
66  EXPECT_TRUE(cgt[0].isApprox(octomap_pose, 1e-5));
67  }
68  else
69  {
70  EXPECT_TRUE(cgt[0].isApprox(octomap_pose_b, 1e-5));
71  }
72  }
73 }
74 
76 {
78  // Test when object is in collision
80  std::vector<std::string> active_links{ "octomap1_link", "octomap2_link" };
81  checker.setActiveCollisionObjects(active_links);
82  std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
83  EXPECT_TRUE(tesseract_common::isIdentical<std::string>(active_links, check_active_links, false));
84 
85  EXPECT_TRUE(checker.getContactAllowedValidator() == nullptr);
86 
89 
90  // Set the collision object transforms
92  location["octomap1_link"] = Eigen::Isometry3d::Identity();
93  location["octomap2_link"] = Eigen::Isometry3d::Identity();
94  checker.setCollisionObjectsTransform(location);
95 
96  // Perform collision check
97  ContactResultMap result;
99 
100  ContactResultVector result_vector;
101  result.flattenMoveResults(result_vector);
102 
103  EXPECT_TRUE(!result_vector.empty());
104  for (const auto& cr : result_vector)
105  {
106  EXPECT_NEAR(cr.distance, 0.20, 0.001);
107  }
108 }
109 
111 {
113  // Test when object is in collision
115  std::vector<std::string> active_links{ "octomap1_link" };
116  checker.setActiveCollisionObjects(active_links);
117  std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
118  EXPECT_TRUE(tesseract_common::isIdentical<std::string>(active_links, check_active_links, false));
119 
120  EXPECT_TRUE(checker.getContactAllowedValidator() == nullptr);
121 
124 
125  // Set Pair
126  checker.setCollisionMarginPair("octomap1_link", "octomap2_link", 0.25);
127 
128  // Set the collision object transforms
130  location["octomap2_link"] = Eigen::Isometry3d::Identity();
131  checker.setCollisionObjectsTransform(location);
132 
133  // Set the collision object transforms
134  Eigen::Isometry3d start_pos, end_pos;
135  start_pos = Eigen::Isometry3d::Identity();
136  end_pos = Eigen::Isometry3d::Identity();
137  start_pos.translation() = Eigen::Vector3d(0, -2.0, 0);
138  end_pos.translation() = Eigen::Vector3d(0, 2.0, 0);
139  checker.setCollisionObjectsTransform("octomap1_link", start_pos, end_pos);
140 
141  // Perform collision check
142  ContactResultMap result;
144 
145  ContactResultVector result_vector;
146  result.flattenCopyResults(result_vector);
147 
148  EXPECT_TRUE(!result_vector.empty());
149  for (const auto& cr : result_vector)
150  {
151  EXPECT_NEAR(cr.distance, 0.20, 0.001);
152  }
153 }
154 } // namespace detail
155 
156 inline void runTest(ContinuousContactManager& checker)
157 {
158  detail::addCollisionObjects<ContinuousContactManager>(checker);
159 
160  // Call it again to test adding same object
161  detail::addCollisionObjects<ContinuousContactManager>(checker);
162 
163  detail::runTestCompound(checker);
164 
165  ContinuousContactManager::Ptr cloned_checker = checker.clone();
166  detail::runTestCompound(*cloned_checker);
167 }
168 
169 inline void runTest(DiscreteContactManager& checker)
170 {
171  detail::addCollisionObjects<DiscreteContactManager>(checker);
172 
173  // Call it again to test adding same object
174  detail::addCollisionObjects<DiscreteContactManager>(checker);
175 
176  detail::runTestCompound(checker);
177 
178  DiscreteContactManager::Ptr cloned_checker = checker.clone();
179  detail::runTestCompound(*cloned_checker);
180 }
181 } // namespace tesseract_collision::test_suite
182 #endif // TESSERACT_COLLISION_COLLISION_COMPOUND_COMPOUND_UNIT_HPP
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_common::CollisionMarginData::getMaxCollisionMargin
double getMaxCollisionMargin() const
tesseract_collision::ContinuousContactManager::Ptr
std::shared_ptr< ContinuousContactManager > Ptr
Definition: continuous_contact_manager.h:46
tesseract_collision::ContinuousContactManager::clone
virtual ContinuousContactManager::UPtr clone() const =0
Clone the manager.
tesseract_collision::DiscreteContactManager::getActiveCollisionObjects
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
tesseract_collision::DiscreteContactManager::setCollisionMarginData
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data)=0
Set the contact distance threshold.
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
discrete_contact_manager.h
This is the discrete contact manager base class.
tesseract_collision::ContinuousContactManager::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::ContinuousContactManager::getActiveCollisionObjects
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
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
EXPECT_TRUE
#define EXPECT_TRUE(args)
tesseract_collision::ContactResultMap::flattenMoveResults
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:270
geometries.h
tesseract_collision::test_suite::detail::runTestCompound
void runTestCompound(DiscreteContactManager &checker)
Definition: collision_compound_compound_unit.hpp:75
tesseract_collision::ContinuousContactManager
Definition: continuous_contact_manager.h:41
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::ContinuousContactManager::setCollisionObjectsTransform
virtual void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)=0
Set a single static collision object's tansforms.
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
tesseract_collision::ContinuousContactManager::setCollisionMarginPair
virtual void setCollisionMarginPair(const std::string &name1, const std::string &name2, double collision_margin)=0
Set the margin for a given contact pair.
tesseract_common::GeneralResourceLocator::locateResource
std::shared_ptr< Resource > locateResource(const std::string &url) const override
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::ContinuousContactManager::setCollisionMarginData
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data)=0
Set the contact distance threshold.
tesseract_collision::DiscreteContactManager::getCollisionMarginData
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
macros.h
tesseract_collision::ContinuousContactManager::contactTest
virtual void contactTest(ContactResultMap &collisions, const ContactRequest &request)=0
Perform a contact test for all objects based.
tesseract_collision::ContactTestType::ALL
@ ALL
tesseract_collision::ContactResultMap::flattenCopyResults
void flattenCopyResults(ContactResultVector &v) const
Definition: types.cpp:282
tesseract_collision::DiscreteContactManager::Ptr
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:48
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300
tesseract_collision::ContinuousContactManager::setActiveCollisionObjects
virtual void setActiveCollisionObjects(const std::vector< std::string > &names)=0
Set which collision objects can move.
continuous_contact_manager.h
This is the continuous contact manager base class.
tesseract_collision::ContinuousContactManager::getCollisionMarginData
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
tesseract_geometry::OctreeSubType::BOX
@ BOX
tesseract_collision::CollisionMarginData
tesseract_common::CollisionMarginData CollisionMarginData
Definition: types.h:52


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