1#ifndef TESSERACT_COLLISION_LARGE_DATASET_BENCHMARKS_HPP
2#define TESSERACT_COLLISION_LARGE_DATASET_BENCHMARKS_HPP
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);
36 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
42 sphere = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
47 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
52 throw(std::runtime_error(
"Invalid geometry type"));
61 for (
int x = 0; x < edge_size; ++x)
63 for (
int y = 0; y < edge_size; ++y)
65 for (
int z = 0; z < edge_size; ++z)
69 Eigen::Isometry3d sphere_pose;
70 sphere_pose.setIdentity();
73 obj3_poses.push_back(sphere_pose);
75 link_names.push_back(
"sphere_link_" + std::to_string(x) + std::to_string(y) + std::to_string(z));
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);
86 checker->setActiveCollisionObjects(
link_names);
88 checker->setCollisionObjectsTransform(location);
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);
120 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
126 sphere = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
131 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
136 throw(std::runtime_error(
"Invalid geometry type"));
148 for (
int x = 0; x < edge_size; ++x)
150 for (
int y = 0; y < edge_size; ++y)
152 for (
int z = 0; z < edge_size; ++z)
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);
160 obj3_poses.push_back(sphere_pose);
165 checker->addCollisionObject(
link_names.back(), 0, obj3_shapes, obj3_poses);
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);
176 single_poses.push_back(sphere_pose);
178 checker->addCollisionObject(
link_names.back(), 0, single_shapes, single_poses);
181 checker->setActiveCollisionObjects(
link_names);
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.
#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