Overview
This example demonstrates how to create and instantiate various geometry types in Tesseract. Geometries are the building blocks for collision objects, which are used in motion planning, simulation, and collision detection. Understanding the different geometry types and when to use each one is fundamental to working with Tesseract.
Key Concepts
- Primitive Shapes: Simple, analytically-defined shapes (Box, Sphere, Cylinder, etc.) that are computationally efficient for collision checking.
- Mesh Geometries: Triangle-based representations of arbitrary 3D shapes, loaded from files or constructed manually. More flexible but slower than primitives.
- Signed Distance Field (SDF) Mesh: A specialized mesh that stores per-vertex or per-cell distance information. Useful for faster proximity queries and haptic feedback.
- Convex Mesh: A mesh guaranteed to be convex (all interior angles < 180°). More efficient for collision checking than arbitrary meshes while maintaining flexibility.
- Octree: A hierarchical spatial data structure that represents volumetric regions, useful for voxel-based collision detection and occupancy information.
When to Use Each Type
| Geometry Type | Speed | Flexibility | Use Case |
| Primitive | Very Fast | Low | Robot links, obstacles with simple shapes |
| Mesh | Slow | Very High | Complex geometry, CAD models |
| SDF Mesh | Medium | High | Smooth contact, force feedback |
| Convex Mesh | Fast | Medium | Complex convex objects, gripper fingers |
| Octree | Medium | Medium | Point clouds, voxel grids, occupancy maps |
Creating Primitive Shapes
Primitive shapes are created with a single constructor call. They are analytically defined and are the fastest for collision checking:
Box (width × height × depth):
auto box = std::make_shared<tesseract::geometry::Box>(1, 1, 1);
Sphere (radius):
auto sphere = std::make_shared<tesseract::geometry::Sphere>(1);
Cylinder (radius × height):
auto cylinder = std::make_shared<tesseract::geometry::Cylinder>(1, 1);
Cone (radius × height):
auto cone = std::make_shared<tesseract::geometry::Cone>(1, 1);
Capsule (radius × height):
auto capsule = std::make_shared<tesseract::geometry::Capsule>(1, 1);
Plane (a·x + b·y + c·z + d = 0):
auto plane = std::make_shared<tesseract::geometry::Plane>(1, 1, 1, 1);
Loading Meshes from Files
The most practical way to use meshes is to load them from CAD files (DAE, STL, OBJ, etc.). Tesseract provides createMeshFromPath() which automatically parses the file format and returns a vector of meshes (some files may contain multiple mesh objects):
std::string mesh_file = "package://tesseract/support/meshes/sphere_p25m.dae";
std::vector<Mesh::Ptr> loaded_meshes = createMeshFromPath<Mesh>(locator.
locateResource(mesh_file)->getFilePath());
A general resource loaders using environment variable.
Definition resource_locator.h:84
std::shared_ptr< Resource > locateResource(const std::string &url) const override
Locate a resource based on a URL.
Definition resource_locator.cpp:158
You can then inspect the loaded meshes and use them in collision checking:
CONSOLE_BRIDGE_logInform("Number of meshes loaded: %zu", loaded_meshes.size());
for (size_t i = 0; i < loaded_meshes.size(); ++i)
{
CONSOLE_BRIDGE_logInform("Mesh #%zu - Triangles: %zu, Vertices: %zu",
i + 1,
loaded_meshes[i]->getFaceCount(),
loaded_meshes[i]->getVertexCount());
}
Creating Mesh Geometries Manually
Mesh geometries require you to provide vertex positions and face indices (triangles). Vertices are 3D points, and faces are groups of 3 indices defining triangles:
Standard Mesh - Use for complex geometry loaded from CAD files:
std::shared_ptr<const tesseract::common::VectorVector3d> mesh_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> mesh_faces = std::make_shared<const Eigen::VectorXi>();
auto mesh = std::make_shared<tesseract::geometry::Mesh>(mesh_vertices, mesh_faces);
Signed Distance Field (SDF) Mesh - Use when you need distance information at vertices:
std::shared_ptr<const tesseract::common::VectorVector3d> sdf_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> sdf_faces = std::make_shared<const Eigen::VectorXi>();
auto sdf_mesh = std::make_shared<tesseract::geometry::SDFMesh>(sdf_vertices, sdf_faces);
Convex Mesh - Use when your geometry should be convex (more efficient):
std::shared_ptr<const tesseract::common::VectorVector3d> convex_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> convex_faces = std::make_shared<const Eigen::VectorXi>();
auto convex_mesh = std::make_shared<tesseract::geometry::ConvexMesh>(convex_vertices, convex_faces);
Creating Octrees
An octree represents volumetric space hierarchically. It's useful when working with point clouds, occupancy grids, or voxel-based representations:
std::shared_ptr<const octomap::OcTree> octree;
auto octree_t = std::make_shared<tesseract::geometry::Octree>(octree, tesseract::geometry::OctreeSubType::BOX);
Typical Workflow
- Choose the geometry type based on the shape and performance requirements
- Create the geometry with appropriate parameters (see sections above)
- Add to collision manager - Pass the geometry to
addCollisionObject() (see box_box_example)
- Use in collision checks - Query distances, penetration, contacts
- Use in planning - Feed collision results to motion planners
Tips and Best Practices
- Prefer primitives: Always use primitives when possible (faster and simpler)
- Convex hulls for complex shapes: If you have a complex mesh, compute its convex hull for better performance
- Scale appropriately: Geometry parameters should match your robot's dimensions in meters
- Mesh resolution: Complex meshes are slower; balance between fidelity and performance
- Octree resolution: Choose appropriate octree depth based on your precision needs
- Shared ownership: Use
std::shared_ptr for memory management (shown in all examples)
Integrating with Collision Checking
After creating geometries, use them with the collision manager:
BulletDiscreteBVHManager checker;
checker.addCollisionObject("my_object", 0, {box}, {Eigen::Isometry3d::Identity()});
See the box_box_example page for complete collision checking examples.
Summary
This example demonstrates creating all major geometry types in Tesseract:
- Common primitives: Box, Sphere, Cylinder, Cone, Capsule, Plane
- Mesh loading from files (practical for real-world usage)
- Mesh variants: Standard, SDF, and Convex meshes
- Volumetric representation: Octrees
Choose the simplest geometry that fits your use case for optimal performance.
Full source code
For reference, here is the complete source of this example:
#include <console_bridge/console.h>
#include <tesseract/geometry/mesh_parser.h>
#include <octomap/OcTree.h>
#include <iostream>
using namespace tesseract::geometry;
{
std::string mesh_file = "package://tesseract/support/meshes/sphere_p25m.dae";
std::vector<Mesh::Ptr> loaded_meshes = createMeshFromPath<Mesh>(locator.
locateResource(mesh_file)->getFilePath());
CONSOLE_BRIDGE_logInform("Number of meshes loaded: %zu", loaded_meshes.size());
for (size_t i = 0; i < loaded_meshes.size(); ++i)
{
CONSOLE_BRIDGE_logInform("Mesh #%zu - Triangles: %zu, Vertices: %zu",
i + 1,
loaded_meshes[i]->getFaceCount(),
loaded_meshes[i]->getVertexCount());
}
auto box = std::make_shared<tesseract::geometry::Box>(1, 1, 1);
auto cone = std::make_shared<tesseract::geometry::Cone>(1, 1);
auto capsule = std::make_shared<tesseract::geometry::Capsule>(1, 1);
auto cylinder = std::make_shared<tesseract::geometry::Cylinder>(1, 1);
auto plane = std::make_shared<tesseract::geometry::Plane>(1, 1, 1, 1);
auto sphere = std::make_shared<tesseract::geometry::Sphere>(1);
std::shared_ptr<const tesseract::common::VectorVector3d> mesh_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> mesh_faces = std::make_shared<const Eigen::VectorXi>();
auto mesh = std::make_shared<tesseract::geometry::Mesh>(mesh_vertices, mesh_faces);
std::shared_ptr<const tesseract::common::VectorVector3d> sdf_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> sdf_faces = std::make_shared<const Eigen::VectorXi>();
auto sdf_mesh = std::make_shared<tesseract::geometry::SDFMesh>(sdf_vertices, sdf_faces);
std::shared_ptr<const tesseract::common::VectorVector3d> convex_vertices =
std::make_shared<const tesseract::common::VectorVector3d>();
std::shared_ptr<const Eigen::VectorXi> convex_faces = std::make_shared<const Eigen::VectorXi>();
auto convex_mesh = std::make_shared<tesseract::geometry::ConvexMesh>(convex_vertices, convex_faces);
std::shared_ptr<const octomap::OcTree> octree;
auto octree_t = std::make_shared<tesseract::geometry::Octree>(octree, tesseract::geometry::OctreeSubType::BOX);
}
int main(int argc, char **argv)
Definition create_convex_hull.cpp:43
Locate and retrieve resource data.