MeshManager.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GAZEBO_MESHMANAGER_HH_
18 #define _GAZEBO_MESHMANAGER_HH_
19 
20 #include <map>
21 #include <utility>
22 #include <string>
23 #include <vector>
24 #include <boost/thread/mutex.hpp>
25 
26 #include <ignition/math/Plane.hh>
27 #include <ignition/math/Matrix3.hh>
28 #include <ignition/math/Matrix4.hh>
29 #include <ignition/math/Vector2.hh>
30 
31 #include "gazebo/math/Vector3.hh"
32 #include "gazebo/math/Vector2d.hh"
33 #include "gazebo/math/Vector2i.hh"
34 #include "gazebo/math/Pose.hh"
35 #include "gazebo/math/Plane.hh"
38 #include "gazebo/util/system.hh"
39 
40 namespace gazebo
41 {
42  namespace common
43  {
44  class ColladaLoader;
45  class ColladaExporter;
46  class STLLoader;
47  class Mesh;
48  class Plane;
49  class SubMesh;
50 
53 
56  class GZ_COMMON_VISIBLE MeshManager : public SingletonT<MeshManager>
57  {
59  private: MeshManager();
60 
64  private: virtual ~MeshManager();
65 
69  public: const Mesh *Load(const std::string &_filename);
70 
77  public: void Export(const Mesh *_mesh, const std::string &_filename,
78  const std::string &_extension, bool _exportTextures = false);
79 
82  public: bool IsValidFilename(const std::string &_filename);
83 
90  public: void GetMeshAABB(const Mesh *_mesh,
91  math::Vector3 &_center,
92  math::Vector3 &_minXYZ,
93  math::Vector3 &_maxXYZ) GAZEBO_DEPRECATED(6.0);
94 
100  public: void GetMeshAABB(const Mesh *_mesh,
101  ignition::math::Vector3d &_center,
102  ignition::math::Vector3d &_min_xyz,
103  ignition::math::Vector3d &_max_xyz);
104 
110  public: void GenSphericalTexCoord(const Mesh *_mesh,
111  math::Vector3 _center) GAZEBO_DEPRECATED(6.0);
112 
116  public: void GenSphericalTexCoord(const Mesh *_mesh,
117  const ignition::math::Vector3d &_center);
118 
124  public: void AddMesh(Mesh *_mesh);
125 
129  public: const Mesh *GetMesh(const std::string &_name) const;
130 
133  public: bool HasMesh(const std::string &_name) const;
134 
140  public: void CreateSphere(const std::string &_name, float _radius,
141  int _rings, int _segments);
142 
149  public: void CreateBox(const std::string &_name,
150  const math::Vector3 &_sides,
151  const math::Vector2d &_uvCoords) GAZEBO_DEPRECATED(6.0);
152 
157  public: void CreateBox(const std::string &_name,
158  const ignition::math::Vector3d &_sides,
159  const ignition::math::Vector2d &_uvCoords);
160 
175  public: void CreateExtrudedPolyline(const std::string &_name,
176  const std::vector<std::vector<math::Vector2d> > &_vertices,
177  double _height) GAZEBO_DEPRECATED(6.0);
178 
191  public: void CreateExtrudedPolyline(const std::string &_name,
192  const std::vector<std::vector<ignition::math::Vector2d> >
193  &_vertices, double _height);
194 
201  public: void CreateCylinder(const std::string &_name,
202  float _radius,
203  float _height,
204  int _rings,
205  int _segments);
206 
213  public: void CreateCone(const std::string &_name,
214  float _radius,
215  float _height,
216  int _rings,
217  int _segments);
218 
230  public: void CreateTube(const std::string &_name,
231  float _innerRadius,
232  float _outterRadius,
233  float _height,
234  int _rings,
235  int _segments,
236  double _arc = 2.0 * M_PI);
237 
245  public: void CreatePlane(const std::string &_name,
246  const math::Plane &_plane,
247  const math::Vector2d &_segments,
248  const math::Vector2d &_uvTile) GAZEBO_DEPRECATED(6.0);
249 
255  public: void CreatePlane(const std::string &_name,
256  const ignition::math::Planed &_plane,
257  const ignition::math::Vector2d &_segments,
258  const ignition::math::Vector2d &_uvTile);
259 
269  public: void CreatePlane(const std::string &_name,
270  const math::Vector3 &_normal,
271  double _d,
272  const math::Vector2d &_size,
273  const math::Vector2d &_segments,
274  const math::Vector2d &_uvTile) GAZEBO_DEPRECATED(6.0);
275 
283  public: void CreatePlane(const std::string &_name,
284  const ignition::math::Vector3d &_normal,
285  const double _d,
286  const ignition::math::Vector2d &_size,
287  const ignition::math::Vector2d &_segments,
288  const ignition::math::Vector2d &_uvTile);
289 
297  private: void Tesselate2DMesh(SubMesh *_sm,
298  int _meshWidth,
299  int _meshHeight,
300  bool _doubleSided);
301 
305  public: void CreateCamera(const std::string &_name, float _scale);
306 
307 #ifdef HAVE_GTS
308  public: void CreateBoolean(const std::string &_name, const Mesh *_m1,
317  const Mesh *_m2, const int _operation,
318  const math::Pose &_offset = math::Pose::Zero) GAZEBO_DEPRECATED(6.0);
319 
326  public: void CreateBoolean(const std::string &_name, const Mesh *_m1,
327  const Mesh *_m2, const int _operation,
328  const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
329 #endif
330 
338  private: static void ConvertPolylinesToVerticesAndEdges(
339  const std::vector<std::vector<ignition::math::Vector2d> >
340  &_polys,
341  double _tol,
342  std::vector<ignition::math::Vector2d> &_vertices,
343  std::vector<ignition::math::Vector2i> &_edges);
344 
352  private: static size_t AddUniquePointToVerticesTable(
353  std::vector<ignition::math::Vector2d> &_vertices,
354  const ignition::math::Vector2d &_p,
355  double _tol);
356 
358  private: ColladaLoader *colladaLoader;
359 
361  private: ColladaExporter *colladaExporter;
362 
364  private: STLLoader *stlLoader;
365 
367  private: std::map<std::string, Mesh*> meshes;
368 
370  private: std::vector<std::string> fileExtensions;
371 
372  private: boost::mutex mutex;
373 
375  private: friend class SingletonT<MeshManager>;
376  };
378  }
379 }
380 #endif
A 3D mesh.
Definition: Mesh.hh:44
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
Generic double x, y vector.
Definition: Vector2d.hh:36
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:47
Singleton template class.
Definition: SingletonT.hh:33
A child mesh.
Definition: Mesh.hh:265
#define GZ_COMMON_VISIBLE
Definition: system.hh:91
A plane and related functions.
Definition: Plane.hh:35
Class used to load Collada mesh files.
Definition: ColladaLoader.hh:46
Maintains and manages all meshes.
Definition: MeshManager.hh:56
Class used to export Collada mesh files.
Definition: ColladaExporter.hh:42
static const Pose Zero
math::Pose(0, 0, 0, 0, 0, 0)
Definition: Pose.hh:40
Class used to load STL mesh files.
Definition: STLLoader.hh:40