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 =
"");
84 public:
void Save(
const std::string &_filename);
96 public:
void Run(
unsigned int _iterations = 0);
113 public:
void Clear();
117 public: std::string
GetName()
const;
152 public:
void Reset();
258 public: std::string
StripWorldName(
const std::string &_name)
const;
280 public:
void LoadPlugin(
const std::string &_filename,
281 const std::string &_name,
291 {
return this->setWorldPoseMutex;}
296 {
return this->enablePhysicsEngine;}
301 {this->enablePhysicsEngine = _enable;}
324 private:
ModelPtr GetModelById(
unsigned int _id);
330 private:
void LoadPlugins();
356 private:
void RunLoop();
359 private:
void Step();
362 private:
void LogStep();
365 private:
void Update();
369 private:
void OnPause(
bool _p);
372 private:
void OnStep();
376 private:
void OnControl(ConstWorldControlPtr &_data);
380 private:
void OnRequest(ConstRequestPtr &_msg);
384 private:
void SetSelectedEntityCB(
const std::string &_name);
390 private:
void BuildSceneMsg(msgs::Scene &_scene,
BasePtr _entity);
394 private:
void JointLog(ConstJointPtr &_msg);
398 private:
void OnFactoryMsg(ConstFactoryPtr &_data);
402 private:
void OnModelMsg(ConstModelPtr &_msg);
405 private:
void ModelUpdateTBB();
408 private:
void ModelUpdateSingleLoop();
417 private:
void FillModelMsg(msgs::Model &_msg,
ModelPtr _model);
421 private:
void ProcessEntityMsgs();
425 private:
void ProcessRequestMsgs();
429 private:
void ProcessFactoryMsgs();
433 private:
void ProcessModelMsgs();
436 private:
bool OnLog(std::ostringstream &_stream);
439 private:
void ProcessMessages();
442 private:
void PublishWorldStats();
445 private:
void LogWorker();
457 private: boost::thread *thread;
466 private: std::string name;
481 private:
int stepInc;
529 private: msgs::WorldStatistics worldStatsMsg;
532 private: msgs::Scene sceneMsg;
535 private: void (
World::*modelUpdateFunc)();
547 private: boost::recursive_mutex *receiveMutex;
550 private: boost::mutex *loadModelMutex;
556 private: boost::mutex *setWorldPoseMutex;
564 private: boost::recursive_mutex *worldUpdateMutex;
570 private: std::vector<WorldPluginPtr> plugins;
573 private: std::list<std::string> deleteEntity;
581 private: std::list<msgs::Request> requestMsgs;
584 private: std::list<msgs::Factory> factoryMsgs;
587 private: std::list<msgs::Model> modelMsgs;
590 private:
bool needsReset;
593 private:
bool resetAll;
596 private:
bool resetTimeOnly;
599 private:
bool resetModelOnly;
602 private:
bool initialized;
605 private:
bool loaded;
608 private:
bool enablePhysicsEngine;
614 private:
bool pluginsLoaded;
626 private: std::deque<WorldState> states[2];
629 private:
int currentStateBuffer;
632 private:
int stateToggle;
642 private: std::set<ModelPtr> publishModelPoses;
648 private: uint64_t iterations;
651 private: uint64_t stopIterations;
654 private: boost::condition_variable logCondition;
658 private: boost::condition_variable logContinueCondition;
661 private: uint64_t logPrevIteration;
667 private: boost::mutex logMutex;
670 private: boost::mutex logBufferMutex;
673 private: boost::mutex entityDeleteMutex;
676 private: boost::thread *logThread;