24 #include <boost/enable_shared_from_this.hpp>
25 #include <boost/shared_ptr.hpp>
40 class BasicController;
76 class Scene :
public boost::enable_shared_from_this<Scene>
86 public:
Scene(
const std::string &_name,
87 bool _enableVisualizations =
false);
107 public: Ogre::SceneManager *
GetManager()
const;
111 public: std::string
GetName()
const;
134 public:
void CreateGrid(uint32_t _cellCount,
float _cellLength,
152 bool _autoRender =
true);
160 bool _autoRender =
true);
225 const std::string &_mode);
268 std::vector<VisualPtr> &_visuals);
293 public:
void SetVisible(
const std::string &_name,
bool _visible);
301 const std::string &_name);
310 public:
void SetFog(
const std::string &_type,
312 double _density,
double _start,
double _end);
316 public: uint32_t
GetId()
const;
340 public:
void SetGrid(
bool _enabled);
349 public: std::string
StripSceneName(
const std::string &_name)
const;
356 public:
void Clear();
363 const std::string &_newName);
394 private:
void SetSky();
397 private:
void InitDeferredShading();
405 private: Ogre::Entity *GetOgreEntityAt(
CameraPtr _camera,
407 bool _ignorSelectionObj);
419 private:
void GetMeshInformation(
const Ogre::Mesh *_mesh,
420 size_t &_vertexCount,
421 Ogre::Vector3* &_vertices,
424 const Ogre::Vector3 &_position,
425 const Ogre::Quaternion &_orient,
426 const Ogre::Vector3 &_scale);
431 private:
void PrintSceneGraphHelper(
const std::string &_prefix,
437 private:
void OnScene(ConstScenePtr &_msg);
441 private:
void OnResponse(ConstResponsePtr &_msg);
445 private:
void OnRequest(ConstRequestPtr &_msg);
449 private:
void OnJointMsg(ConstJointPtr &_msg);
453 private:
bool ProcessSensorMsg(ConstSensorPtr &_msg);
457 private:
bool ProcessJointMsg(ConstJointPtr &_msg);
461 private:
bool ProcessLinkMsg(ConstLinkPtr &_msg);
465 private:
void ProcessSceneMsg(ConstScenePtr &_msg);
469 private:
bool ProcessModelMsg(
const msgs::Model &_msg);
473 private:
void OnSensorMsg(ConstSensorPtr &_msg);
477 private:
void OnVisualMsg(ConstVisualPtr &_msg);
481 private:
bool ProcessVisualMsg(ConstVisualPtr &_msg);
485 private:
void OnLightMsg(ConstLightPtr &_msg);
489 private:
void ProcessLightMsg(ConstLightPtr &_msg);
493 private:
void ProcessRequestMsg(ConstRequestPtr &_msg);
497 private:
void OnSelectionMsg(ConstSelectionPtr &_msg);
501 private:
void OnSkyMsg(ConstSkyPtr &_msg);
505 private:
void OnModelMsg(ConstModelPtr &_msg);
509 private:
void OnPoseMsg(ConstPose_VPtr &_msg);
513 private:
void OnSkeletonPoseMsg(ConstPoseAnimationPtr &_msg);
518 private:
void CreateCOMVisual(ConstLinkPtr &_msg,
VisualPtr _linkVisual);
527 private: std::string name;
533 private: std::vector<CameraPtr> cameras;
536 private: std::vector<UserCameraPtr> userCameras;
539 private: Ogre::SceneManager *manager;
542 private: Ogre::RaySceneQuery *raySceneQuery;
545 private: std::vector<Grid *> grids;
548 private:
static uint32_t idCounter;
551 private: uint32_t id;
554 private: std::string idString;
558 typedef std::list<boost::shared_ptr<msgs::Visual const> > VisualMsgs_L;
561 private: VisualMsgs_L visualMsgs;
565 typedef std::list<boost::shared_ptr<msgs::Light const> > LightMsgs_L;
568 private: LightMsgs_L lightMsgs;
572 typedef std::list<msgs::Pose> PoseMsgs_L;
575 private: PoseMsgs_L poseMsgs;
579 typedef std::list<boost::shared_ptr<msgs::Scene const> > SceneMsgs_L;
582 private: SceneMsgs_L sceneMsgs;
586 typedef std::list<boost::shared_ptr<msgs::Joint const> > JointMsgs_L;
589 private: JointMsgs_L jointMsgs;
593 typedef std::list<boost::shared_ptr<msgs::Link const> > LinkMsgs_L;
596 private: LinkMsgs_L linkMsgs;
600 typedef std::list<boost::shared_ptr<msgs::Model const> > ModelMsgs_L;
602 private: ModelMsgs_L modelMsgs;
606 typedef std::list<boost::shared_ptr<msgs::Sensor const> > SensorMsgs_L;
609 private: SensorMsgs_L sensorMsgs;
613 typedef std::list<boost::shared_ptr<msgs::Request const> > RequestMsgs_L;
615 private: RequestMsgs_L requestMsgs;
619 typedef std::map<std::string, VisualPtr> Visual_M;
622 private: Visual_M visuals;
626 typedef std::map<std::string, LightPtr> Light_M;
629 private: Light_M lights;
633 typedef std::list<boost::shared_ptr<msgs::PoseAnimation const> >
636 private: SkeletonPoseMsgs_L skeletonPoseMsgs;
639 private: boost::shared_ptr<msgs::Selection const> selectionMsg;
642 private: boost::mutex *receiveMutex;
693 private: std::vector<event::ConnectionPtr> connections;
706 private: std::string selectionMode;
709 private: msgs::Request *requestMsg;
712 private:
bool enableVisualizations;
718 private: std::map<std::string, Projector *> projectors;
724 private: SkyX::BasicController *skyxController;
727 private:
bool showCOMs;
730 private:
bool showCollisions;
733 private:
bool showJoints;
736 private:
bool transparent;
739 private:
bool initialized;