collision_large_dataset_unit.hpp
Go to the documentation of this file.
1 #ifndef TESSERACT_COLLISION_COLLISION_LARGE_DATASET_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_LARGE_DATASET_UNIT_HPP
3 
6 #include <console_bridge/console.h>
7 #include <chrono>
9 
15 
17 {
18 inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = false, int num_interations = 10)
19 {
20  // Add Meshed Sphere to checker
21  CollisionShapePtr sphere;
22 
23  if (use_convex_mesh)
24  {
25  auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
26  auto mesh_faces = std::make_shared<Eigen::VectorXi>();
28  EXPECT_GT(
29  loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
30  *mesh_vertices,
31  *mesh_faces,
32  true),
33  0);
34 
35  auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
36  sphere = makeConvexMesh(*mesh);
37  }
38  else
39  {
40  sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
41  }
42 
43  double delta = 0.55;
44 
45  std::size_t t = 5; // Because of unit test runtime this was reduced from 10 to 5.
46  std::vector<std::string> link_names;
48  for (std::size_t x = 0; x < t; ++x)
49  {
50  for (std::size_t y = 0; y < t; ++y)
51  {
52  for (std::size_t z = 0; z < t; ++z)
53  {
54  CollisionShapesConst obj3_shapes;
56  Eigen::Isometry3d sphere_pose;
57  sphere_pose.setIdentity();
58 
59  obj3_shapes.push_back(CollisionShapePtr(sphere->clone()));
60  obj3_poses.push_back(sphere_pose);
61 
62  link_names.push_back("sphere_link_" + std::to_string(x) + std::to_string(y) + std::to_string(z));
63 
64  location[link_names.back()] = sphere_pose;
65  location[link_names.back()].translation() = Eigen::Vector3d(
66  static_cast<double>(x) * delta, static_cast<double>(y) * delta, static_cast<double>(z) * delta);
67  checker.addCollisionObject(link_names.back(), 0, obj3_shapes, obj3_poses);
68  }
69  }
70  }
71 
72  // Check if they are in collision
73  checker.setActiveCollisionObjects(link_names);
74  std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
75  EXPECT_TRUE(tesseract_common::isIdentical<std::string>(link_names, check_active_links, false));
76 
77  EXPECT_TRUE(checker.getContactAllowedValidator() == nullptr);
78 
81  checker.setCollisionObjectsTransform(location);
82 
83  ContactResultMap result;
84  ContactResultVector result_vector;
85 
86  auto start_time = std::chrono::high_resolution_clock::now();
87  num_interations = 1;
88  for (auto i = 0; i < num_interations; ++i)
89  {
90  result.clear();
91  result_vector.clear();
93  result.flattenMoveResults(result_vector);
94 
95  if (result_vector.size() != 300)
96  for (const auto& result : result_vector)
97  std::cout << result.link_names[0] << "," << result.link_names[1] << "," << result.distance << "\n";
98 
99  EXPECT_EQ(result_vector.size(), 300);
100  }
101  auto end_time = std::chrono::high_resolution_clock::now();
102 
103  CONSOLE_BRIDGE_logInform("DT: %f ms", std::chrono::duration<double, std::milli>(end_time - start_time).count());
104 }
105 } // namespace tesseract_collision::test_suite
106 #endif // TESSERACT_COLLISION_COLLISION_LARGE_DATASET_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::setCollisionMarginData
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data)=0
Set the contact distance threshold.
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_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::ContactResultVector
tesseract_common::AlignedVector< ContactResult > ContactResultVector
Definition: types.h:136
tesseract_collision::ContactResultMap::clear
void clear()
This is a consurvative clear.
Definition: types.cpp:231
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::addCollisionObject
virtual bool addCollisionObject(const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)=0
Add a object to the checker.
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_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::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.
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_EQ
#define EXPECT_EQ(a, b)
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