Tesseract Geometry Package¶
Background¶
This package contains geometry types used by Tesseract including primitive shapes, mesh, convex hull mesh, octomap and signed distance field.
Features¶
Primitive Shapes
Box
Cone
Capsule
Cylinder
Plane
Sphere
Mesh
Convex Mesh
SDF Mesh
Octree
Creating Geometry Shapes¶
#include <console_bridge/console.h> #include <tesseract_geometry/geometries.h> #include <iostream> using namespace tesseract_geometry; int main(int /*argc*/, char** /*argv*/) { // Shape Box auto box = std::make_shared<tesseract_geometry::Box>(1, 1, 1); // Shape Cone auto cone = std::make_shared<tesseract_geometry::Cone>(1, 1); // Shape Capsule auto capsule = std::make_shared<tesseract_geometry::Capsule>(1, 1); // Shape Cylinder auto cylinder = std::make_shared<tesseract_geometry::Cylinder>(1, 1); // Shape Plane auto plane = std::make_shared<tesseract_geometry::Plane>(1, 1, 1, 1); // Shape Sphere auto sphere = std::make_shared<tesseract_geometry::Sphere>(1); // Manually create mesh 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>(); // Next fill out vertices and triangles auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces); // Manually create signed distance field mesh 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>(); // Next fill out vertices and triangles auto sdf_mesh = std::make_shared<tesseract_geometry::SDFMesh>(sdf_vertices, sdf_faces); // Manually create convex mesh 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>(); // Next fill out vertices and triangles auto convex_mesh = std::make_shared<tesseract_geometry::ConvexMesh>(convex_vertices, convex_faces); // Create an octree std::shared_ptr<const octomap::OcTree> octree; auto octree_t = std::make_shared<tesseract_geometry::Octree>(octree, tesseract_geometry::Octree::SubType::BOX); }
Example Explanation¶
Create a box.
auto box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
Create a cone.
auto cone = std::make_shared<tesseract_geometry::Cone>(1, 1);
Create a capsule.
auto capsule = std::make_shared<tesseract_geometry::Capsule>(1, 1);
Create a cylinder.
auto cylinder = std::make_shared<tesseract_geometry::Cylinder>(1, 1);
Create a plane.
auto plane = std::make_shared<tesseract_geometry::Plane>(1, 1, 1, 1);
Create a sphere.
auto sphere = std::make_shared<tesseract_geometry::Sphere>(1);
Create a mesh.
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>(); // Next fill out vertices and triangles auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
Note
This shows how to create a mesh provided vertices and faces. You may also use utilities in tesseract_scene_graph mesh parser to load meshes from file.
Create a signed distance field mesh.
Note
This should be the same as a mesh, but when interpreted as the collision object it will be encoded as a signed distance field.
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>(); // Next fill out vertices and triangles auto sdf_mesh = std::make_shared<tesseract_geometry::SDFMesh>(sdf_vertices, sdf_faces);
Note
This shows how to create a SDF mesh provided vertices and faces. You may also use utilities in tesseract_scene_graph mesh parser to load meshes from file.
Create a convex mesh.
Warning
This expects the data to already represent a convex mesh. If yours does not load as a mesh and then use tesseract utility to convert to a convex mesh.
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>(); // Next fill out vertices and triangles auto convex_mesh = std::make_shared<tesseract_geometry::ConvexMesh>(convex_vertices, convex_faces);
Note
This shows how to create a convex mesh provided vertices and faces. You may also use utilities in tesseract_scene_graph mesh parser to load meshes from file.
Create an octree.
std::shared_ptr<const octomap::OcTree> octree; auto octree_t = std::make_shared<tesseract_geometry::Octree>(octree, tesseract_geometry::Octree::SubType::BOX);
Note
It is beneficial to prune the octree prior to creating the tesseract octree shape to simplify
Octree support multiple shape types to represent a cell in the octree.
BOX tesseract_geometry::Octree::SubType::BOX
SPHERE_INSIDE tesseract_geometry::Octree::SubType::SPHERE_INSIDE
SPHERE_OUTSIDE tesseract_geometry::Octree::SubType::SPHERE_OUTSIDE