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>
33 #include "gazebo/gazebo_config.h"
43 class BasicController;
82 GZ_SKYX_ALL = 0x0FFFFFFF,
83 GZ_SKYX_CLOUDS = 0x0000001,
84 GZ_SKYX_MOON = 0x0000002,
96 public: Scene(
const std::string &_name,
97 bool _enableVisualizations =
false,
98 bool _isServer =
false);
101 public:
virtual ~Scene();
105 public:
void Load(sdf::ElementPtr _scene);
114 public:
void PreRender();
118 public: Ogre::SceneManager *GetManager()
const;
122 public: std::string GetName()
const;
134 public:
void SetBackgroundColor(
const common::Color &_color);
145 public:
void CreateGrid(uint32_t _cellCount,
float _cellLength,
151 public: Grid *GetGrid(uint32_t _index)
const;
155 public: uint32_t GetGridCount()
const;
162 public:
CameraPtr CreateCamera(
const std::string &_name,
163 bool _autoRender =
true);
173 public: uint32_t GetOculusCameraCount()
const;
182 public:
DepthCameraPtr CreateDepthCamera(
const std::string &_name,
183 bool _autoRender =
true);
190 public:
GpuLaserPtr CreateGpuLaser(
const std::string &_name,
191 bool _autoRender =
true);
195 public: uint32_t GetCameraCount()
const;
201 public:
CameraPtr GetCamera(uint32_t _index)
const;
206 public:
CameraPtr GetCamera(
const std::string &_name)
const;
213 public:
UserCameraPtr CreateUserCamera(
const std::string &_name);
217 public: uint32_t GetUserCameraCount()
const;
228 public:
void RemoveCamera(
const std::string &_name);
233 public:
LightPtr GetLight(
const std::string &_name)
const;
237 public: uint32_t GetLightCount()
const;
243 public:
LightPtr GetLight(uint32_t _index)
const;
248 public:
VisualPtr GetVisual(
const std::string &_name)
const;
253 public:
VisualPtr GetVisual(uint32_t _id)
const;
258 public:
void SelectVisual(
const std::string &_name,
259 const std::string &_mode);
273 public:
void SnapVisualToNearestBelow(
const std::string &_visualName);
295 public:
VisualPtr GetVisualBelow(
const std::string &_visualName);
302 std::vector<VisualPtr> &_visuals);
309 public:
double GetHeightBelowPoint(
const math::Vector3 &_pt);
316 public:
bool GetFirstContact(
CameraPtr _camera,
321 public:
void PrintSceneGraph();
327 public:
void SetVisible(
const std::string &_name,
bool _visible);
335 const std::string &_name);
344 public:
void SetFog(
const std::string &_type,
346 double _density,
double _start,
double _end);
350 public: uint32_t GetId()
const;
354 public: std::string GetIdString()
const;
358 public:
void SetShadowsEnabled(
bool _value);
362 public:
bool GetShadowsEnabled()
const;
370 public:
void RemoveVisual(
VisualPtr _vis);
374 public:
void AddLight(
LightPtr _light);
378 public:
void RemoveLight(
LightPtr _light);
382 public:
void SetGrid(
bool _enabled);
386 public:
VisualPtr GetWorldVisual()
const;
391 public: std::string StripSceneName(
const std::string &_name)
const;
395 public: Heightmap *GetHeightmap()
const;
398 public:
void Clear();
403 public:
VisualPtr GetSelectedVisual()
const;
407 public:
void SetWireframe(
bool _show);
411 public:
void SetTransparent(
bool _show);
415 public:
void ShowCOMs(
bool _show);
419 public:
void ShowJoints(
bool _show);
423 public:
void ShowCollisions(
bool _show);
427 public:
void ShowContacts(
bool _show);
431 public:
void ShowClouds(
bool _show);
435 public:
bool GetShowClouds()
const;
442 public:
void SetSkyXMode(
unsigned int _mode);
445 public:
bool GetInitialized()
const;
456 public: uint32_t GetVisualCount()
const;
459 public:
void RemoveProjectors();
462 private:
void SetSky();
465 private:
void InitDeferredShading();
473 private: Ogre::Entity *GetOgreEntityAt(
CameraPtr _camera,
475 bool _ignorSelectionObj);
487 private:
void GetMeshInformation(
const Ogre::Mesh *_mesh,
488 size_t &_vertexCount,
489 Ogre::Vector3* &_vertices,
492 const Ogre::Vector3 &_position,
493 const Ogre::Quaternion &_orient,
494 const Ogre::Vector3 &_scale);
499 private:
void PrintSceneGraphHelper(
const std::string &_prefix,
505 private:
void OnScene(ConstScenePtr &_msg);
509 private:
void OnResponse(ConstResponsePtr &_msg);
513 private:
void OnRequest(ConstRequestPtr &_msg);
517 private:
void OnJointMsg(ConstJointPtr &_msg);
521 private:
bool ProcessSensorMsg(ConstSensorPtr &_msg);
525 private:
bool ProcessJointMsg(ConstJointPtr &_msg);
529 private:
bool ProcessLinkMsg(ConstLinkPtr &_msg);
533 private:
bool ProcessSceneMsg(ConstScenePtr &_msg);
537 private:
bool ProcessModelMsg(
const msgs::Model &_msg);
541 private:
void OnSensorMsg(ConstSensorPtr &_msg);
545 private:
void OnVisualMsg(ConstVisualPtr &_msg);
549 private:
bool ProcessVisualMsg(ConstVisualPtr &_msg);
553 private:
void OnLightMsg(ConstLightPtr &_msg);
557 private:
bool ProcessLightMsg(ConstLightPtr &_msg);
561 private:
void ProcessRequestMsg(ConstRequestPtr &_msg);
565 private:
void OnSelectionMsg(ConstSelectionPtr &_msg);
569 private:
void OnSkyMsg(ConstSkyPtr &_msg);
573 private:
void OnModelMsg(ConstModelPtr &_msg);
577 private:
void OnPoseMsg(ConstPosesStampedPtr &_msg);
581 private:
void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
586 private:
void CreateCOMVisual(ConstLinkPtr &_msg,
VisualPtr _linkVisual);
591 private:
void CreateCOMVisual(sdf::ElementPtr _elem,
595 private: std::string name;
598 private: sdf::ElementPtr sdf;
601 private: std::vector<CameraPtr> cameras;
604 private: std::vector<UserCameraPtr> userCameras;
607 private: std::vector<OculusCameraPtr> oculusCameras;
612 private: Ogre::SceneManager *manager;
615 private: Ogre::RaySceneQuery *raySceneQuery;
618 private: std::vector<Grid *> grids;
621 private:
static uint32_t idCounter;
624 private: uint32_t id;
627 private: std::string idString;
631 typedef std::list<boost::shared_ptr<msgs::Visual const> > VisualMsgs_L;
634 private: VisualMsgs_L visualMsgs;
638 typedef std::list<boost::shared_ptr<msgs::Light const> > LightMsgs_L;
641 private: LightMsgs_L lightMsgs;
645 typedef std::map<uint32_t, msgs::Pose> PoseMsgs_M;
648 private: PoseMsgs_M poseMsgs;
652 typedef std::list<boost::shared_ptr<msgs::Scene const> > SceneMsgs_L;
655 private: SceneMsgs_L sceneMsgs;
659 typedef std::list<boost::shared_ptr<msgs::Joint const> > JointMsgs_L;
662 private: JointMsgs_L jointMsgs;
666 typedef std::list<boost::shared_ptr<msgs::Link const> > LinkMsgs_L;
669 private: LinkMsgs_L linkMsgs;
673 typedef std::list<boost::shared_ptr<msgs::Model const> > ModelMsgs_L;
675 private: ModelMsgs_L modelMsgs;
679 typedef std::list<boost::shared_ptr<msgs::Sensor const> > SensorMsgs_L;
682 private: SensorMsgs_L sensorMsgs;
686 typedef std::list<boost::shared_ptr<msgs::Request const> > RequestMsgs_L;
688 private: RequestMsgs_L requestMsgs;
692 typedef std::map<uint32_t, VisualPtr> Visual_M;
695 private: Visual_M visuals;
699 typedef std::map<std::string, LightPtr> Light_M;
702 private: Light_M lights;
706 typedef std::list<boost::shared_ptr<msgs::PoseAnimation const> >
709 private: SkeletonPoseMsgs_L skeletonPoseMsgs;
712 private: boost::shared_ptr<msgs::Selection const> selectionMsg;
715 private: boost::mutex *receiveMutex;
718 private: boost::recursive_mutex poseMsgMutex;
769 private: std::vector<event::ConnectionPtr> connections;
782 private: std::string selectionMode;
785 private: msgs::Request *requestMsg;
788 private:
bool enableVisualizations;
791 private: Heightmap *terrain;
794 private: std::map<std::string, Projector *> projectors;
800 private: SkyX::BasicController *skyxController;
803 private:
bool showCOMs;
806 private:
bool showCollisions;
809 private:
bool showJoints;
812 private:
bool transparent;
815 private:
bool wireframe;
818 private:
bool initialized;
829 private: uint32_t contactVisId;
833 typedef boost::unordered_map<std::string,
834 boost::shared_ptr<msgs::Joint const> > JointMsgs_M;
837 private: JointMsgs_M joints;
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