All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
Scene.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 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 _SCENE_HH_
18 #define _SCENE_HH_
19 
20 #include <list>
21 #include <map>
22 #include <string>
23 #include <vector>
24 #include <boost/enable_shared_from_this.hpp>
25 #include <boost/shared_ptr.hpp>
26 #include <boost/unordered/unordered_map.hpp>
27 #include <boost/thread/recursive_mutex.hpp>
28 
29 #include <sdf/sdf.hh>
30 
31 #include "gazebo/common/Events.hh"
32 #include "gazebo/common/Color.hh"
33 #include "gazebo/gazebo_config.h"
34 #include "gazebo/math/Vector2i.hh"
35 #include "gazebo/msgs/msgs.hh"
38 #include "gazebo/util/system.hh"
39 
40 namespace SkyX
41 {
42  class SkyX;
43  class BasicController;
44 }
45 
46 namespace Ogre
47 {
48  class SceneManager;
49  class RaySceneQuery;
50  class Node;
51  class Entity;
52  class Mesh;
53  class Vector3;
54  class Quaternion;
55 }
56 
57 namespace boost
58 {
59  class mutex;
60 }
61 
62 namespace gazebo
63 {
64  namespace rendering
65  {
66  class Projector;
67  class Light;
68  class Visual;
69  class Grid;
70  class Heightmap;
71 
74 
79  class GAZEBO_VISIBLE Scene : public boost::enable_shared_from_this<Scene>
80  {
81  public: enum SkyXMode {
82  GZ_SKYX_ALL = 0x0FFFFFFF,
83  GZ_SKYX_CLOUDS = 0x0000001,
84  GZ_SKYX_MOON = 0x0000002,
85  GZ_SKYX_NONE = 0
86  };
87 
89  private: Scene() {}
90 
96  public: Scene(const std::string &_name,
97  bool _enableVisualizations = false,
98  bool _isServer = false);
99 
101  public: virtual ~Scene();
102 
105  public: void Load(sdf::ElementPtr _scene);
106 
108  public: void Load();
109 
111  public: void Init();
112 
114  public: void PreRender();
115 
118  public: Ogre::SceneManager *GetManager() const;
119 
122  public: std::string GetName() const;
123 
126  public: void SetAmbientColor(const common::Color &_color);
127 
130  public: common::Color GetAmbientColor() const;
131 
134  public: void SetBackgroundColor(const common::Color &_color);
135 
138  public: common::Color GetBackgroundColor() const;
139 
145  public: void CreateGrid(uint32_t _cellCount, float _cellLength,
146  float _lineWidth, const common::Color &_color);
147 
151  public: Grid *GetGrid(uint32_t _index) const;
152 
155  public: uint32_t GetGridCount() const;
156 
162  public: CameraPtr CreateCamera(const std::string &_name,
163  bool _autoRender = true);
164 
165 #ifdef HAVE_OCULUS
166  public: OculusCameraPtr CreateOculusCamera(const std::string &_name);
170 
173  public: uint32_t GetOculusCameraCount() const;
174 
175 #endif
176 
182  public: DepthCameraPtr CreateDepthCamera(const std::string &_name,
183  bool _autoRender = true);
184 
190  public: GpuLaserPtr CreateGpuLaser(const std::string &_name,
191  bool _autoRender = true);
192 
195  public: uint32_t GetCameraCount() const;
196 
201  public: CameraPtr GetCamera(uint32_t _index) const;
202 
206  public: CameraPtr GetCamera(const std::string &_name) const;
207 
213  public: UserCameraPtr CreateUserCamera(const std::string &_name);
214 
217  public: uint32_t GetUserCameraCount() const;
218 
224  public: UserCameraPtr GetUserCamera(uint32_t _index) const;
225 
228  public: void RemoveCamera(const std::string &_name);
229 
233  public: LightPtr GetLight(const std::string &_name) const;
234 
237  public: uint32_t GetLightCount() const;
238 
243  public: LightPtr GetLight(uint32_t _index) const;
244 
248  public: VisualPtr GetVisual(const std::string &_name) const;
249 
253  public: VisualPtr GetVisual(uint32_t _id) const;
254 
258  public: void SelectVisual(const std::string &_name,
259  const std::string &_mode);
260 
267  public: VisualPtr GetVisualAt(CameraPtr _camera,
268  const math::Vector2i &_mousePos,
269  std::string &_mod);
270 
273  public: void SnapVisualToNearestBelow(const std::string &_visualName);
274 
280  public: VisualPtr GetVisualAt(CameraPtr _camera,
281  const math::Vector2i &_mousePos);
282 
288  public: VisualPtr GetModelVisualAt(CameraPtr _camera,
289  const math::Vector2i &_mousePos);
290 
291 
295  public: VisualPtr GetVisualBelow(const std::string &_visualName);
296 
301  public: void GetVisualsBelowPoint(const math::Vector3 &_pt,
302  std::vector<VisualPtr> &_visuals);
303 
304 
309  public: double GetHeightBelowPoint(const math::Vector3 &_pt);
310 
316  public: bool GetFirstContact(CameraPtr _camera,
317  const math::Vector2i &_mousePos,
318  math::Vector3 &_position);
319 
321  public: void PrintSceneGraph();
322 
327  public: void SetVisible(const std::string &_name, bool _visible);
328 
333  public: void DrawLine(const math::Vector3 &_start,
334  const math::Vector3 &_end,
335  const std::string &_name);
336 
344  public: void SetFog(const std::string &_type,
345  const common::Color &_color,
346  double _density, double _start, double _end);
347 
350  public: uint32_t GetId() const;
351 
354  public: std::string GetIdString() const;
355 
358  public: void SetShadowsEnabled(bool _value);
359 
362  public: bool GetShadowsEnabled() const;
363 
366  public: void AddVisual(VisualPtr _vis);
367 
370  public: void RemoveVisual(VisualPtr _vis);
371 
374  public: void AddLight(LightPtr _light);
375 
378  public: void RemoveLight(LightPtr _light);
379 
382  public: void SetGrid(bool _enabled);
383 
386  public: VisualPtr GetWorldVisual() const;
387 
391  public: std::string StripSceneName(const std::string &_name) const;
392 
395  public: Heightmap *GetHeightmap() const;
396 
398  public: void Clear();
399 
403  public: VisualPtr GetSelectedVisual() const;
404 
407  public: void SetWireframe(bool _show);
408 
411  public: void SetTransparent(bool _show);
412 
415  public: void ShowCOMs(bool _show);
416 
419  public: void ShowJoints(bool _show);
420 
423  public: void ShowCollisions(bool _show);
424 
427  public: void ShowContacts(bool _show);
428 
431  public: void ShowClouds(bool _show);
432 
435  public: bool GetShowClouds() const;
436 
437 
442  public: void SetSkyXMode(unsigned int _mode);
443 
445  public: bool GetInitialized() const;
446 
452  public: common::Time GetSimTime() const;
453 
456  public: uint32_t GetVisualCount() const;
457 
459  public: void RemoveProjectors();
460 
462  private: void SetSky();
463 
465  private: void InitDeferredShading();
466 
473  private: Ogre::Entity *GetOgreEntityAt(CameraPtr _camera,
474  const math::Vector2i &_mousePos,
475  bool _ignorSelectionObj);
476 
486  // Code found in Wiki: www.ogre3d.org/wiki/index.php/RetrieveVertexData
487  private: void GetMeshInformation(const Ogre::Mesh *_mesh,
488  size_t &_vertexCount,
489  Ogre::Vector3* &_vertices,
490  size_t &_indexCount,
491  uint64_t* &_indices,
492  const Ogre::Vector3 &_position,
493  const Ogre::Quaternion &_orient,
494  const Ogre::Vector3 &_scale);
495 
499  private: void PrintSceneGraphHelper(const std::string &_prefix,
500  Ogre::Node *_node);
501 
505  private: void OnScene(ConstScenePtr &_msg);
506 
509  private: void OnResponse(ConstResponsePtr &_msg);
510 
513  private: void OnRequest(ConstRequestPtr &_msg);
514 
517  private: void OnJointMsg(ConstJointPtr &_msg);
518 
521  private: bool ProcessSensorMsg(ConstSensorPtr &_msg);
522 
525  private: bool ProcessJointMsg(ConstJointPtr &_msg);
526 
529  private: bool ProcessLinkMsg(ConstLinkPtr &_msg);
530 
533  private: bool ProcessSceneMsg(ConstScenePtr &_msg);
534 
537  private: bool ProcessModelMsg(const msgs::Model &_msg);
538 
541  private: void OnSensorMsg(ConstSensorPtr &_msg);
542 
545  private: void OnVisualMsg(ConstVisualPtr &_msg);
546 
549  private: bool ProcessVisualMsg(ConstVisualPtr &_msg);
550 
553  private: void OnLightMsg(ConstLightPtr &_msg);
554 
557  private: bool ProcessLightMsg(ConstLightPtr &_msg);
558 
561  private: void ProcessRequestMsg(ConstRequestPtr &_msg);
562 
565  private: void OnSelectionMsg(ConstSelectionPtr &_msg);
566 
569  private: void OnSkyMsg(ConstSkyPtr &_msg);
570 
573  private: void OnModelMsg(ConstModelPtr &_msg);
574 
577  private: void OnPoseMsg(ConstPosesStampedPtr &_msg);
578 
581  private: void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
582 
586  private: void CreateCOMVisual(ConstLinkPtr &_msg, VisualPtr _linkVisual);
587 
591  private: void CreateCOMVisual(sdf::ElementPtr _elem,
592  VisualPtr _linkVisual);
593 
595  private: std::string name;
596 
598  private: sdf::ElementPtr sdf;
599 
601  private: std::vector<CameraPtr> cameras;
602 
604  private: std::vector<UserCameraPtr> userCameras;
605 
606 #ifdef HAVE_OCULUS
607  private: std::vector<OculusCameraPtr> oculusCameras;
609 #endif
610 
612  private: Ogre::SceneManager *manager;
613 
615  private: Ogre::RaySceneQuery *raySceneQuery;
616 
618  private: std::vector<Grid *> grids;
619 
621  private: static uint32_t idCounter;
622 
624  private: uint32_t id;
625 
627  private: std::string idString;
628 
631  typedef std::list<boost::shared_ptr<msgs::Visual const> > VisualMsgs_L;
632 
634  private: VisualMsgs_L visualMsgs;
635 
638  typedef std::list<boost::shared_ptr<msgs::Light const> > LightMsgs_L;
639 
641  private: LightMsgs_L lightMsgs;
642 
645  typedef std::map<uint32_t, msgs::Pose> PoseMsgs_M;
646 
648  private: PoseMsgs_M poseMsgs;
649 
652  typedef std::list<boost::shared_ptr<msgs::Scene const> > SceneMsgs_L;
653 
655  private: SceneMsgs_L sceneMsgs;
656 
659  typedef std::list<boost::shared_ptr<msgs::Joint const> > JointMsgs_L;
660 
662  private: JointMsgs_L jointMsgs;
663 
666  typedef std::list<boost::shared_ptr<msgs::Link const> > LinkMsgs_L;
667 
669  private: LinkMsgs_L linkMsgs;
670 
673  typedef std::list<boost::shared_ptr<msgs::Model const> > ModelMsgs_L;
675  private: ModelMsgs_L modelMsgs;
676 
679  typedef std::list<boost::shared_ptr<msgs::Sensor const> > SensorMsgs_L;
680 
682  private: SensorMsgs_L sensorMsgs;
683 
686  typedef std::list<boost::shared_ptr<msgs::Request const> > RequestMsgs_L;
688  private: RequestMsgs_L requestMsgs;
689 
692  typedef std::map<uint32_t, VisualPtr> Visual_M;
693 
695  private: Visual_M visuals;
696 
699  typedef std::map<std::string, LightPtr> Light_M;
700 
702  private: Light_M lights;
703 
706  typedef std::list<boost::shared_ptr<msgs::PoseAnimation const> >
707  SkeletonPoseMsgs_L;
709  private: SkeletonPoseMsgs_L skeletonPoseMsgs;
710 
712  private: boost::shared_ptr<msgs::Selection const> selectionMsg;
713 
715  private: boost::mutex *receiveMutex;
716 
718  private: boost::recursive_mutex poseMsgMutex;
719 
721  private: transport::NodePtr node;
722 
724  private: transport::SubscriberPtr sensorSub;
725 
727  private: transport::SubscriberPtr sceneSub;
728 
730  private: transport::SubscriberPtr requestSub;
731 
733  private: transport::SubscriberPtr visSub;
734 
736  private: transport::SubscriberPtr lightSub;
737 
739  private: transport::SubscriberPtr poseSub;
740 
742  private: transport::SubscriberPtr jointSub;
743 
745  private: transport::SubscriberPtr selectionSub;
746 
748  private: transport::SubscriberPtr responseSub;
749 
751  private: transport::SubscriberPtr skeletonPoseSub;
752 
754  private: transport::SubscriberPtr skySub;
755 
757  private: transport::SubscriberPtr modelInfoSub;
758 
760  private: transport::PublisherPtr lightPub;
761 
763  private: transport::PublisherPtr responsePub;
764 
766  private: transport::PublisherPtr requestPub;
767 
769  private: std::vector<event::ConnectionPtr> connections;
770 
772  private: VisualPtr worldVisual;
773 
775  private: VisualPtr selectedVis;
776 
782  private: std::string selectionMode;
783 
785  private: msgs::Request *requestMsg;
786 
788  private: bool enableVisualizations;
789 
791  private: Heightmap *terrain;
792 
794  private: std::map<std::string, Projector *> projectors;
795 
797  public: SkyX::SkyX *skyx;
798 
800  private: SkyX::BasicController *skyxController;
801 
803  private: bool showCOMs;
804 
806  private: bool showCollisions;
807 
809  private: bool showJoints;
810 
812  private: bool transparent;
813 
815  private: bool wireframe;
816 
818  private: bool initialized;
819 
822  private: common::Time sceneSimTimePosesReceived;
823 
826  private: common::Time sceneSimTimePosesApplied;
827 
829  private: uint32_t contactVisId;
830 
833  typedef boost::unordered_map<std::string,
834  boost::shared_ptr<msgs::Joint const> > JointMsgs_M;
835 
837  private: JointMsgs_M joints;
838  };
840  }
841 }
842 #endif
boost::shared_ptr< DepthCamera > DepthCameraPtr
Definition: RenderTypes.hh:88
SkyX::SkyX * skyx
Pointer to the sky.
Definition: Scene.hh:797
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
boost::shared_ptr< Light > LightPtr
Definition: RenderTypes.hh:76
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:48
Generic integer x, y vector.
Definition: Vector2i.hh:39
Forward declarations for transport.
boost::shared_ptr< Camera > CameraPtr
Definition: RenderTypes.hh:80
SkyXMode
Definition: Scene.hh:81
boost::shared_ptr< GpuLaser > GpuLaserPtr
Definition: RenderTypes.hh:92
Representation of an entire scene graph.
Definition: Scene.hh:79
SkyX(Ogre::SceneManager *sm, Controller *c)
Contructor.
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:52
Defines a color.
Definition: Color.hh:39
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
boost::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:100
boost::shared_ptr< UserCamera > UserCameraPtr
Definition: RenderTypes.hh:84
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:44
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43
boost::shared_ptr< OculusCamera > OculusCameraPtr
Definition: RenderTypes.hh:157