Classes | Typedefs | Enumerations | Functions | Variables
tesseract_geometry Namespace Reference

Classes

class  Box
 
class  Capsule
 
class  CompoundMesh
 This is store meshes that are associated with as single resource. More...
 
class  Cone
 
class  ConvexMesh
 
class  Cylinder
 
class  Geometry
 
class  Mesh
 
class  MeshMaterial
 Represents material information extracted from a mesh file. More...
 
class  MeshTexture
 Represents a texture and UV coordinates extracted from a mesh file. More...
 
class  Octree
 
class  Plane
 
struct  PointCloud
 A basic point cloud structure to leverage instead of PCL. More...
 
class  PolygonMesh
 
class  SDFMesh
 
class  Sphere
 

Typedefs

using Geometrys = std::vector< Geometry::Ptr >
 
using GeometrysConst = std::vector< Geometry::ConstPtr >
 

Enumerations

enum  GeometryType : std::uint8_t {
  GeometryType::UNINITIALIZED, GeometryType::SPHERE, GeometryType::CYLINDER, GeometryType::CAPSULE,
  GeometryType::CONE, GeometryType::BOX, GeometryType::PLANE, GeometryType::MESH,
  GeometryType::CONVEX_MESH, GeometryType::SDF_MESH, GeometryType::OCTREE, GeometryType::POLYGON_MESH,
  GeometryType::COMPOUND_MESH
}
 
enum  OctreeSubType : std::uint8_t { OctreeSubType::BOX, OctreeSubType::SPHERE_INSIDE, OctreeSubType::SPHERE_OUTSIDE }
 

Functions

template<class T >
std::vector< std::shared_ptr< T > > createMeshFromAsset (const aiScene *scene, const Eigen::Vector3d &scale, tesseract_common::Resource::Ptr resource, bool normals, bool vertex_colors, bool material_and_texture)
 Create list of meshes from the assimp scene. More...
 
template<typename T >
static std::vector< std::shared_ptr< T > > createMeshFromBytes (const std::string &url, const uint8_t *bytes, size_t bytes_len, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), bool triangulate=false, bool flatten=false, bool normals=false, bool vertex_colors=false, bool material_and_texture=false)
 Create a mesh from byte array. More...
 
template<class T >
std::vector< std::shared_ptr< T > > createMeshFromPath (const std::string &path, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), bool triangulate=false, bool flatten=false, bool normals=false, bool vertex_colors=false, bool material_and_texture=false)
 Create a mesh using assimp from file path. More...
 
template<class T >
std::vector< std::shared_ptr< T > > createMeshFromResource (tesseract_common::Resource::Ptr resource, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), bool triangulate=false, bool flatten=false, bool normals=false, bool vertex_colors=false, bool material_and_texture=false)
 Create a mesh using assimp from resource. More...
 
template<typename PointT >
std::unique_ptr< octomap::OcTree > createOctree (const PointT &point_cloud, const double resolution, const bool prune, const bool binary=true)
 
template<class T >
std::vector< std::shared_ptr< T > > extractMeshData (const aiScene *scene, const aiNode *node, const aiMatrix4x4 &parent_transform, const Eigen::Vector3d &scale, tesseract_common::Resource::Ptr resource, bool normals, bool vertex_colors, bool material_and_texture)
 
bool isIdentical (const Geometry &geom1, const Geometry &geom2)
 Check if two Geometries are identical. More...
 

Variables

static const std::vector< std::string > GeometryTypeStrings
 

Typedef Documentation

◆ Geometrys

using tesseract_geometry::Geometrys = typedef std::vector<Geometry::Ptr>

Definition at line 110 of file geometry.h.

◆ GeometrysConst

Definition at line 111 of file geometry.h.

Enumeration Type Documentation

◆ GeometryType

enum tesseract_geometry::GeometryType : std::uint8_t
strong
Enumerator
UNINITIALIZED 
SPHERE 
CYLINDER 
CAPSULE 
CONE 
BOX 
PLANE 
MESH 
CONVEX_MESH 
SDF_MESH 
OCTREE 
POLYGON_MESH 
COMPOUND_MESH 

Definition at line 48 of file geometry.h.

◆ OctreeSubType

enum tesseract_geometry::OctreeSubType : std::uint8_t
strong
Enumerator
BOX 
SPHERE_INSIDE 
SPHERE_OUTSIDE 

Definition at line 51 of file octree.h.

Function Documentation

◆ createMeshFromAsset()

template<class T >
std::vector<std::shared_ptr<T> > tesseract_geometry::createMeshFromAsset ( const aiScene *  scene,
const Eigen::Vector3d &  scale,
tesseract_common::Resource::Ptr  resource,
bool  normals,
bool  vertex_colors,
bool  material_and_texture 
)

Create list of meshes from the assimp scene.

Parameters
sceneThe assimp scene
scalePerform an axis scaling
resourceThe mesh resource that generated the scene
normalsIf true, loads mesh normals
vertex_colorsIf true, loads mesh vertex colors
material_and_textureIf true, loads mesh materials and textures
Returns
A list of tesseract meshes

Definition at line 333 of file mesh_parser.h.

◆ createMeshFromBytes()

template<typename T >
static std::vector<std::shared_ptr<T> > tesseract_geometry::createMeshFromBytes ( const std::string &  url,
const uint8_t *  bytes,
size_t  bytes_len,
const Eigen::Vector3d &  scale = Eigen::Vector3d(1, 1, 1),
bool  triangulate = false,
bool  flatten = false,
bool  normals = false,
bool  vertex_colors = false,
bool  material_and_texture = false 
)
static

Create a mesh from byte array.

Parameters
urlThe URL of source resource
bytesByte array
bytes_lenThe length of bytes
scalePerform an axis scaling
triangulateIf true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flattenIf true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normalsIf true, loads mesh normals
vertex_colorsIf true, loads mesh vertex colors
material_and_textureIf true, loads mesh materials and textures
Returns

Definition at line 569 of file mesh_parser.h.

◆ createMeshFromPath()

template<class T >
std::vector<std::shared_ptr<T> > tesseract_geometry::createMeshFromPath ( const std::string &  path,
const Eigen::Vector3d &  scale = Eigen::Vector3d(1, 1, 1),
bool  triangulate = false,
bool  flatten = false,
bool  normals = false,
bool  vertex_colors = false,
bool  material_and_texture = false 
)

Create a mesh using assimp from file path.

Parameters
pathThe file path to the mesh
scalePerform an axis scaling
triangulateIf true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flattenIf true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normalsIf true, loads mesh normals
vertex_colorsIf true, loads mesh vertex colors
material_and_textureIf true, loads mesh materials and textures
Returns

Definition at line 370 of file mesh_parser.h.

◆ createMeshFromResource()

template<class T >
std::vector<std::shared_ptr<T> > tesseract_geometry::createMeshFromResource ( tesseract_common::Resource::Ptr  resource,
const Eigen::Vector3d &  scale = Eigen::Vector3d(1, 1, 1),
bool  triangulate = false,
bool  flatten = false,
bool  normals = false,
bool  vertex_colors = false,
bool  material_and_texture = false 
)

Create a mesh using assimp from resource.

Parameters
resourceThe located resource
scalePerform an axis scaling
triangulateIf true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flattenIf true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normalsIf true, loads mesh normals
vertex_colorsIf true, loads mesh vertex colors
material_and_textureIf true, loads mesh materials and textures
Returns

Definition at line 452 of file mesh_parser.h.

◆ createOctree()

template<typename PointT >
std::unique_ptr<octomap::OcTree> tesseract_geometry::createOctree ( const PointT &  point_cloud,
const double  resolution,
const bool  prune,
const bool  binary = true 
)

Definition at line 59 of file octree_utils.h.

◆ extractMeshData()

template<class T >
std::vector<std::shared_ptr<T> > tesseract_geometry::extractMeshData ( const aiScene *  scene,
const aiNode *  node,
const aiMatrix4x4 &  parent_transform,
const Eigen::Vector3d &  scale,
tesseract_common::Resource::Ptr  resource,
bool  normals,
bool  vertex_colors,
bool  material_and_texture 
)

The template type must have a constructor as follows Constructor(std::shared_ptr<tesseract_geometry::VectorVector3d> vertices, std::shared_ptr<std::vector<int>> faces, int face_count)

Definition at line 106 of file mesh_parser.h.

◆ isIdentical()

bool tesseract_geometry::isIdentical ( const Geometry geom1,
const Geometry geom2 
)

Check if two Geometries are identical.

Parameters
geom1First Geometry
geom2Second Geometry
Returns
True if identical, otherwise false

Definition at line 38 of file utils.cpp.

Variable Documentation

◆ GeometryTypeStrings

const std::vector<std::string> tesseract_geometry::GeometryTypeStrings
static
Initial value:
= { "UNINITIALIZED", "SPHERE", "CYLINDER", "CAPSULE",
"CONE", "BOX", "PLANE", "MESH",
"CONVEX_MESH", "SDF_MESH", "OCTREE", "POLYGON_MESH",
"COMPOUND_MESH" }

Definition at line 64 of file geometry.h.



tesseract_geometry
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:46