30 #include <boost/thread.hpp>
31 #include <boost/enable_shared_from_this.hpp>
32 #include <boost/shared_ptr.hpp>
63 class World :
public boost::enable_shared_from_this<World>
69 public:
explicit World(
const std::string &_name =
"");
78 public:
void Load(sdf::ElementPtr _sdf);
84 public:
void Save(
const std::string &_filename);
96 public:
void Run(
unsigned int _iterations = 0);
115 public:
void Clear();
119 public: std::string
GetName()
const;
158 public:
void Reset();
264 public: std::string
StripWorldName(
const std::string &_name)
const;
286 public:
void LoadPlugin(
const std::string &_filename,
287 const std::string &_name,
288 sdf::ElementPtr _sdf);
297 {
return this->setWorldPoseMutex;}
302 {
return this->enablePhysicsEngine;}
307 {this->enablePhysicsEngine = _enable;}
330 private:
ModelPtr GetModelById(
unsigned int _id);
336 private:
void LoadPlugins();
341 private:
void LoadEntities(sdf::ElementPtr _sdf,
BasePtr _parent);
362 private:
void RunLoop();
365 private:
void Step();
368 private:
void LogStep();
371 private:
void Update();
375 private:
void OnPause(
bool _p);
378 private:
void OnStep();
382 private:
void OnControl(ConstWorldControlPtr &_data);
386 private:
void OnRequest(ConstRequestPtr &_msg);
390 private:
void SetSelectedEntityCB(
const std::string &_name);
396 private:
void BuildSceneMsg(msgs::Scene &_scene,
BasePtr _entity);
400 private:
void JointLog(ConstJointPtr &_msg);
404 private:
void OnFactoryMsg(ConstFactoryPtr &_data);
408 private:
void OnModelMsg(ConstModelPtr &_msg);
411 private:
void ModelUpdateTBB();
414 private:
void ModelUpdateSingleLoop();
418 private:
void LoadPlugin(sdf::ElementPtr _sdf);
423 private:
void FillModelMsg(msgs::Model &_msg,
ModelPtr _model);
427 private:
void ProcessEntityMsgs();
431 private:
void ProcessRequestMsgs();
435 private:
void ProcessFactoryMsgs();
440 private:
void RemoveModel(
const std::string &_name);
444 private:
void ProcessModelMsgs();
447 private:
bool OnLog(std::ostringstream &_stream);
450 private:
void ProcessMessages();
453 private:
void PublishWorldStats();
456 private:
void LogWorker();
475 private: boost::thread *thread;
484 private: std::string name;
499 private:
int stepInc;
550 private: msgs::WorldStatistics worldStatsMsg;
553 private: msgs::Scene sceneMsg;
556 private: void (
World::*modelUpdateFunc)();
568 private: boost::recursive_mutex *receiveMutex;
571 private: boost::mutex *loadModelMutex;
577 private: boost::mutex *setWorldPoseMutex;
585 private: boost::recursive_mutex *worldUpdateMutex;
588 private: sdf::ElementPtr sdf;
591 private: std::vector<WorldPluginPtr> plugins;
594 private: std::list<std::string> deleteEntity;
602 private: std::list<msgs::Request> requestMsgs;
605 private: std::list<msgs::Factory> factoryMsgs;
608 private: std::list<msgs::Model> modelMsgs;
611 private:
bool needsReset;
614 private:
bool resetAll;
617 private:
bool resetTimeOnly;
620 private:
bool resetModelOnly;
623 private:
bool initialized;
626 private:
bool loaded;
629 private:
bool enablePhysicsEngine;
635 private:
bool pluginsLoaded;
647 private: std::deque<WorldState> states[2];
650 private:
int currentStateBuffer;
653 private:
int stateToggle;
655 private: sdf::ElementPtr logPlayStateSDF;
660 private: sdf::SDFPtr factorySDF;
663 private: std::set<ModelPtr> publishModelPoses;
669 private: uint64_t iterations;
672 private: uint64_t stopIterations;
675 private: boost::condition_variable logCondition;
679 private: boost::condition_variable logContinueCondition;
682 private: uint64_t logPrevIteration;
688 private: boost::mutex logMutex;
691 private: boost::mutex logBufferMutex;
694 private: boost::mutex entityDeleteMutex;
697 private: boost::thread *logThread;