MeshManager.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 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 
89  public: void GetMeshAABB(const Mesh *_mesh,
90  ignition::math::Vector3d &_center,
91  ignition::math::Vector3d &_min_xyz,
92  ignition::math::Vector3d &_max_xyz);
93 
97  public: void GenSphericalTexCoord(const Mesh *_mesh,
98  const ignition::math::Vector3d &_center);
99 
105  public: void AddMesh(Mesh *_mesh);
106 
110  public: const Mesh *GetMesh(const std::string &_name) const;
111 
114  public: bool HasMesh(const std::string &_name) const;
115 
121  public: void CreateSphere(const std::string &_name, float _radius,
122  int _rings, int _segments);
123 
128  public: void CreateBox(const std::string &_name,
129  const ignition::math::Vector3d &_sides,
130  const ignition::math::Vector2d &_uvCoords);
131 
144  public: void CreateExtrudedPolyline(const std::string &_name,
145  const std::vector<std::vector<ignition::math::Vector2d> >
146  &_vertices, double _height);
147 
154  public: void CreateCylinder(const std::string &_name,
155  float _radius,
156  float _height,
157  int _rings,
158  int _segments);
159 
166  public: void CreateCone(const std::string &_name,
167  float _radius,
168  float _height,
169  int _rings,
170  int _segments);
171 
183  public: void CreateTube(const std::string &_name,
184  float _innerRadius,
185  float _outterRadius,
186  float _height,
187  int _rings,
188  int _segments,
189  double _arc = 2.0 * M_PI);
190 
196  public: void CreatePlane(const std::string &_name,
197  const ignition::math::Planed &_plane,
198  const ignition::math::Vector2d &_segments,
199  const ignition::math::Vector2d &_uvTile);
200 
208  public: void CreatePlane(const std::string &_name,
209  const ignition::math::Vector3d &_normal,
210  const double _d,
211  const ignition::math::Vector2d &_size,
212  const ignition::math::Vector2d &_segments,
213  const ignition::math::Vector2d &_uvTile);
214 
222  private: void Tesselate2DMesh(SubMesh *_sm,
223  int _meshWidth,
224  int _meshHeight,
225  bool _doubleSided);
226 
230  public: void CreateCamera(const std::string &_name, float _scale);
231 
232 #ifdef HAVE_GTS
233  public: void CreateBoolean(const std::string &_name, const Mesh *_m1,
240  const Mesh *_m2, const int _operation,
241  const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
242 #endif
243 
251  private: static void ConvertPolylinesToVerticesAndEdges(
252  const std::vector<std::vector<ignition::math::Vector2d> >
253  &_polys,
254  double _tol,
255  std::vector<ignition::math::Vector2d> &_vertices,
256  std::vector<ignition::math::Vector2i> &_edges);
257 
265  private: static size_t AddUniquePointToVerticesTable(
266  std::vector<ignition::math::Vector2d> &_vertices,
267  const ignition::math::Vector2d &_p,
268  double _tol);
269 
271  private: ColladaLoader *colladaLoader;
272 
274  private: ColladaExporter *colladaExporter;
275 
277  private: STLLoader *stlLoader;
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:44
Singleton template class.
Definition: SingletonT.hh:33
A child mesh.
Definition: Mesh.hh:216
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
Class used to load STL mesh files.
Definition: STLLoader.hh:40