Maintains and manages all meshes. Supported mesh formats are STL (STLA, STLB), COLLADA, OBJ, GLTF (GLB) and FBX. By default only GLTF and FBX are loaded using assimp loader, however if GZ_MESH_FORCE_ASSIMP environment variable is set, then MeshManager will use assimp loader for all supported mesh formats. More...
#include <gz/common/MeshManager.hh>
Public Member Functions | |
void | AddMesh (Mesh *_mesh) |
Add a mesh to the manager. More... | |
void | CreateBoolean (const std::string &_name, const Mesh *_m1, const Mesh *_m2, const int _operation, const gz::math::Pose3d &_offset=gz::math::Pose3d::Zero) |
Create a boolean mesh from two meshes. More... | |
void | CreateBox (const std::string &_name, const gz::math::Vector3d &_sides, const gz::math::Vector2d &_uvCoords) |
Create a Box mesh. More... | |
void | CreateCamera (const std::string &_name, const float _scale) |
Create a Camera mesh. More... | |
void | CreateCapsule (const std::string &_name, const double radius, const double length, const unsigned int _rings, const unsigned int _segments) |
Create a capsule mesh. More... | |
void | CreateCone (const std::string &_name, const float _radius, const float _height, const int _rings, const int _segments) |
Create a cone mesh. More... | |
void | CreateCylinder (const std::string &_name, const float _radius, const float _height, const int _rings, const int _segments) |
Create a cylinder mesh. More... | |
void | CreateEllipsoid (const std::string &_name, const gz::math::Vector3d &_radii, const unsigned int _rings, const unsigned int _segments) |
Create a ellipsoid mesh. More... | |
void | CreateExtrudedPolyline (const std::string &_name, const std::vector< std::vector< gz::math::Vector2d > > &_vertices, const 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. More... | |
void | CreatePlane (const std::string &_name, const gz::math::Planed &_plane, const gz::math::Vector2d &_segments, const gz::math::Vector2d &_uvTile) |
Create mesh for a plane. More... | |
void | CreatePlane (const std::string &_name, const gz::math::Vector3d &_normal, const double _d, const gz::math::Vector2d &_size, const gz::math::Vector2d &_segments, const gz::math::Vector2d &_uvTile) |
Create mesh for a plane. More... | |
void | CreateSphere (const std::string &_name, const float _radius, const int _rings, const int _segments) |
Create a sphere mesh. More... | |
void | CreateTube (const std::string &_name, const float _innerRadius, const float _outterRadius, const float _height, const int _rings, const int _segments, const double _arc=2.0 *GZ_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 gz::math::Vector3d &_center) |
generate spherical texture coordinates 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 Mesh * | Load (const std::string &_filename) |
Load a mesh from a file. The mesh will be searched on the global SystemPaths instance provided by Util.hh. More... | |
void | MeshAABB (const Mesh *_mesh, gz::math::Vector3d &_center, gz::math::Vector3d &_min_xyz, gz::math::Vector3d &_max_xyz) |
Get mesh aabb and center. More... | |
const Mesh * | MeshByName (const std::string &_name) const |
Get a mesh by name. More... | |
void | RemoveAll () |
Remove all meshes. More... | |
bool | RemoveMesh (const std::string &_name) |
Remove a mesh based on a name. More... | |
void | SetAssimpEnvs () |
Sets the forceAssimp flag by reading the GZ_MESH_FORCE_ASSIMP environment variable. If forceAssimp true, MeshManager uses Assimp for loading all mesh formats, otherwise only for GLTF and FBX. More... | |
Static Public Member Functions | |
static std::vector< SubMesh > | ConvexDecomposition (const common::SubMesh &_subMesh, std::size_t _maxConvexHulls=16u, std::size_t _voxelResolution=200000u) |
Perform convex decomposition on a submesh. The submesh is decomposed into multiple convex submeshes. The output submeshes contain vertices and indices but texture coordinates are not preserved. More... | |
static MeshManager * | Instance () |
static std::unique_ptr< Mesh > | MergeSubMeshes (const common::Mesh &_mesh) |
Merge all submeshes from one mesh into one single submesh. More... | |
Static Public Member Functions inherited from SingletonT< MeshManager > | |
static MeshManager * | Instance () |
Get an instance of the singleton. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from SingletonT< MeshManager > | |
SingletonT () | |
Constructor. More... | |
virtual | ~SingletonT () |
Destructor. More... | |
Detailed Description
Maintains and manages all meshes. Supported mesh formats are STL (STLA, STLB), COLLADA, OBJ, GLTF (GLB) and FBX. By default only GLTF and FBX are loaded using assimp loader, however if GZ_MESH_FORCE_ASSIMP environment variable is set, then MeshManager will use assimp loader for all supported mesh formats.
Member Function Documentation
◆ AddMesh()
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] the mesh to add.
◆ ConvexDecomposition()
|
static |
Perform convex decomposition on a submesh. The submesh is decomposed into multiple convex submeshes. The output submeshes contain vertices and indices but texture coordinates are not preserved.
- Parameters
-
[in] _subMesh Input submesh to decompose. [in] _maxConvexHulls Maximum number of convex hull submeshes to produce. [in] _voxelResolution Voxel resolution to use. Higher value produces more accurate shapes.
- Returns
- A vector of decomposed submeshes.
◆ CreateBoolean()
void CreateBoolean | ( | const std::string & | _name, |
const Mesh * | _m1, | ||
const Mesh * | _m2, | ||
const int | _operation, | ||
const gz::math::Pose3d & | _offset = gz::math::Pose3d::Zero |
||
) |
Create a boolean mesh from two meshes.
- Parameters
-
[in] _name the name of the new mesh [in] _m1 the parent mesh in the boolean operation [in] _m2 the child mesh in the boolean operation [in] _operation the boolean operation applied to the two meshes [in] _offset _m2's pose offset from _m1
◆ CreateBox()
void CreateBox | ( | const std::string & | _name, |
const gz::math::Vector3d & | _sides, | ||
const gz::math::Vector2d & | _uvCoords | ||
) |
Create a Box mesh.
- Parameters
-
[in] _name the name of the new mesh [in] _sides the x y x dimentions of eah side in meter [in] _uvCoords the texture coordinates
◆ CreateCamera()
void CreateCamera | ( | const std::string & | _name, |
const float | _scale | ||
) |
Create a Camera mesh.
- Parameters
-
[in] _name name of the new mesh [in] _scale scaling factor for the camera
◆ CreateCapsule()
void CreateCapsule | ( | const std::string & | _name, |
const double | radius, | ||
const double | length, | ||
const unsigned int | _rings, | ||
const unsigned int | _segments | ||
) |
Create a capsule mesh.
- Parameters
-
[in] _name the name of the new mesh [in] _radius the radius of the capsule in the x y plane [in] _length length of the capsule along z [in] _rings the number of circles along the height [in] _segments the number of segments per circle
◆ CreateCone()
void CreateCone | ( | const std::string & | _name, |
const float | _radius, | ||
const float | _height, | ||
const int | _rings, | ||
const int | _segments | ||
) |
Create a cone mesh.
- Parameters
-
[in] _name the name of the new mesh [in] _radius the radius of the cylinder in the x y plane [in] _height the height along z [in] _rings the number of circles along the height [in] _segments the number of segment per circle
◆ CreateCylinder()
void CreateCylinder | ( | const std::string & | _name, |
const float | _radius, | ||
const float | _height, | ||
const int | _rings, | ||
const int | _segments | ||
) |
Create a cylinder mesh.
- Parameters
-
[in] _name the name of the new mesh [in] _radius the radius of the cylinder in the x y plane [in] _height the height along z [in] _rings the number of circles along the height [in] _segments the number of segment per circle
◆ CreateEllipsoid()
void CreateEllipsoid | ( | const std::string & | _name, |
const gz::math::Vector3d & | _radii, | ||
const unsigned int | _rings, | ||
const unsigned int | _segments | ||
) |
Create a ellipsoid mesh.
- Parameters
-
[in] _name the name of the new mesh [in] _radii the three radius that define a ellipsoid [in] _rings the number of circles along the height [in] _segments the number of segment per circle
◆ CreateExtrudedPolyline()
void CreateExtrudedPolyline | ( | const std::string & | _name, |
const std::vector< std::vector< gz::math::Vector2d > > & | _vertices, | ||
const 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] _name the name of the new mesh [in] _vertices A 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] _height the height of extrusion
◆ CreatePlane() [1/2]
void CreatePlane | ( | const std::string & | _name, |
const gz::math::Planed & | _plane, | ||
const gz::math::Vector2d & | _segments, | ||
const gz::math::Vector2d & | _uvTile | ||
) |
Create mesh for a plane.
- Parameters
-
[in] _name [in] _plane plane parameters [in] _segments number of segments in x and y [in] _uvTile the texture tile size in x and y
◆ CreatePlane() [2/2]
void CreatePlane | ( | const std::string & | _name, |
const gz::math::Vector3d & | _normal, | ||
const double | _d, | ||
const gz::math::Vector2d & | _size, | ||
const gz::math::Vector2d & | _segments, | ||
const gz::math::Vector2d & | _uvTile | ||
) |
Create mesh for a plane.
- Parameters
-
[in] _name the name of the new mesh [in] _normal the normal to the plane [in] _d distance from the origin along normal [in] _size the size of the plane in x and y [in] _segments the number of segments in x and y [in] _uvTile the texture tile size in x and y
◆ CreateSphere()
void CreateSphere | ( | const std::string & | _name, |
const float | _radius, | ||
const int | _rings, | ||
const int | _segments | ||
) |
Create a sphere mesh.
- Parameters
-
[in] _name the name of the mesh [in] _radius radius of the sphere in meter [in] _rings number of circles on th y axis [in] _segments number of segment per circle
◆ CreateTube()
void CreateTube | ( | const std::string & | _name, |
const float | _innerRadius, | ||
const float | _outterRadius, | ||
const float | _height, | ||
const int | _rings, | ||
const int | _segments, | ||
const double | _arc = 2.0 *GZ_PI |
||
) |
Create a tube mesh.
Generates rings inside and outside the cylinder Needs at least two rings and 3 segments
- Parameters
-
[in] _name the name of the new mesh [in] _innerRadius the inner radius of the tube in the x y plane [in] _outterRadius the outer radius of the tube in the x y plane [in] _height the height along z [in] _rings the number of circles along the height [in] _segments the number of segment per circle [in] _arc the arc angle in radians
◆ Export()
void Export | ( | const Mesh * | _mesh, |
const std::string & | _filename, | ||
const std::string & | _extension, | ||
bool | _exportTextures = false |
||
) |
Export a mesh to a file.
- Parameters
-
[in] _mesh Pointer to the mesh to be exported [in] _filename Exported file's path and name [in] _extension Exported file's format ("dae" for Collada) [in] _exportTextures True to export texture images to '../materials/textures' folder
◆ GenSphericalTexCoord()
void GenSphericalTexCoord | ( | const Mesh * | _mesh, |
const gz::math::Vector3d & | _center | ||
) |
generate spherical texture coordinates
- Parameters
-
[in] _mesh Pointer to the mesh [in] _center Center of the mesh
◆ HasMesh()
bool HasMesh | ( | const std::string & | _name | ) | const |
Return true if the mesh exists.
- Parameters
-
[in] _name the name of the mesh
◆ Instance()
|
static |
Return a pointer to the mesh manager
- Todo:
- (ahcorde) Remove inheritance from Singleton base class
- Returns
- a pointer to the mesh manager
◆ IsValidFilename()
bool IsValidFilename | ( | const std::string & | _filename | ) |
Checks a path extension against the list of valid extensions.
- Returns
- true if the file extension is loadable
◆ Load()
const Mesh* Load | ( | const std::string & | _filename | ) |
Load a mesh from a file. The mesh will be searched on the global SystemPaths instance provided by Util.hh.
- Parameters
-
[in] _filename the path to the mesh
- Returns
- a pointer to the created mesh
◆ MergeSubMeshes()
|
static |
Merge all submeshes from one mesh into one single submesh.
- Parameters
-
[in] _mesh Input mesh with submeshes to merge.
- Returns
- A new mesh with the submeshes merged.
◆ MeshAABB()
void MeshAABB | ( | const Mesh * | _mesh, |
gz::math::Vector3d & | _center, | ||
gz::math::Vector3d & | _min_xyz, | ||
gz::math::Vector3d & | _max_xyz | ||
) |
Get mesh aabb and center.
- Parameters
-
[in] _mesh the mesh [out] _center the AAB center position [out] _min_xyz the bounding box minimum [out] _max_xyz the bounding box maximum
◆ MeshByName()
const Mesh* MeshByName | ( | const std::string & | _name | ) | const |
Get a mesh by name.
- Parameters
-
[in] _name the name of the mesh to look for
- Returns
- the mesh or nullptr if not found
◆ RemoveAll()
void RemoveAll | ( | ) |
Remove all meshes.
◆ RemoveMesh()
bool RemoveMesh | ( | const std::string & | _name | ) |
Remove a mesh based on a name.
- Parameters
-
[in] _name Name of the mesh to remove.
- Returns
- True if the mesh was removed, false if the mesh with the provided name could not be found.
◆ SetAssimpEnvs()
void SetAssimpEnvs | ( | ) |
Sets the forceAssimp flag by reading the GZ_MESH_FORCE_ASSIMP environment variable. If forceAssimp true, MeshManager uses Assimp for loading all mesh formats, otherwise only for GLTF and FBX.
The documentation for this class was generated from the following file: