Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
tesseract_geometry::PolygonMesh Class Reference

#include <polygon_mesh.h>

Inheritance diagram for tesseract_geometry::PolygonMesh:
Inheritance graph
[legend]
Collaboration diagram for tesseract_geometry::PolygonMesh:
Collaboration graph
[legend]

Public Types

using Ptr = std::shared_ptr< PolygonMesh >
 
using ConstPtr = std::shared_ptr< const PolygonMesh >
 
- Public Types inherited from tesseract_geometry::Geometry
using Ptr = std::shared_ptr< Geometry >
 
using ConstPtr = std::shared_ptr< const Geometry >
 

Public Member Functions

 PolygonMesh (std::shared_ptr< const tesseract_common::VectorVector3d > vertices, std::shared_ptr< const Eigen::VectorXi > faces, tesseract_common::Resource::ConstPtr resource=nullptr, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), std::shared_ptr< const tesseract_common::VectorVector3d > normals=nullptr, std::shared_ptr< const tesseract_common::VectorVector4d > vertex_colors=nullptr, MeshMaterial::Ptr mesh_material=nullptr, std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures=nullptr, GeometryType type=GeometryType::CONVEX_MESH)
 Polygon Mesh geometry. More...
 
 PolygonMesh (std::shared_ptr< const tesseract_common::VectorVector3d > vertices, std::shared_ptr< const Eigen::VectorXi > faces, int face_count, tesseract_common::Resource::ConstPtr resource=nullptr, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), std::shared_ptr< const tesseract_common::VectorVector3d > normals=nullptr, std::shared_ptr< const tesseract_common::VectorVector4d > vertex_colors=nullptr, MeshMaterial::Ptr mesh_material=nullptr, std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures=nullptr, GeometryType type=GeometryType::CONVEX_MESH)
 Polygon Mesh geometry. More...
 
 PolygonMesh ()=default
 
 ~PolygonMesh () override=default
 
const std::shared_ptr< const tesseract_common::VectorVector3d > & getVertices () const
 Get Polygon mesh vertices. More...
 
const std::shared_ptr< const Eigen::VectorXi > & getFaces () const
 Get Polygon mesh faces. More...
 
int getVertexCount () const
 Get vertex count. More...
 
int getFaceCount () const
 Get face count. More...
 
tesseract_common::Resource::ConstPtr getResource () const
 Get the path to file used to generate the mesh. More...
 
const Eigen::Vector3d & getScale () const
 Get the scale applied to file used to generate the mesh. More...
 
const std::shared_ptr< const tesseract_common::VectorVector3d > & getNormals () const
 Get the vertex normal vectors. More...
 
const std::shared_ptr< const tesseract_common::VectorVector4d > & getVertexColors () const
 Get the vertex colors. More...
 
MeshMaterial::ConstPtr getMaterial () const
 Get material data extracted from the mesh file. More...
 
const std::shared_ptr< const std::vector< MeshTexture::Ptr > > & getTextures () const
 Get textures extracted from the mesh file. More...
 
Geometry::Ptr clone () const override
 Create a copy of this shape. More...
 
bool operator== (const PolygonMesh &rhs) const
 
bool operator!= (const PolygonMesh &rhs) const
 
- Public Member Functions inherited from tesseract_geometry::Geometry
 Geometry (GeometryType type=GeometryType::UNINITIALIZED)
 
virtual ~Geometry ()=default
 
 Geometry (const Geometry &)=default
 
Geometryoperator= (const Geometry &)=default
 
 Geometry (Geometry &&)=default
 
Geometryoperator= (Geometry &&)=default
 
virtual Geometry::Ptr clone () const =0
 Create a copy of this shape. More...
 
GeometryType getType () const
 
bool operator== (const Geometry &rhs) const
 
bool operator!= (const Geometry &rhs) const
 

Private Member Functions

template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 

Private Attributes

std::shared_ptr< const tesseract_common::VectorVector3dvertices_
 
std::shared_ptr< const Eigen::VectorXi > faces_
 
int vertex_count_ { 0 }
 
int face_count_ { 0 }
 
tesseract_common::Resource::ConstPtr resource_
 
Eigen::Vector3d scale_
 
std::shared_ptr< const tesseract_common::VectorVector3dnormals_
 
std::shared_ptr< const tesseract_common::VectorVector4dvertex_colors_
 
MeshMaterial::Ptr mesh_material_
 
std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures_
 

Friends

class boost::serialization::access
 

Member Typedef Documentation

◆ ConstPtr

◆ Ptr

Constructor & Destructor Documentation

◆ PolygonMesh() [1/3]

tesseract_geometry::PolygonMesh::PolygonMesh ( std::shared_ptr< const tesseract_common::VectorVector3d vertices,
std::shared_ptr< const Eigen::VectorXi >  faces,
tesseract_common::Resource::ConstPtr  resource = nullptr,
const Eigen::Vector3d &  scale = Eigen::Vector3d(1, 1, 1),
std::shared_ptr< const tesseract_common::VectorVector3d normals = nullptr,
std::shared_ptr< const tesseract_common::VectorVector4d vertex_colors = nullptr,
MeshMaterial::Ptr  mesh_material = nullptr,
std::shared_ptr< const std::vector< MeshTexture::Ptr > >  mesh_textures = nullptr,
GeometryType  type = GeometryType::CONVEX_MESH 
)
inline

Polygon Mesh geometry.

Parameters
verticesA vector of vertices associated with the mesh
facesA vector of face indices, where the first number indicates the number of vertices associated with the face, followed by the vertex index in parameter vertices. For example, a triangle has three vertices, so there should be four inputs, where the first should be 3, indicating there are three vertices that define this face, followed by three indices.
resourceA resource locator for locating resource
scaleScale the mesh
normalsA vector of normals for the vertices (optional)
vertex_colorsA vector of colors (RGBA) for the vertices (optional)
mesh_materialA MeshMaterial describing the color and material properties of the mesh (optional)
mesh_texturesA vector of MeshTexture to apply to the mesh (optional)

◆ PolygonMesh() [2/3]

tesseract_geometry::PolygonMesh::PolygonMesh ( std::shared_ptr< const tesseract_common::VectorVector3d vertices,
std::shared_ptr< const Eigen::VectorXi >  faces,
int  face_count,
tesseract_common::Resource::ConstPtr  resource = nullptr,
const Eigen::Vector3d &  scale = Eigen::Vector3d(1, 1, 1),
std::shared_ptr< const tesseract_common::VectorVector3d normals = nullptr,
std::shared_ptr< const tesseract_common::VectorVector4d vertex_colors = nullptr,
MeshMaterial::Ptr  mesh_material = nullptr,
std::shared_ptr< const std::vector< MeshTexture::Ptr > >  mesh_textures = nullptr,
GeometryType  type = GeometryType::CONVEX_MESH 
)
inline

Polygon Mesh geometry.

Parameters
verticesA vector of vertices associated with the mesh
facesA vector of face indices, where the first number indicates the number of vertices associated with the face, followed by the vertex index in parameter vertices. For example, a triangle has three vertices, so there should be four inputs, where the first should be 3, indicating there are three vertices that define this face, followed by three indices.
face_countProvide the number of faces. This is faster because it does not need to loop over the faces.
resourceA resource locator for locating resource
scaleScale the mesh
normalsA vector of normals for the vertices (optional)
vertex_colorsA vector of colors (RGBA) for the vertices (optional)
mesh_materialDescribes the color and material properties of the mesh (optional)
mesh_texturesA vector of MeshTexture to apply to the mesh (optional)

◆ PolygonMesh() [3/3]

tesseract_geometry::PolygonMesh::PolygonMesh ( )
default

◆ ~PolygonMesh()

tesseract_geometry::PolygonMesh::~PolygonMesh ( )
overridedefault

Member Function Documentation

◆ clone()

Geometry::Ptr tesseract_geometry::PolygonMesh::clone ( ) const
inlineoverridevirtual

Create a copy of this shape.

Implements tesseract_geometry::Geometry.

Reimplemented in tesseract_geometry::SDFMesh.

◆ getFaceCount()

int tesseract_geometry::PolygonMesh::getFaceCount ( ) const
inline

Get face count.

Returns
Number of faces

◆ getFaces()

const std::shared_ptr< const Eigen::VectorXi > & tesseract_geometry::PolygonMesh::getFaces ( ) const
inline

Get Polygon mesh faces.

Returns
A vector of face indices

◆ getMaterial()

MeshMaterial::ConstPtr tesseract_geometry::PolygonMesh::getMaterial ( ) const
inline

Get material data extracted from the mesh file.

Mesh files contain material information. The mesh parser will extract the material information and store it in a MeshMaterial structure.

Returns
The MeshMaterial data extracted from mesh file

◆ getNormals()

const std::shared_ptr< const tesseract_common::VectorVector3d > & tesseract_geometry::PolygonMesh::getNormals ( ) const
inline

Get the vertex normal vectors.

Optional, may be nullptr

Returns
The vertex normal vector

◆ getResource()

tesseract_common::Resource::ConstPtr tesseract_geometry::PolygonMesh::getResource ( ) const
inline

Get the path to file used to generate the mesh.

Note: If empty, assume it was manually generated.

Returns
Absolute path to the mesh file

◆ getScale()

const Eigen::Vector3d & tesseract_geometry::PolygonMesh::getScale ( ) const
inline

Get the scale applied to file used to generate the mesh.

Returns
The scale x, y, z

◆ getTextures()

const std::shared_ptr< const std::vector< MeshTexture::Ptr > > & tesseract_geometry::PolygonMesh::getTextures ( ) const
inline

Get textures extracted from the mesh file.

Mesh files contain (or reference) image files that form textures on the surface of the mesh. UV coordinates specify how the image is applied to the mesh. The MeshTexture structure contains a resource to the image, and the UV coordinates. Currently only jpg and png image formats are supported.

Returns
Vector of mesh textures

◆ getVertexColors()

const std::shared_ptr< const tesseract_common::VectorVector4d > & tesseract_geometry::PolygonMesh::getVertexColors ( ) const
inline

Get the vertex colors.

Optional, may be nullptr

Returns
Vertex colors

◆ getVertexCount()

int tesseract_geometry::PolygonMesh::getVertexCount ( ) const
inline

Get vertex count.

Returns
Number of vertices

◆ getVertices()

const std::shared_ptr< const tesseract_common::VectorVector3d > & tesseract_geometry::PolygonMesh::getVertices ( ) const
inline

Get Polygon mesh vertices.

Returns
A vector of vertices

◆ operator!=()

bool tesseract_geometry::PolygonMesh::operator!= ( const PolygonMesh rhs) const

◆ operator==()

bool tesseract_geometry::PolygonMesh::operator== ( const PolygonMesh rhs) const
Todo:
Finish PolygonMesh == operator

◆ serialize()

template<class Archive >
void tesseract_geometry::PolygonMesh::serialize ( Archive &  ar,
const unsigned int  version 
)
private
Todo:
Serialize mesh materials and textures

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Member Data Documentation

◆ face_count_

int tesseract_geometry::PolygonMesh::face_count_ { 0 }
private

◆ faces_

std::shared_ptr<const Eigen::VectorXi> tesseract_geometry::PolygonMesh::faces_
private

◆ mesh_material_

MeshMaterial::Ptr tesseract_geometry::PolygonMesh::mesh_material_
private

◆ mesh_textures_

std::shared_ptr<const std::vector<MeshTexture::Ptr> > tesseract_geometry::PolygonMesh::mesh_textures_
private

◆ normals_

std::shared_ptr<const tesseract_common::VectorVector3d> tesseract_geometry::PolygonMesh::normals_
private

◆ resource_

tesseract_common::Resource::ConstPtr tesseract_geometry::PolygonMesh::resource_
private

◆ scale_

Eigen::Vector3d tesseract_geometry::PolygonMesh::scale_
private

◆ vertex_colors_

std::shared_ptr<const tesseract_common::VectorVector4d> tesseract_geometry::PolygonMesh::vertex_colors_
private

◆ vertex_count_

int tesseract_geometry::PolygonMesh::vertex_count_ { 0 }
private

◆ vertices_

std::shared_ptr<const tesseract_common::VectorVector3d> tesseract_geometry::PolygonMesh::vertices_
private

The documentation for this class was generated from the following files: