MeshManager Class Reference

Maintains and manages all meshes. More...

#include <common/common.hh>

Inherits SingletonT< MeshManager >.

Public Member Functions

void AddMesh (Mesh *_mesh)
 Add a mesh to the manager. More...
 
void CreateBox (const std::string &_name, const ignition::math::Vector3d &_sides, const ignition::math::Vector2d &_uvCoords)
 Create a Box mesh. More...
 
void CreateCamera (const std::string &_name, float _scale)
 Create a Camera mesh. More...
 
void CreateCone (const std::string &_name, float _radius, float _height, int _rings, int _segments)
 Create a cone mesh. More...
 
void CreateCylinder (const std::string &_name, float _radius, float _height, int _rings, int _segments)
 Create a cylinder mesh. More...
 
void CreateExtrudedPolyline (const std::string &_name, const std::vector< std::vector< ignition::math::Vector2d > > &_vertices, double _height)
 Create an extruded mesh from polylines. More...
 
void CreatePlane (const std::string &_name, const ignition::math::Planed &_plane, const ignition::math::Vector2d &_segments, const ignition::math::Vector2d &_uvTile)
 Create mesh for a plane. More...
 
void CreatePlane (const std::string &_name, const ignition::math::Vector3d &_normal, const double _d, const ignition::math::Vector2d &_size, const ignition::math::Vector2d &_segments, const ignition::math::Vector2d &_uvTile)
 Create mesh for a plane. More...
 
void CreateSphere (const std::string &_name, float _radius, int _rings, int _segments)
 Create a sphere mesh. More...
 
void CreateTube (const std::string &_name, float _innerRadius, float _outterRadius, float _height, int _rings, int _segments, double _arc=2.0 *M_PI)
 Create a tube mesh. More...
 
void Export (const Mesh *_mesh, const std::string &_filename, const std::string &_extension, bool _exportTextures=false)
 Export a mesh to a file. More...
 
void GenSphericalTexCoord (const Mesh *_mesh, const ignition::math::Vector3d &_center)
 generate spherical texture coordinates More...
 
const MeshGetMesh (const std::string &_name) const
 Get a mesh by name. More...
 
void GetMeshAABB (const Mesh *_mesh, ignition::math::Vector3d &_center, ignition::math::Vector3d &_min_xyz, ignition::math::Vector3d &_max_xyz)
 Get mesh aabb and center. More...
 
bool HasMesh (const std::string &_name) const
 Return true if the mesh exists. More...
 
bool IsValidFilename (const std::string &_filename)
 Checks a path extension against the list of valid extensions. More...
 
const MeshLoad (const std::string &_filename)
 Load a mesh from a file. More...
 

Static Public Member Functions

static MeshManagerInstance ()
 Get an instance of the singleton. More...
 

Detailed Description

Maintains and manages all meshes.

Member Function Documentation

void AddMesh ( Mesh _mesh)

Add a mesh to the manager.

This MeshManager takes ownership of the mesh and will destroy it. See ~MeshManager.

Parameters
[in]themesh to add.
void CreateBox ( const std::string &  _name,
const ignition::math::Vector3d &  _sides,
const ignition::math::Vector2d &  _uvCoords 
)

Create a Box mesh.

Parameters
[in]_namethe name of the new mesh
[in]_sidesthe x y x dimentions of eah side in meter
[in]_uvCoordsthe texture coordinates
void CreateCamera ( const std::string &  _name,
float  _scale 
)

Create a Camera mesh.

Parameters
[in]_namename of the new mesh
[in]_scalescaling factor for the camera
void CreateCone ( const std::string &  _name,
float  _radius,
float  _height,
int  _rings,
int  _segments 
)

Create a cone mesh.

Parameters
[in]_namethe name of the new mesh
[in]_radiusthe radius of the cylinder in the x y plane
[in]_heightthe height along z
[in]_ringsthe number of circles along the height
[in]_segmentsthe number of segment per circle
void CreateCylinder ( const std::string &  _name,
float  _radius,
float  _height,
int  _rings,
int  _segments 
)

Create a cylinder mesh.

Parameters
[in]_namethe name of the new mesh
[in]_radiusthe radius of the cylinder in the x y plane
[in]_heightthe height along z
[in]_ringsthe number of circles along the height
[in]_segmentsthe number of segment per circle
void CreateExtrudedPolyline ( const std::string &  _name,
const std::vector< std::vector< ignition::math::Vector2d > > &  _vertices,
double  _height 
)

Create an extruded mesh from polylines.

The polylines are assumed to be closed and non-intersecting. Delaunay triangulation is applied to create the resulting mesh. If there is more than one polyline, a ray casting algorithm will be used to identify the exterior/interior edges and remove holes from the 2D shape before extrusion.

Parameters
[in]_namethe name of the new mesh
[in]_verticesA multidimensional vector of polylines and their vertices. Each element in the outer vector consists of a vector of vertices that describe one polyline. edges and remove the holes in the shape.
[in]_heightthe height of extrusion
void CreatePlane ( const std::string &  _name,
const ignition::math::Planed &  _plane,
const ignition::math::Vector2d &  _segments,
const ignition::math::Vector2d &  _uvTile 
)

Create mesh for a plane.

Parameters
[in]_name
[in]_planeplane parameters
[in]_segmentsnumber of segments in x and y
[in]_uvTilethe texture tile size in x and y
void CreatePlane ( const std::string &  _name,
const ignition::math::Vector3d &  _normal,
const double  _d,
const ignition::math::Vector2d &  _size,
const ignition::math::Vector2d &  _segments,
const ignition::math::Vector2d &  _uvTile 
)

Create mesh for a plane.

Parameters
[in]_namethe name of the new mesh
[in]_normalthe normal to the plane
[in]_ddistance from the origin along normal
[in]_sizethe size of the plane in x and y
[in]_segmentsthe number of segments in x and y
[in]_uvTilethe texture tile size in x and y
void CreateSphere ( const std::string &  _name,
float  _radius,
int  _rings,
int  _segments 
)

Create a sphere mesh.

Parameters
[in]_namethe name of the mesh
[in]_radiusradius of the sphere in meter
[in]_ringsnumber of circles on th y axis
[in]_segmentsnumber of segment per circle
void CreateTube ( const std::string &  _name,
float  _innerRadius,
float  _outterRadius,
float  _height,
int  _rings,
int  _segments,
double  _arc = 2.0 *M_PI 
)

Create a tube mesh.

Generates rings inside and outside the cylinder Needs at least two rings and 3 segments

Parameters
[in]_namethe name of the new mesh
[in]_innerRadiusthe inner radius of the tube in the x y plane
[in]_outterRadiusthe outer radius of the tube in the x y plane
[in]_heightthe height along z
[in]_ringsthe number of circles along the height
[in]_segmentsthe number of segment per circle
[in]_arcthe arc angle in radians
void Export ( const Mesh _mesh,
const std::string &  _filename,
const std::string &  _extension,
bool  _exportTextures = false 
)

Export a mesh to a file.

Parameters
[in]_meshPointer to the mesh to be exported
[in]_filenameExported file's path and name
[in]_extensionExported file's format ("dae" for Collada)
[in]_exportTexturesTrue to export texture images to '../materials/textures' folder
void GenSphericalTexCoord ( const Mesh _mesh,
const ignition::math::Vector3d &  _center 
)

generate spherical texture coordinates

Parameters
[in]_meshPointer to the mesh
[in]_centerCenter of the mesh
const Mesh* GetMesh ( const std::string &  _name) const

Get a mesh by name.

Parameters
[in]_namethe name of the mesh to look for
Returns
the mesh or nullptr if not found
void GetMeshAABB ( const Mesh _mesh,
ignition::math::Vector3d &  _center,
ignition::math::Vector3d &  _min_xyz,
ignition::math::Vector3d &  _max_xyz 
)

Get mesh aabb and center.

Parameters
[in]_meshthe mesh
[out]_centerthe AAB center position
[out]_min_xyzthe bounding box minimum
[out]_max_xyzthe bounding box maximum
bool HasMesh ( const std::string &  _name) const

Return true if the mesh exists.

Parameters
[in]_namethe name of the mesh
static MeshManager * Instance ( )
inlinestaticinherited

Get an instance of the singleton.

bool IsValidFilename ( const std::string &  _filename)

Checks a path extension against the list of valid extensions.

Returns
true if the file extension is loadable
const Mesh* Load ( const std::string &  _filename)

Load a mesh from a file.

Parameters
[in]_filenamethe path to the mesh
Returns
a pointer to the created mesh

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