All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
World.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /* Desc: The world; all models are collected here
18  * Author: Andrew Howard and Nate Koenig
19  * Date: 3 Apr 2007
20  */
21 
22 #ifndef _WORLD_HH_
23 #define _WORLD_HH_
24 
25 #include <vector>
26 #include <list>
27 #include <deque>
28 #include <string>
29 #include <boost/enable_shared_from_this.hpp>
30 #include <boost/shared_ptr.hpp>
31 
33 
34 #include "gazebo/msgs/msgs.hh"
35 
37 #include "gazebo/common/Event.hh"
38 
39 #include "gazebo/physics/Base.hh"
42 #include "gazebo/sdf/sdf.hh"
43 
44 namespace boost
45 {
46  class thread;
47  class mutex;
48  class recursive_mutex;
49 }
50 
51 namespace gazebo
52 {
53  namespace physics
54  {
57 
66  class World : public boost::enable_shared_from_this<World>
67  {
72  public: explicit World(const std::string &_name = "");
73 
75  public: ~World();
76 
81  public: void Load(sdf::ElementPtr _sdf);
82 
87  public: void Save(const std::string &_filename);
88 
92  public: void Init();
93 
97  public: void Run();
98 
102  public: void Stop();
103 
107  public: void Fini();
108 
110  public: void Clear();
111 
114  public: std::string GetName() const;
115 
120  public: PhysicsEnginePtr GetPhysicsEngine() const;
121 
124  public: unsigned int GetModelCount() const;
125 
132  public: ModelPtr GetModel(unsigned int _index) const;
133 
136  public: Model_V GetModels() const;
137 
143  public: void ResetEntities(Base::EntityType _type = Base::BASE);
144 
146  public: void ResetTime();
147 
149  public: void Reset();
150 
155  public: EntityPtr GetSelectedEntity() const;
156 
160  public: void PrintEntityTree();
161 
165  public: common::Time GetSimTime() const;
166 
169  public: void SetSimTime(const common::Time &_t);
170 
173  public: common::Time GetPauseTime() const;
174 
177  public: common::Time GetStartTime() const;
178 
181  public: common::Time GetRealTime() const;
182 
185  public: bool IsPaused() const;
186 
189  public: void SetPaused(bool _p);
190 
197  public: BasePtr GetByName(const std::string &_name);
198 
205  public: ModelPtr GetModel(const std::string &_name);
206 
213  public: EntityPtr GetEntity(const std::string &_name);
214 
220  public: ModelPtr GetModelBelowPoint(const math::Vector3 &_pt);
221 
228  public: EntityPtr GetEntityBelowPoint(const math::Vector3 &_pt);
229 
232  public: void SetState(const WorldState &_state);
233 
238  public: void InsertModelFile(const std::string &_sdfFilename);
239 
244  public: void InsertModelString(const std::string &_sdfString);
245 
250  public: void InsertModelSDF(const sdf::SDF &_sdf);
251 
255  public: std::string StripWorldName(const std::string &_name) const;
256 
261  public: void EnableAllModels();
262 
267  public: void DisableAllModels();
268 
271  public: void StepWorld(int _steps);
272 
277  public: void LoadPlugin(const std::string &_filename,
278  const std::string &_name,
279  sdf::ElementPtr _sdf);
280 
283  public: void RemovePlugin(const std::string &_name);
284 
287  public: boost::mutex *GetSetWorldPoseMutex() const
288  {return this->setWorldPoseMutex;}
289 
292  public: bool GetEnablePhysicsEngine()
293  {return this->enablePhysicsEngine;}
294 
297  public: void EnablePhysicsEngine(bool _enable)
298  {this->enablePhysicsEngine = _enable;}
299 
301  public: void UpdateStateSDF();
302 
305  public: bool IsLoaded() const;
306 
310  public: void EnqueueMsg(msgs::Pose *_msg);
311 
318  private: ModelPtr GetModelById(unsigned int _id);
319 
323  private: void LoadPlugins();
324 
328  private: void LoadEntities(sdf::ElementPtr _sdf, BasePtr _parent);
329 
334  private: ModelPtr LoadModel(sdf::ElementPtr _sdf, BasePtr _parent);
335 
340  private: ActorPtr LoadActor(sdf::ElementPtr _sdf, BasePtr _parent);
341 
346  private: RoadPtr LoadRoad(sdf::ElementPtr _sdf, BasePtr _parent);
347 
349  private: void RunLoop();
350 
352  private: void Step();
353 
355  private: void LogStep();
356 
358  private: void Update();
359 
362  private: void OnPause(bool _p);
363 
365  private: void OnStep();
366 
369  private: void OnControl(ConstWorldControlPtr &_data);
370 
373  private: void OnRequest(ConstRequestPtr &_msg);
374 
377  private: void SetSelectedEntityCB(const std::string &_name);
378 
383  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
384 
387  private: void JointLog(ConstJointPtr &_msg);
388 
391  private: void OnFactoryMsg(ConstFactoryPtr &_data);
392 
395  private: void OnModelMsg(ConstModelPtr &_msg);
396 
398  private: void ModelUpdateTBB();
399 
401  private: void ModelUpdateSingleLoop();
402 
405  private: void LoadPlugin(sdf::ElementPtr _sdf);
406 
410  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
411 
414  private: void ProcessEntityMsgs();
415 
418  private: void ProcessRequestMsgs();
419 
422  private: void ProcessFactoryMsgs();
423 
426  private: void ProcessModelMsgs();
427 
429  private: bool OnLog(std::ostringstream &_stream);
430 
432  private: void ProcessMessages();
433 
435  private: void PublishWorldStats();
436 
438  private: common::Time prevStepWallTime;
439 
441  private: PhysicsEnginePtr physicsEngine;
442 
444  private: BasePtr rootElement;
445 
447  private: boost::thread *thread;
448 
450  private: bool stop;
451 
453  private: EntityPtr selectedEntity;
454 
456  private: std::vector<google::protobuf::Message> messages;
457 
459  private: std::string name;
460 
462  private: common::Time simTime;
463 
465  private: common::Time pauseTime;
466 
468  private: common::Time startTime;
469 
471  private: bool pause;
472 
474  private: int stepInc;
475 
477  private: event::Connection_V connections;
478 
480  private: transport::NodePtr node;
481 
483  private: transport::PublisherPtr selectionPub;
484 
486  private: transport::PublisherPtr statPub;
487 
489  private: transport::PublisherPtr responsePub;
490 
492  private: transport::PublisherPtr modelPub;
493 
495  private: transport::PublisherPtr guiPub;
496 
498  private: transport::PublisherPtr lightPub;
499 
501  private: transport::PublisherPtr posePub;
502 
504  private: transport::SubscriberPtr controlSub;
505 
507  private: transport::SubscriberPtr factorySub;
508 
510  private: transport::SubscriberPtr jointSub;
511 
513  private: transport::SubscriberPtr modelSub;
514 
516  private: transport::SubscriberPtr requestSub;
517 
519  private: msgs::WorldStatistics worldStatsMsg;
520 
522  private: msgs::Scene sceneMsg;
523 
525  private: void (World::*modelUpdateFunc)();
526 
528  private: common::Time statPeriod;
529 
531  private: common::Time prevStatTime;
532 
534  private: common::Time pauseStartTime;
535 
537  private: common::Time realTimeOffset;
538 
540  private: boost::recursive_mutex *receiveMutex;
541 
543  private: boost::mutex *loadModelMutex;
544 
549  private: boost::mutex *setWorldPoseMutex;
550 
557  private: boost::recursive_mutex *worldUpdateMutex;
558 
560  private: sdf::ElementPtr sdf;
561 
563  private: std::vector<WorldPluginPtr> plugins;
564 
566  private: std::list<std::string> deleteEntity;
567 
571  public: std::list<Entity*> dirtyPoses;
572 
574  private: std::list<msgs::Request> requestMsgs;
575 
577  private: std::list<msgs::Factory> factoryMsgs;
578 
580  private: std::list<msgs::Model> modelMsgs;
581 
583  private: bool needsReset;
584 
586  private: bool resetAll;
587 
589  private: bool resetTimeOnly;
590 
592  private: bool resetModelOnly;
593 
595  private: bool initialized;
596 
598  private: bool loaded;
599 
601  private: bool enablePhysicsEngine;
602 
604  private: RayShapePtr testRay;
605 
607  private: bool pluginsLoaded;
608 
610  private: common::Time sleepOffset;
611 
613  private: common::Time prevProcessMsgsTime;
614 
616  private: common::Time processMsgsPeriod;
617 
619  private: std::deque<WorldState> states;
620  private: WorldState prevStates[2];
621  private: int stateToggle;
622 
623  private: sdf::ElementPtr logPlayStateSDF;
624  private: WorldState logPlayState;
625 
628  private: sdf::SDFPtr factorySDF;
629 
631  private: msgs::Pose_V poseMsgs;
632  };
634  }
635 }
636 #endif