Scene.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 
18 #ifndef _SCENE_HH_
19 #define _SCENE_HH_
20 
21 #include <string>
22 #include <vector>
23 #include <boost/enable_shared_from_this.hpp>
24 #include <boost/shared_ptr.hpp>
25 
26 #include <sdf/sdf.hh>
27 
28 #include "gazebo/common/Events.hh"
29 #include "gazebo/common/Color.hh"
30 #include "gazebo/gazebo_config.h"
31 #include "gazebo/math/Vector2i.hh"
32 #include "gazebo/msgs/msgs.hh"
36 #include "gazebo/util/system.hh"
37 
38 namespace SkyX
39 {
40  class SkyX;
41 }
42 
43 namespace Ogre
44 {
45  class SceneManager;
46  class Node;
47  class Entity;
48  class Mesh;
49  class Vector3;
50  class Quaternion;
51 }
52 
53 namespace gazebo
54 {
55  namespace rendering
56  {
57  class Visual;
58  class Grid;
59  class Heightmap;
60  class ScenePrivate;
61 
64 
70  public boost::enable_shared_from_this<Scene>
71  {
72  public: enum SkyXMode {
73  GZ_SKYX_ALL = 0x0FFFFFFF,
74  GZ_SKYX_CLOUDS = 0x0000001,
75  GZ_SKYX_MOON = 0x0000002,
76  GZ_SKYX_NONE = 0
77  };
78 
80  private: Scene() {}
81 
87  public: Scene(const std::string &_name,
88  bool _enableVisualizations = false,
89  bool _isServer = false);
90 
92  public: virtual ~Scene();
93 
96  public: void Load(sdf::ElementPtr _scene);
97 
99  public: void Load();
100 
102  public: void Init();
103 
105  public: void PreRender();
106 
109  public: Ogre::SceneManager *GetManager() const;
110 
113  public: std::string GetName() const;
114 
117  public: void SetAmbientColor(const common::Color &_color);
118 
121  public: common::Color GetAmbientColor() const;
122 
125  public: void SetBackgroundColor(const common::Color &_color);
126 
129  public: common::Color GetBackgroundColor() const;
130 
136  public: void CreateGrid(uint32_t _cellCount, float _cellLength,
137  float _lineWidth, const common::Color &_color);
138 
142  public: Grid *GetGrid(uint32_t _index) const;
143 
146  public: uint32_t GetGridCount() const;
147 
153  public: CameraPtr CreateCamera(const std::string &_name,
154  bool _autoRender = true);
155 
156 #ifdef HAVE_OCULUS
157  public: OculusCameraPtr CreateOculusCamera(const std::string &_name);
161 
164  public: uint32_t GetOculusCameraCount() const;
165 #endif
166 
172  public: DepthCameraPtr CreateDepthCamera(const std::string &_name,
173  bool _autoRender = true);
174 
180  public: GpuLaserPtr CreateGpuLaser(const std::string &_name,
181  bool _autoRender = true);
182 
185  public: uint32_t GetCameraCount() const;
186 
191  public: CameraPtr GetCamera(uint32_t _index) const;
192 
196  public: CameraPtr GetCamera(const std::string &_name) const;
197 
205  public: UserCameraPtr CreateUserCamera(const std::string &_name,
206  bool _stereoEnabled = false);
207 
210  public: uint32_t GetUserCameraCount() const;
211 
217  public: UserCameraPtr GetUserCamera(uint32_t _index) const;
218 
221  public: void RemoveCamera(const std::string &_name);
222 
226  public: LightPtr GetLight(const std::string &_name) const;
227 
230  public: uint32_t GetLightCount() const;
231 
236  public: LightPtr GetLight(uint32_t _index) const;
237 
241  public: VisualPtr GetVisual(const std::string &_name) const;
242 
246  public: VisualPtr GetVisual(uint32_t _id) const;
247 
251  public: void SelectVisual(const std::string &_name,
252  const std::string &_mode);
253 
260  public: VisualPtr GetVisualAt(CameraPtr _camera,
261  const math::Vector2i &_mousePos,
262  std::string &_mod);
263 
266  public: void SnapVisualToNearestBelow(const std::string &_visualName);
267 
273  public: VisualPtr GetVisualAt(CameraPtr _camera,
274  const math::Vector2i &_mousePos);
275 
281  public: VisualPtr GetModelVisualAt(CameraPtr _camera,
282  const math::Vector2i &_mousePos);
283 
284 
288  public: VisualPtr GetVisualBelow(const std::string &_visualName);
289 
294  public: void GetVisualsBelowPoint(const math::Vector3 &_pt,
295  std::vector<VisualPtr> &_visuals);
296 
297 
302  public: double GetHeightBelowPoint(const math::Vector3 &_pt);
303 
309  public: bool GetFirstContact(CameraPtr _camera,
310  const math::Vector2i &_mousePos,
311  math::Vector3 &_position);
312 
314  public: void PrintSceneGraph();
315 
320  public: void SetVisible(const std::string &_name, bool _visible);
321 
326  public: void DrawLine(const math::Vector3 &_start,
327  const math::Vector3 &_end,
328  const std::string &_name);
329 
337  public: void SetFog(const std::string &_type,
338  const common::Color &_color,
339  double _density, double _start, double _end);
340 
343  public: uint32_t GetId() const;
344 
347  public: std::string GetIdString() const;
348 
351  public: void SetShadowsEnabled(bool _value);
352 
355  public: bool GetShadowsEnabled() const;
356 
359  public: void AddVisual(VisualPtr _vis);
360 
363  public: void RemoveVisual(VisualPtr _vis);
364 
367  public: void RemoveVisual(uint32_t _id);
368 
374  public: void SetVisualId(VisualPtr _vis, uint32_t _id);
375 
378  public: void AddLight(LightPtr _light);
379 
382  public: void RemoveLight(LightPtr _light);
383 
386  public: void SetGrid(bool _enabled);
387 
390  public: void ShowOrigin(bool _show);
391 
394  public: VisualPtr GetWorldVisual() const;
395 
399  public: std::string StripSceneName(const std::string &_name) const;
400 
403  public: Heightmap *GetHeightmap() const;
404 
406  public: void Clear();
407 
411  public: VisualPtr GetSelectedVisual() const;
412 
415  public: void SetWireframe(bool _show);
416 
419  public: void SetTransparent(bool _show);
420 
423  public: void ShowCOMs(bool _show);
424 
427  public: void ShowInertias(bool _show);
428 
431  public: void ShowLinkFrames(bool _show);
432 
435  public: void ShowJoints(bool _show);
436 
439  public: void ShowCollisions(bool _show);
440 
443  public: void ShowContacts(bool _show);
444 
447  public: void ShowClouds(bool _show);
448 
451  public: bool GetShowClouds() const;
452 
453 
458  public: void SetSkyXMode(unsigned int _mode);
459 
462  public: SkyX::SkyX *GetSkyX() const;
463 
465  public: bool GetInitialized() const;
466 
472  public: common::Time GetSimTime() const;
473 
476  public: uint32_t GetVisualCount() const;
477 
479  public: void RemoveProjectors();
480 
485  public: void ToggleLayer(const int32_t _layer);
486 
488  private: void SetSky();
489 
491  private: void InitDeferredShading();
492 
499  private: Ogre::Entity *GetOgreEntityAt(CameraPtr _camera,
500  const math::Vector2i &_mousePos,
501  bool _ignorSelectionObj);
502 
512  // Code found in Wiki: www.ogre3d.org/wiki/index.php/RetrieveVertexData
513  private: void GetMeshInformation(const Ogre::Mesh *_mesh,
514  size_t &_vertexCount,
515  Ogre::Vector3* &_vertices,
516  size_t &_indexCount,
517  uint64_t* &_indices,
518  const Ogre::Vector3 &_position,
519  const Ogre::Quaternion &_orient,
520  const Ogre::Vector3 &_scale);
521 
525  private: void PrintSceneGraphHelper(const std::string &_prefix,
526  Ogre::Node *_node);
527 
531  private: void OnScene(ConstScenePtr &_msg);
532 
535  private: void OnResponse(ConstResponsePtr &_msg);
536 
539  private: void OnRequest(ConstRequestPtr &_msg);
540 
543  private: void OnJointMsg(ConstJointPtr &_msg);
544 
547  private: bool ProcessSensorMsg(ConstSensorPtr &_msg);
548 
551  private: bool ProcessJointMsg(ConstJointPtr &_msg);
552 
555  private: bool ProcessLinkMsg(ConstLinkPtr &_msg);
556 
559  private: bool ProcessSceneMsg(ConstScenePtr &_msg);
560 
563  private: bool ProcessModelMsg(const msgs::Model &_msg);
564 
567  private: void OnSensorMsg(ConstSensorPtr &_msg);
568 
571  private: void OnVisualMsg(ConstVisualPtr &_msg);
572 
577  private: bool ProcessVisualMsg(ConstVisualPtr &_msg,
579 
582  private: void OnLightMsg(ConstLightPtr &_msg);
583 
586  private: bool ProcessLightMsg(ConstLightPtr &_msg);
587 
590  private: void ProcessRequestMsg(ConstRequestPtr &_msg);
591 
594  private: void OnSkyMsg(ConstSkyPtr &_msg);
595 
598  private: void OnModelMsg(ConstModelPtr &_msg);
599 
602  private: void OnPoseMsg(ConstPosesStampedPtr &_msg);
603 
606  private: void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
607 
611  private: void CreateCOMVisual(ConstLinkPtr &_msg, VisualPtr _linkVisual);
612 
616  private: void CreateCOMVisual(sdf::ElementPtr _elem,
617  VisualPtr _linkVisual);
618 
622  private: void CreateInertiaVisual(ConstLinkPtr &_msg,
623  VisualPtr _linkVisual);
624 
628  private: void CreateInertiaVisual(sdf::ElementPtr _elem,
629  VisualPtr _linkVisual);
630 
634  private: void CreateLinkFrameVisual(ConstLinkPtr &_msg,
635  VisualPtr _linkVisual);
636 
640  private: void RemoveVisualizations(VisualPtr _vis);
641 
644  private: ScenePrivate *dataPtr;
645  };
647  }
648 }
649 #endif
boost::shared_ptr< DepthCamera > DepthCameraPtr
Definition: RenderTypes.hh:95
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
boost::shared_ptr< Light > LightPtr
Definition: RenderTypes.hh:83
Generic integer x, y vector.
Definition: Vector2i.hh:36
Forward declarations for transport.
boost::shared_ptr< Camera > CameraPtr
Definition: RenderTypes.hh:87
VisualType
Type of visual.
Definition: Visual.hh:62
SkyXMode
Definition: Scene.hh:72
#define GZ_RENDERING_VISIBLE
Definition: system.hh:241
boost::shared_ptr< GpuLaser > GpuLaserPtr
Definition: RenderTypes.hh:99
Entity visual.
Definition: Visual.hh:65
Representation of an entire scene graph.
Definition: Scene.hh:69
Defines a color.
Definition: Color.hh:36
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
boost::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:107
boost::shared_ptr< UserCamera > UserCameraPtr
Definition: RenderTypes.hh:91
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:39