All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Scene.hh
Go to the documentation of this file.
1 /*
2  * Copyright 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 _SCENE_HH_
18 #define _SCENE_HH_
19 
20 #include <vector>
21 #include <map>
22 #include <string>
23 #include <list>
24 #include <boost/enable_shared_from_this.hpp>
25 #include <boost/shared_ptr.hpp>
26 
27 #include "sdf/sdf.hh"
28 #include "msgs/msgs.hh"
29 
30 #include "rendering/RenderTypes.hh"
31 
33 #include "common/Events.hh"
34 #include "common/Color.hh"
35 #include "math/Vector2i.hh"
36 
37 namespace SkyX
38 {
39  class SkyX;
40  class BasicController;
41 }
42 
43 namespace Ogre
44 {
45  class SceneManager;
46  class RaySceneQuery;
47  class Node;
48  class Entity;
49  class Mesh;
50  class Vector3;
51  class Quaternion;
52 }
53 
54 namespace boost
55 {
56  class mutex;
57 }
58 
59 namespace gazebo
60 {
61  namespace rendering
62  {
63  class Projector;
64  class Light;
65  class Visual;
66  class Grid;
67  class Heightmap;
68 
71 
76  class Scene : public boost::enable_shared_from_this<Scene>
77  {
79  private: Scene() {}
80 
86  public: Scene(const std::string &_name,
87  bool _enableVisualizations = false);
88 
90  public: virtual ~Scene();
91 
94  public: void Load(sdf::ElementPtr _scene);
95 
97  public: void Load();
98 
100  public: void Init();
101 
103  public: void PreRender();
104 
107  public: Ogre::SceneManager *GetManager() const;
108 
111  public: std::string GetName() const;
112 
115  public: void SetAmbientColor(const common::Color &_color);
116 
119  public: common::Color GetAmbientColor() const;
120 
123  public: void SetBackgroundColor(const common::Color &_color);
124 
127  public: common::Color GetBackgroundColor() const;
128 
134  public: void CreateGrid(uint32_t _cellCount, float _cellLength,
135  float _lineWidth, const common::Color &_color);
136 
140  public: Grid *GetGrid(uint32_t _index) const;
141 
144  public: uint32_t GetGridCount() const;
145 
151  public: CameraPtr CreateCamera(const std::string &_name,
152  bool _autoRender = true);
153 
159  public: DepthCameraPtr CreateDepthCamera(const std::string &_name,
160  bool _autoRender = true);
161 
167  // public: GpuLaserPtr CreateGpuLaser(const std::string &_name,
168  // bool _autoRender = true);
169 
172  public: uint32_t GetCameraCount() const;
173 
178  public: CameraPtr GetCamera(uint32_t _index) const;
179 
183  public: CameraPtr GetCamera(const std::string &_name) const;
184 
190  public: UserCameraPtr CreateUserCamera(const std::string &_name);
191 
194  public: uint32_t GetUserCameraCount() const;
195 
201  public: UserCameraPtr GetUserCamera(uint32_t _index) const;
202 
206  public: LightPtr GetLight(const std::string &_name) const;
207 
210  public: uint32_t GetLightCount() const;
211 
216  public: LightPtr GetLight(uint32_t _index) const;
217 
219  public: VisualPtr GetVisual(const std::string &_name) const;
220 
224  public: void SelectVisual(const std::string &_name,
225  const std::string &_mode);
226 
233  public: VisualPtr GetVisualAt(CameraPtr _camera,
234  const math::Vector2i &_mousePos,
235  std::string &_mod);
236 
239  public: void SnapVisualToNearestBelow(const std::string &_visualName);
240 
246  public: VisualPtr GetVisualAt(CameraPtr _camera,
247  const math::Vector2i &_mousePos);
248 
254  public: VisualPtr GetModelVisualAt(CameraPtr _camera,
255  const math::Vector2i &_mousePos);
256 
257 
261  public: VisualPtr GetVisualBelow(const std::string &_visualName);
262 
267  public: void GetVisualsBelowPoint(const math::Vector3 &_pt,
268  std::vector<VisualPtr> &_visuals);
269 
270 
275  public: double GetHeightBelowPoint(const math::Vector3 &_pt);
276 
282  public: bool GetFirstContact(CameraPtr _camera,
283  const math::Vector2i &_mousePos,
284  math::Vector3 &_position);
285 
287  public: void PrintSceneGraph();
288 
293  public: void SetVisible(const std::string &_name, bool _visible);
294 
299  public: void DrawLine(const math::Vector3 &_start,
300  const math::Vector3 &_end,
301  const std::string &_name);
302 
310  public: void SetFog(const std::string &_type,
311  const common::Color &_color,
312  double _density, double _start, double _end);
313 
316  public: uint32_t GetId() const;
317 
320  public: std::string GetIdString() const;
321 
324  public: void SetShadowsEnabled(bool _value);
325 
328  public: bool GetShadowsEnabled() const;
329 
332  public: void AddVisual(VisualPtr _vis);
333 
336  public: void RemoveVisual(VisualPtr _vis);
337 
340  public: void SetGrid(bool _enabled);
341 
344  public: VisualPtr GetWorldVisual() const;
345 
349  public: std::string StripSceneName(const std::string &_name) const;
350 
353  public: Heightmap *GetHeightmap() const;
354 
356  public: void Clear();
357 
362  public: VisualPtr CloneVisual(const std::string &_visualName,
363  const std::string &_newName);
364 
368  public: VisualPtr GetSelectedVisual() const;
369 
372  public: void SetWireframe(bool _show);
373 
376  public: void SetTransparent(bool _show);
377 
380  public: void ShowCOMs(bool _show);
381 
384  public: void ShowJoints(bool _show);
385 
388  public: void ShowCollisions(bool _show);
389 
392  public: void ShowContacts(bool _show);
393 
395  public: bool GetInitialized() const;
396 
398  private: void SetSky();
399 
401  private: void InitDeferredShading();
402 
409  private: Ogre::Entity *GetOgreEntityAt(CameraPtr _camera,
410  const math::Vector2i &_mousePos,
411  bool _ignorSelectionObj);
412 
422  // Code found in Wiki: www.ogre3d.org/wiki/index.php/RetrieveVertexData
423  private: void GetMeshInformation(const Ogre::Mesh *_mesh,
424  size_t &_vertexCount,
425  Ogre::Vector3* &_vertices,
426  size_t &_indexCount,
427  uint64_t* &_indices,
428  const Ogre::Vector3 &_position,
429  const Ogre::Quaternion &_orient,
430  const Ogre::Vector3 &_scale);
431 
435  private: void PrintSceneGraphHelper(const std::string &_prefix,
436  Ogre::Node *_node);
437 
441  private: void OnScene(ConstScenePtr &_msg);
442 
445  private: void OnResponse(ConstResponsePtr &_msg);
446 
449  private: void OnRequest(ConstRequestPtr &_msg);
450 
453  private: void OnJointMsg(ConstJointPtr &_msg);
454 
457  private: bool ProcessSensorMsg(ConstSensorPtr &_msg);
458 
461  private: bool ProcessJointMsg(ConstJointPtr &_msg);
462 
465  private: bool ProcessLinkMsg(ConstLinkPtr &_msg);
466 
469  private: void ProcessSceneMsg(ConstScenePtr &_msg);
470 
473  private: bool ProcessModelMsg(const msgs::Model &_msg);
474 
477  private: void OnSensorMsg(ConstSensorPtr &_msg);
478 
481  private: void OnVisualMsg(ConstVisualPtr &_msg);
482 
485  private: bool ProcessVisualMsg(ConstVisualPtr &_msg);
486 
489  private: void OnLightMsg(ConstLightPtr &_msg);
490 
493  private: void ProcessLightMsg(ConstLightPtr &_msg);
494 
497  private: void ProcessRequestMsg(ConstRequestPtr &_msg);
498 
501  private: void OnSelectionMsg(ConstSelectionPtr &_msg);
502 
505  private: void OnSkyMsg(ConstSkyPtr &_msg);
506 
509  private: void OnModelMsg(ConstModelPtr &_msg);
510 
513  private: void OnPoseMsg(ConstPose_VPtr &_msg);
514 
517  private: void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
518 
522  private: void CreateCOMVisual(ConstLinkPtr &_msg, VisualPtr _linkVisual);
523 
527  private: void CreateCOMVisual(sdf::ElementPtr _elem,
528  VisualPtr _linkVisual);
529 
531  private: std::string name;
532 
534  private: sdf::ElementPtr sdf;
535 
537  private: std::vector<CameraPtr> cameras;
538 
540  private: std::vector<UserCameraPtr> userCameras;
541 
543  private: Ogre::SceneManager *manager;
544 
546  private: Ogre::RaySceneQuery *raySceneQuery;
547 
549  private: std::vector<Grid *> grids;
550 
552  private: static uint32_t idCounter;
553 
555  private: uint32_t id;
556 
558  private: std::string idString;
559 
562  typedef std::list<boost::shared_ptr<msgs::Visual const> > VisualMsgs_L;
563 
565  private: VisualMsgs_L visualMsgs;
566 
569  typedef std::list<boost::shared_ptr<msgs::Light const> > LightMsgs_L;
570 
572  private: LightMsgs_L lightMsgs;
573 
576  typedef std::list<msgs::Pose> PoseMsgs_L;
577 
579  private: PoseMsgs_L poseMsgs;
580 
583  typedef std::list<boost::shared_ptr<msgs::Scene const> > SceneMsgs_L;
584 
586  private: SceneMsgs_L sceneMsgs;
587 
590  typedef std::list<boost::shared_ptr<msgs::Joint const> > JointMsgs_L;
591 
593  private: JointMsgs_L jointMsgs;
594 
597  typedef std::list<boost::shared_ptr<msgs::Link const> > LinkMsgs_L;
598 
600  private: LinkMsgs_L linkMsgs;
601 
604  typedef std::list<boost::shared_ptr<msgs::Model const> > ModelMsgs_L;
606  private: ModelMsgs_L modelMsgs;
607 
610  typedef std::list<boost::shared_ptr<msgs::Sensor const> > SensorMsgs_L;
611 
613  private: SensorMsgs_L sensorMsgs;
614 
617  typedef std::list<boost::shared_ptr<msgs::Request const> > RequestMsgs_L;
619  private: RequestMsgs_L requestMsgs;
620 
623  typedef std::map<std::string, VisualPtr> Visual_M;
624 
626  private: Visual_M visuals;
627 
630  typedef std::map<std::string, LightPtr> Light_M;
631 
633  private: Light_M lights;
634 
637  typedef std::list<boost::shared_ptr<msgs::PoseAnimation const> >
638  SkeletonPoseMsgs_L;
640  private: SkeletonPoseMsgs_L skeletonPoseMsgs;
641 
643  private: boost::shared_ptr<msgs::Selection const> selectionMsg;
644 
646  private: boost::mutex *receiveMutex;
647 
649  private: transport::NodePtr node;
650 
652  private: transport::SubscriberPtr sensorSub;
653 
655  private: transport::SubscriberPtr sceneSub;
656 
658  private: transport::SubscriberPtr requestSub;
659 
661  private: transport::SubscriberPtr visSub;
662 
664  private: transport::SubscriberPtr lightSub;
665 
667  private: transport::SubscriberPtr poseSub;
668 
670  private: transport::SubscriberPtr jointSub;
671 
673  private: transport::SubscriberPtr selectionSub;
674 
676  private: transport::SubscriberPtr responseSub;
677 
679  private: transport::SubscriberPtr skeletonPoseSub;
680 
682  private: transport::SubscriberPtr skySub;
683 
685  private: transport::SubscriberPtr modelInfoSub;
686 
688  private: transport::PublisherPtr lightPub;
689 
691  private: transport::PublisherPtr responsePub;
692 
694  private: transport::PublisherPtr requestPub;
695 
697  private: std::vector<event::ConnectionPtr> connections;
698 
700  private: VisualPtr worldVisual;
701 
703  private: VisualPtr selectedVis;
704 
710  private: std::string selectionMode;
711 
713  private: msgs::Request *requestMsg;
714 
716  private: bool enableVisualizations;
717 
719  private: Heightmap *terrain;
720 
722  private: std::map<std::string, Projector *> projectors;
723 
725  public: SkyX::SkyX *skyx;
726 
728  private: SkyX::BasicController *skyxController;
729 
731  private: bool showCOMs;
732 
734  private: bool showCollisions;
735 
737  private: bool showJoints;
738 
740  private: bool transparent;
741 
743  private: bool wireframe;
744 
746  private: bool initialized;
747  };
749  }
750 }
751 #endif