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>
43 class BasicController;
79 class Scene :
public boost::enable_shared_from_this<Scene>
96 public: Scene(
const std::string &_name,
97 bool _enableVisualizations =
false,
98 bool _isServer =
false);
105 public:
void Load(sdf::ElementPtr _scene);
118 public: Ogre::SceneManager *
GetManager()
const;
122 public: std::string
GetName()
const;
145 public:
void CreateGrid(uint32_t _cellCount,
float _cellLength,
151 public: Grid *
GetGrid(uint32_t _index)
const;
163 bool _autoRender =
true);
171 bool _autoRender =
true);
179 bool _autoRender =
true);
247 const std::string &_mode);
290 std::vector<VisualPtr> &_visuals);
315 public:
void SetVisible(
const std::string &_name,
bool _visible);
323 const std::string &_name);
332 public:
void SetFog(
const std::string &_type,
334 double _density,
double _start,
double _end);
338 public: uint32_t
GetId()
const;
362 public:
void SetGrid(
bool _enabled);
371 public: std::string
StripSceneName(
const std::string &_name)
const;
378 public:
void Clear();
443 private:
void SetSky();
446 private:
void InitDeferredShading();
454 private: Ogre::Entity *GetOgreEntityAt(
CameraPtr _camera,
456 bool _ignorSelectionObj);
468 private:
void GetMeshInformation(
const Ogre::Mesh *_mesh,
469 size_t &_vertexCount,
470 Ogre::Vector3* &_vertices,
473 const Ogre::Vector3 &_position,
474 const Ogre::Quaternion &_orient,
475 const Ogre::Vector3 &_scale);
480 private:
void PrintSceneGraphHelper(
const std::string &_prefix,
486 private:
void OnScene(ConstScenePtr &_msg);
490 private:
void OnResponse(ConstResponsePtr &_msg);
494 private:
void OnRequest(ConstRequestPtr &_msg);
498 private:
void OnJointMsg(ConstJointPtr &_msg);
502 private:
bool ProcessSensorMsg(ConstSensorPtr &_msg);
506 private:
bool ProcessJointMsg(ConstJointPtr &_msg);
510 private:
bool ProcessLinkMsg(ConstLinkPtr &_msg);
514 private:
bool ProcessSceneMsg(ConstScenePtr &_msg);
518 private:
bool ProcessModelMsg(
const msgs::Model &_msg);
522 private:
void OnSensorMsg(ConstSensorPtr &_msg);
526 private:
void OnVisualMsg(ConstVisualPtr &_msg);
530 private:
bool ProcessVisualMsg(ConstVisualPtr &_msg);
534 private:
void OnLightMsg(ConstLightPtr &_msg);
538 private:
bool ProcessLightMsg(ConstLightPtr &_msg);
542 private:
void ProcessRequestMsg(ConstRequestPtr &_msg);
546 private:
void OnSelectionMsg(ConstSelectionPtr &_msg);
550 private:
void OnSkyMsg(ConstSkyPtr &_msg);
554 private:
void OnModelMsg(ConstModelPtr &_msg);
558 private:
void OnPoseMsg(ConstPosesStampedPtr &_msg);
562 private:
void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
567 private:
void CreateCOMVisual(ConstLinkPtr &_msg,
VisualPtr _linkVisual);
572 private:
void CreateCOMVisual(sdf::ElementPtr _elem,
576 private: std::string name;
579 private: sdf::ElementPtr sdf;
582 private: std::vector<CameraPtr> cameras;
585 private: std::vector<UserCameraPtr> userCameras;
588 private: Ogre::SceneManager *manager;
591 private: Ogre::RaySceneQuery *raySceneQuery;
594 private: std::vector<Grid *> grids;
597 private:
static uint32_t idCounter;
600 private: uint32_t id;
603 private: std::string idString;
607 typedef std::list<boost::shared_ptr<msgs::Visual const> > VisualMsgs_L;
610 private: VisualMsgs_L visualMsgs;
614 typedef std::list<boost::shared_ptr<msgs::Light const> > LightMsgs_L;
617 private: LightMsgs_L lightMsgs;
621 typedef std::map<uint32_t, msgs::Pose> PoseMsgs_M;
624 private: PoseMsgs_M poseMsgs;
628 typedef std::list<boost::shared_ptr<msgs::Scene const> > SceneMsgs_L;
631 private: SceneMsgs_L sceneMsgs;
635 typedef std::list<boost::shared_ptr<msgs::Joint const> > JointMsgs_L;
638 private: JointMsgs_L jointMsgs;
642 typedef std::list<boost::shared_ptr<msgs::Link const> > LinkMsgs_L;
645 private: LinkMsgs_L linkMsgs;
649 typedef std::list<boost::shared_ptr<msgs::Model const> > ModelMsgs_L;
651 private: ModelMsgs_L modelMsgs;
655 typedef std::list<boost::shared_ptr<msgs::Sensor const> > SensorMsgs_L;
658 private: SensorMsgs_L sensorMsgs;
662 typedef std::list<boost::shared_ptr<msgs::Request const> > RequestMsgs_L;
664 private: RequestMsgs_L requestMsgs;
668 typedef std::map<uint32_t, VisualPtr> Visual_M;
671 private: Visual_M visuals;
675 typedef std::map<std::string, LightPtr> Light_M;
678 private: Light_M lights;
682 typedef std::list<boost::shared_ptr<msgs::PoseAnimation const> >
685 private: SkeletonPoseMsgs_L skeletonPoseMsgs;
688 private: boost::shared_ptr<msgs::Selection const> selectionMsg;
691 private: boost::mutex *receiveMutex;
694 private: boost::recursive_mutex poseMsgMutex;
745 private: std::vector<event::ConnectionPtr> connections;
758 private: std::string selectionMode;
761 private: msgs::Request *requestMsg;
764 private:
bool enableVisualizations;
767 private: Heightmap *terrain;
770 private: std::map<std::string, Projector *> projectors;
776 private: SkyX::BasicController *skyxController;
779 private:
bool showCOMs;
782 private:
bool showCollisions;
785 private:
bool showJoints;
788 private:
bool transparent;
791 private:
bool wireframe;
794 private:
bool initialized;
805 private: uint32_t contactVisId;
809 typedef boost::unordered_map<std::string,
810 boost::shared_ptr<msgs::Joint const> > JointMsgs_M;
813 private: JointMsgs_M joints;