MeshManager.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 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 
33 #include "gazebo/util/system.hh"
34 
35 namespace gazebo
36 {
37  namespace common
38  {
39  class ColladaLoader;
40  class ColladaExporter;
41  class FBXLoader;
42  class STLLoader;
43  class Mesh;
44  class Plane;
45  class SubMesh;
46 
49 
52  class GZ_COMMON_VISIBLE MeshManager : public SingletonT<MeshManager>
53  {
55  private: MeshManager();
56 
60  private: virtual ~MeshManager();
61 
65  public: const Mesh *Load(const std::string &_filename);
66 
73  public: void Export(const Mesh *_mesh, const std::string &_filename,
74  const std::string &_extension, bool _exportTextures = false);
75 
78  public: bool IsValidFilename(const std::string &_filename);
79 
85  public: void GetMeshAABB(const Mesh *_mesh,
86  ignition::math::Vector3d &_center,
87  ignition::math::Vector3d &_min_xyz,
88  ignition::math::Vector3d &_max_xyz);
89 
93  public: void GenSphericalTexCoord(const Mesh *_mesh,
94  const ignition::math::Vector3d &_center);
95 
101  public: void AddMesh(Mesh *_mesh);
102 
106  public: const Mesh *GetMesh(const std::string &_name) const;
107 
110  public: bool HasMesh(const std::string &_name) const;
111 
117  public: void CreateSphere(const std::string &_name, float _radius,
118  int _rings, int _segments);
119 
124  public: void CreateBox(const std::string &_name,
125  const ignition::math::Vector3d &_sides,
126  const ignition::math::Vector2d &_uvCoords);
127 
140  public: void CreateExtrudedPolyline(const std::string &_name,
141  const std::vector<std::vector<ignition::math::Vector2d> >
142  &_vertices, double _height);
143 
150  public: void CreateCylinder(const std::string &_name,
151  float _radius,
152  float _height,
153  int _rings,
154  int _segments);
155 
162  public: void CreateCone(const std::string &_name,
163  float _radius,
164  float _height,
165  int _rings,
166  int _segments);
167 
179  public: void CreateTube(const std::string &_name,
180  float _innerRadius,
181  float _outterRadius,
182  float _height,
183  int _rings,
184  int _segments,
185  double _arc = 2.0 * M_PI);
186 
192  public: void CreatePlane(const std::string &_name,
193  const ignition::math::Planed &_plane,
194  const ignition::math::Vector2d &_segments,
195  const ignition::math::Vector2d &_uvTile);
196 
204  public: void CreatePlane(const std::string &_name,
205  const ignition::math::Vector3d &_normal,
206  const double _d,
207  const ignition::math::Vector2d &_size,
208  const ignition::math::Vector2d &_segments,
209  const ignition::math::Vector2d &_uvTile);
210 
218  private: void Tesselate2DMesh(SubMesh *_sm,
219  int _meshWidth,
220  int _meshHeight,
221  bool _doubleSided);
222 
226  public: void CreateCamera(const std::string &_name, float _scale);
227 
228 #ifdef HAVE_GTS
229  public: void CreateBoolean(const std::string &_name, const Mesh *_m1,
236  const Mesh *_m2, const int _operation,
237  const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
238 #endif
239 
247  private: static void ConvertPolylinesToVerticesAndEdges(
248  const std::vector<std::vector<ignition::math::Vector2d> >
249  &_polys,
250  double _tol,
251  std::vector<ignition::math::Vector2d> &_vertices,
252  std::vector<ignition::math::Vector2i> &_edges);
253 
261  private: static size_t AddUniquePointToVerticesTable(
262  std::vector<ignition::math::Vector2d> &_vertices,
263  const ignition::math::Vector2d &_p,
264  double _tol);
265 
267  private: ColladaLoader *colladaLoader = nullptr;
268 
270  private: ColladaExporter *colladaExporter = nullptr;
271 
273  private: STLLoader *stlLoader = nullptr;
274 
277  private: FBXLoader *fbxLoader = nullptr;
278 
280  private: std::map<std::string, Mesh*> meshes;
281 
283  private: std::vector<std::string> fileExtensions;
284 
285  private: boost::mutex mutex;
286 
288  private: friend class SingletonT<MeshManager>;
289  };
291  }
292 }
293 #endif
A 3D mesh.
Definition: Mesh.hh:42
Singleton template class.
Definition: SingletonT.hh:33
A child mesh.
Definition: Mesh.hh:214
Class used to load Collada mesh files.
Definition: ColladaLoader.hh:46
Maintains and manages all meshes.
Definition: MeshManager.hh:52
Class used to export Collada mesh files.
Definition: ColladaExporter.hh:42
Class used to load STL mesh files.
Definition: STLLoader.hh:40