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 STLLoader;
42  class Mesh;
43  class Plane;
44  class SubMesh;
45 
48 
51  class GZ_COMMON_VISIBLE MeshManager : public SingletonT<MeshManager>
52  {
54  private: MeshManager();
55 
59  private: virtual ~MeshManager();
60 
64  public: const Mesh *Load(const std::string &_filename);
65 
72  public: void Export(const Mesh *_mesh, const std::string &_filename,
73  const std::string &_extension, bool _exportTextures = false);
74 
77  public: bool IsValidFilename(const std::string &_filename);
78 
84  public: void GetMeshAABB(const Mesh *_mesh,
85  ignition::math::Vector3d &_center,
86  ignition::math::Vector3d &_min_xyz,
87  ignition::math::Vector3d &_max_xyz);
88 
92  public: void GenSphericalTexCoord(const Mesh *_mesh,
93  const ignition::math::Vector3d &_center);
94 
100  public: void AddMesh(Mesh *_mesh);
101 
105  public: const Mesh *GetMesh(const std::string &_name) const;
106 
109  public: bool HasMesh(const std::string &_name) const;
110 
116  public: void CreateSphere(const std::string &_name, float _radius,
117  int _rings, int _segments);
118 
123  public: void CreateBox(const std::string &_name,
124  const ignition::math::Vector3d &_sides,
125  const ignition::math::Vector2d &_uvCoords);
126 
139  public: void CreateExtrudedPolyline(const std::string &_name,
140  const std::vector<std::vector<ignition::math::Vector2d> >
141  &_vertices, double _height);
142 
149  public: void CreateCylinder(const std::string &_name,
150  float _radius,
151  float _height,
152  int _rings,
153  int _segments);
154 
161  public: void CreateCone(const std::string &_name,
162  float _radius,
163  float _height,
164  int _rings,
165  int _segments);
166 
178  public: void CreateTube(const std::string &_name,
179  float _innerRadius,
180  float _outterRadius,
181  float _height,
182  int _rings,
183  int _segments,
184  double _arc = 2.0 * M_PI);
185 
191  public: void CreatePlane(const std::string &_name,
192  const ignition::math::Planed &_plane,
193  const ignition::math::Vector2d &_segments,
194  const ignition::math::Vector2d &_uvTile);
195 
203  public: void CreatePlane(const std::string &_name,
204  const ignition::math::Vector3d &_normal,
205  const double _d,
206  const ignition::math::Vector2d &_size,
207  const ignition::math::Vector2d &_segments,
208  const ignition::math::Vector2d &_uvTile);
209 
217  private: void Tesselate2DMesh(SubMesh *_sm,
218  int _meshWidth,
219  int _meshHeight,
220  bool _doubleSided);
221 
225  public: void CreateCamera(const std::string &_name, float _scale);
226 
227 #ifdef HAVE_GTS
228  public: void CreateBoolean(const std::string &_name, const Mesh *_m1,
235  const Mesh *_m2, const int _operation,
236  const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
237 #endif
238 
246  private: static void ConvertPolylinesToVerticesAndEdges(
247  const std::vector<std::vector<ignition::math::Vector2d> >
248  &_polys,
249  double _tol,
250  std::vector<ignition::math::Vector2d> &_vertices,
251  std::vector<ignition::math::Vector2i> &_edges);
252 
260  private: static size_t AddUniquePointToVerticesTable(
261  std::vector<ignition::math::Vector2d> &_vertices,
262  const ignition::math::Vector2d &_p,
263  double _tol);
264 
266  private: ColladaLoader *colladaLoader;
267 
269  private: ColladaExporter *colladaExporter;
270 
272  private: STLLoader *stlLoader;
273 
275  private: std::map<std::string, Mesh*> meshes;
276 
278  private: std::vector<std::string> fileExtensions;
279 
280  private: boost::mutex mutex;
281 
283  private: friend class SingletonT<MeshManager>;
284  };
286  }
287 }
288 #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:51
Class used to export Collada mesh files.
Definition: ColladaExporter.hh:42
Class used to load STL mesh files.
Definition: STLLoader.hh:40