17 #ifndef GAZEBO_COMMON_MESHMANAGER_HH_
18 #define GAZEBO_COMMON_MESHMANAGER_HH_
24 #include <ignition/math/Plane.hh>
25 #include <ignition/math/Pose3.hh>
26 #include <ignition/math/Vector2.hh>
27 #include <ignition/math/Vector3.hh>
41 class MeshManagerPrivate;
63 public:
const Mesh *
Load(
const std::string &_filename);
71 public:
void Export(
const Mesh *_mesh,
const std::string &_filename,
72 const std::string &_extension,
bool _exportTextures =
false);
84 ignition::math::Vector3d &_center,
85 ignition::math::Vector3d &_min_xyz,
86 ignition::math::Vector3d &_max_xyz);
92 const ignition::math::Vector3d &_center);
108 public:
bool HasMesh(
const std::string &_name)
const;
116 int _rings,
int _segments);
123 const ignition::math::Vector3d &_sides,
124 const ignition::math::Vector2d &_uvCoords);
139 const std::vector<std::vector<ignition::math::Vector2d> >
140 &_vertices,
double _height);
183 double _arc = 2.0 * M_PI);
191 const ignition::math::Planed &_plane,
192 const ignition::math::Vector2d &_segments,
193 const ignition::math::Vector2d &_uvTile);
203 const ignition::math::Vector3d &_normal,
205 const ignition::math::Vector2d &_size,
206 const ignition::math::Vector2d &_segments,
207 const ignition::math::Vector2d &_uvTile);
216 private:
void Tesselate2DMesh(
SubMesh *_sm,
233 public:
void CreateBoolean(
const std::string &_name,
const Mesh *_m1,
234 const Mesh *_m2,
const int _operation,
235 const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
245 private:
static void ConvertPolylinesToVerticesAndEdges(
246 const std::vector<std::vector<ignition::math::Vector2d> >
249 std::vector<ignition::math::Vector2d> &_vertices,
250 std::vector<ignition::math::Vector2i> &_edges);
259 private:
static size_t AddUniquePointToVerticesTable(
260 std::vector<ignition::math::Vector2d> &_vertices,
261 const ignition::math::Vector2d &_p,
269 private: MeshManagerPrivate *dataPtr;
common
Definition: MeshManager.hh:34
Singleton template class.
Definition: SingletonT.hh:34
Maintains and manages all meshes.
Definition: MeshManager.hh:51
void CreateExtrudedPolyline(const std::string &_name, const std::vector< std::vector< ignition::math::Vector2d > > &_vertices, double _height)
Create an extruded mesh from polylines.
const Mesh * Load(const std::string &_filename)
Load a mesh from a file.
void CreateSphere(const std::string &_name, float _radius, int _rings, int _segments)
Create a sphere mesh.
void CreateCamera(const std::string &_name, float _scale)
Create a Camera mesh.
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.
void CreateCone(const std::string &_name, float _radius, float _height, int _rings, int _segments)
Create a cone mesh.
void AddMesh(Mesh *_mesh)
Add a mesh to the manager.
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.
void Export(const Mesh *_mesh, const std::string &_filename, const std::string &_extension, bool _exportTextures=false)
Export a mesh to a file.
void CreateBox(const std::string &_name, const ignition::math::Vector3d &_sides, const ignition::math::Vector2d &_uvCoords)
Create a Box mesh.
const Mesh * GetMesh(const std::string &_name) const
Get a mesh by name.
void GetMeshAABB(const Mesh *_mesh, ignition::math::Vector3d &_center, ignition::math::Vector3d &_min_xyz, ignition::math::Vector3d &_max_xyz)
Get mesh aabb and center.
bool IsValidFilename(const std::string &_filename)
Checks a path extension against the list of valid extensions.
bool HasMesh(const std::string &_name) const
Return true if the mesh exists.
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.
void GenSphericalTexCoord(const Mesh *_mesh, const ignition::math::Vector3d &_center)
generate spherical texture coordinates
void CreateCylinder(const std::string &_name, float _radius, float _height, int _rings, int _segments)
Create a cylinder mesh.
A 3D mesh.
Definition: Mesh.hh:43
A child mesh.
Definition: Mesh.hh:215
#define GZ_SINGLETON_DECLARE(visibility, n1, n2, singletonType)
Helper to declare typed SingletonT.
Definition: SingletonT.hh:58
Forward declarations for the common classes.
Definition: Animation.hh:27