Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
large_dataset_benchmarks.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_LARGE_DATASET_BENCHMARKS_HPP
2#define TESSERACT_COLLISION_LARGE_DATASET_BENCHMARKS_HPP
3
6#include <chrono>
8
13
14namespace tesseract_collision
15{
16namespace test_suite
17{
20static void BM_LARGE_DATASET_MULTILINK(benchmark::State& state,
21 DiscreteContactManager::Ptr checker, // NOLINT
22 int edge_size,
24{
25 // Add Meshed Sphere to checker
27
28 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
29 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
30 loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);
31
32 switch (type)
33 {
35 {
36 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
38 break;
39 }
41 {
42 sphere = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
43 break;
44 }
46 {
47 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
48 break;
49 }
50 default:
51 {
52 throw(std::runtime_error("Invalid geometry type"));
53 break;
54 }
55 }
56
57 double delta = 0.55;
58
59 std::vector<std::string> link_names;
61 for (int x = 0; x < edge_size; ++x)
62 {
63 for (int y = 0; y < edge_size; ++y)
64 {
65 for (int z = 0; z < edge_size; ++z)
66 {
67 CollisionShapesConst obj3_shapes;
69 Eigen::Isometry3d sphere_pose;
70 sphere_pose.setIdentity();
71
72 obj3_shapes.push_back(CollisionShapePtr(sphere->clone()));
73 obj3_poses.push_back(sphere_pose);
74
75 link_names.push_back("sphere_link_" + std::to_string(x) + std::to_string(y) + std::to_string(z));
76
77 location[link_names.back()] = sphere_pose;
78 location[link_names.back()].translation() = Eigen::Vector3d(
79 static_cast<double>(x) * delta, static_cast<double>(y) * delta, static_cast<double>(z) * delta);
80 checker->addCollisionObject(link_names.back(), 0, obj3_shapes, obj3_poses);
81 }
82 }
83 }
84
85 // Check if they are in collision
86 checker->setActiveCollisionObjects(link_names);
87 checker->setCollisionMarginData(CollisionMarginData(0.1));
88 checker->setCollisionObjectsTransform(location);
89
90 ContactResultMap result;
92
93 for (auto _ : state) // NOLINT
94 {
95 result.clear();
96 result_vector.clear();
97 checker->contactTest(result, ContactTestType::ALL);
99 }
100}
101
104static void BM_LARGE_DATASET_SINGLELINK(benchmark::State& state,
105 DiscreteContactManager::Ptr checker, // NOLINT
106 int edge_size,
108{
109 // Add Meshed Sphere to checker
111
112 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
113 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
114 loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);
115
116 switch (type)
117 {
119 {
120 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
122 break;
123 }
125 {
126 sphere = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
127 break;
128 }
130 {
131 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
132 break;
133 }
134 default:
135 {
136 throw(std::runtime_error("Invalid geometry type"));
137 break;
138 }
139 }
140
141 // Add Grid of spheres
142 double delta = 0.55;
143
144 std::vector<std::string> link_names;
145 // tesseract_common::TransformMap location;
146 CollisionShapesConst obj3_shapes;
148 for (int x = 0; x < edge_size; ++x)
149 {
150 for (int y = 0; y < edge_size; ++y)
151 {
152 for (int z = 0; z < edge_size; ++z)
153 {
154 Eigen::Isometry3d sphere_pose;
155 sphere_pose.setIdentity();
156 sphere_pose.translation() = Eigen::Vector3d(
157 static_cast<double>(x) * delta, static_cast<double>(y) * delta, static_cast<double>(z) * delta);
158
159 obj3_shapes.push_back(CollisionShapePtr(sphere->clone()));
160 obj3_poses.push_back(sphere_pose);
161 }
162 }
163 }
164 link_names.emplace_back("grid_link");
165 checker->addCollisionObject(link_names.back(), 0, obj3_shapes, obj3_poses);
166
167 // Add Single Sphere Link
168 Eigen::Isometry3d sphere_pose;
169 sphere_pose.setIdentity();
170 sphere_pose.translation() = Eigen::Vector3d(static_cast<double>(edge_size) / 2.0 * delta,
171 static_cast<double>(edge_size) / 2.0 * delta,
172 static_cast<double>(edge_size) / 2.0 * delta);
173 CollisionShapesConst single_shapes;
175 single_shapes.push_back(CollisionShapePtr(sphere->clone()));
176 single_poses.push_back(sphere_pose);
177 link_names.emplace_back("single_link");
178 checker->addCollisionObject(link_names.back(), 0, single_shapes, single_poses);
179
180 // Check if they are in collision
181 checker->setActiveCollisionObjects(link_names);
182 checker->setCollisionMarginData(CollisionMarginData(0.1));
183 // checker->setCollisionObjectsTransform(location);
184
185 ContactResultMap result;
187
188 for (auto _ : state) // NOLINT
189 {
190 result.clear();
191 result_vector.clear();
192 checker->contactTest(result, ContactTestType::ALL);
194 }
195}
196
197} // namespace test_suite
198} // namespace tesseract_collision
199
200#endif
This structure hold contact results for link pairs.
Definition: types.h:154
void clear()
This is a consurvative clear.
Definition: types.cpp:183
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:215
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:47
tesseract_collision::ContactResultVector result_vector
Definition: collision_core_unit.cpp:410
results link_names[0]
Definition: collision_core_unit.cpp:146
This is a collection of common methods.
This is a collection of common methods.
This is the discrete contact manager base class.
Tesseract Geometries.
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
static void BM_LARGE_DATASET_MULTILINK(benchmark::State &state, DiscreteContactManager::Ptr checker, int edge_size, tesseract_geometry::GeometryType type)
Benchmark that checks collisions between a lot of objects. In this case it is a grid of spheres - eac...
Definition: large_dataset_benchmarks.hpp:20
static void BM_LARGE_DATASET_SINGLELINK(benchmark::State &state, DiscreteContactManager::Ptr checker, int edge_size, tesseract_geometry::GeometryType type)
Benchmark that checks collisions between a lot of objects. In this case it is a grid of spheres in on...
Definition: large_dataset_benchmarks.hpp:104
Definition: bullet_cast_bvh_manager.h:49
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
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:285
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh(const tesseract_geometry::Mesh &mesh)
Definition: convex_hull_utils.cpp:114
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
Definition: types.h:62
GeometryType
Definition: geometry.h:41
@ MESH
Definition: geometry.h:49
@ CONVEX_MESH
Definition: geometry.h:50
@ SPHERE
Definition: geometry.h:43
mCollisionCheckConfig contact_request type
Definition: tesseract_environment_collision.cpp:103
auto sphere
Definition: tesseract_geometry_unit.cpp:23
auto mesh
Definition: tesseract_geometry_unit.cpp:25