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 (C) 2012-2014 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 <set>
28 #include <deque>
29 #include <string>
30 #include <boost/thread.hpp>
31 #include <boost/enable_shared_from_this.hpp>
32 #include <boost/shared_ptr.hpp>
33 
34 #include <sdf/sdf.hh>
35 
37 
38 #include "gazebo/msgs/msgs.hh"
39 
42 #include "gazebo/common/Event.hh"
43 
44 #include "gazebo/physics/Base.hh"
47 
48 namespace gazebo
49 {
50  namespace physics
51  {
54 
63  class World : public boost::enable_shared_from_this<World>
64  {
69  public: explicit World(const std::string &_name = "");
70 
72  public: ~World();
73 
78  public: void Load(sdf::ElementPtr _sdf);
79 
84  public: void Save(const std::string &_filename);
85 
89  public: void Init();
90 
96  public: void Run(unsigned int _iterations = 0);
97 
100  public: bool GetRunning() const;
101 
105  public: void Stop();
106 
110  public: void Fini();
111 
115  public: void Clear();
116 
119  public: std::string GetName() const;
120 
125  public: PhysicsEnginePtr GetPhysicsEngine() const;
126 
130 
133  public: unsigned int GetModelCount() const;
134 
141  public: ModelPtr GetModel(unsigned int _index) const;
142 
145  public: Model_V GetModels() const;
146 
152  public: void ResetEntities(Base::EntityType _type = Base::BASE);
153 
155  public: void ResetTime();
156 
158  public: void Reset();
159 
164  public: EntityPtr GetSelectedEntity() const;
165 
169  public: void PrintEntityTree();
170 
174  public: common::Time GetSimTime() const;
175 
178  public: void SetSimTime(const common::Time &_t);
179 
182  public: common::Time GetPauseTime() const;
183 
186  public: common::Time GetStartTime() const;
187 
190  public: common::Time GetRealTime() const;
191 
194  public: bool IsPaused() const;
195 
198  public: void SetPaused(bool _p);
199 
206  public: BasePtr GetByName(const std::string &_name);
207 
214  public: ModelPtr GetModel(const std::string &_name);
215 
222  public: EntityPtr GetEntity(const std::string &_name);
223 
229  public: ModelPtr GetModelBelowPoint(const math::Vector3 &_pt);
230 
237  public: EntityPtr GetEntityBelowPoint(const math::Vector3 &_pt);
238 
241  public: void SetState(const WorldState &_state);
242 
247  public: void InsertModelFile(const std::string &_sdfFilename);
248 
253  public: void InsertModelString(const std::string &_sdfString);
254 
259  public: void InsertModelSDF(const sdf::SDF &_sdf);
260 
264  public: std::string StripWorldName(const std::string &_name) const;
265 
270  public: void EnableAllModels();
271 
276  public: void DisableAllModels();
277 
280  public: void StepWorld(int _steps);
281 
286  public: void LoadPlugin(const std::string &_filename,
287  const std::string &_name,
288  sdf::ElementPtr _sdf);
289 
292  public: void RemovePlugin(const std::string &_name);
293 
296  public: boost::mutex *GetSetWorldPoseMutex() const
297  {return this->setWorldPoseMutex;}
298 
301  public: bool GetEnablePhysicsEngine()
302  {return this->enablePhysicsEngine;}
303 
306  public: void EnablePhysicsEngine(bool _enable)
307  {this->enablePhysicsEngine = _enable;}
308 
310  public: void UpdateStateSDF();
311 
314  public: bool IsLoaded() const;
315 
320  public: void PublishModelPose(physics::ModelPtr _model);
321 
330  private: ModelPtr GetModelById(unsigned int _id);
332 
336  private: void LoadPlugins();
337 
341  private: void LoadEntities(sdf::ElementPtr _sdf, BasePtr _parent);
342 
347  private: ModelPtr LoadModel(sdf::ElementPtr _sdf, BasePtr _parent);
348 
353  private: ActorPtr LoadActor(sdf::ElementPtr _sdf, BasePtr _parent);
354 
359  private: RoadPtr LoadRoad(sdf::ElementPtr _sdf, BasePtr _parent);
360 
362  private: void RunLoop();
363 
365  private: void Step();
366 
368  private: void LogStep();
369 
371  private: void Update();
372 
375  private: void OnPause(bool _p);
376 
378  private: void OnStep();
379 
382  private: void OnControl(ConstWorldControlPtr &_data);
383 
386  private: void OnRequest(ConstRequestPtr &_msg);
387 
390  private: void SetSelectedEntityCB(const std::string &_name);
391 
396  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
397 
400  private: void JointLog(ConstJointPtr &_msg);
401 
404  private: void OnFactoryMsg(ConstFactoryPtr &_data);
405 
408  private: void OnModelMsg(ConstModelPtr &_msg);
409 
411  private: void ModelUpdateTBB();
412 
414  private: void ModelUpdateSingleLoop();
415 
418  private: void LoadPlugin(sdf::ElementPtr _sdf);
419 
423  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
424 
427  private: void ProcessEntityMsgs();
428 
431  private: void ProcessRequestMsgs();
432 
435  private: void ProcessFactoryMsgs();
436 
440  private: void RemoveModel(const std::string &_name);
441 
444  private: void ProcessModelMsgs();
445 
447  private: bool OnLog(std::ostringstream &_stream);
448 
450  private: void ProcessMessages();
451 
453  private: void PublishWorldStats();
454 
456  private: void LogWorker();
457 
460  public: void ClearModels();
461 
463  private: common::Time prevStepWallTime;
464 
466  private: PhysicsEnginePtr physicsEngine;
467 
469  private: common::SphericalCoordinatesPtr sphericalCoordinates;
470 
472  private: BasePtr rootElement;
473 
475  private: boost::thread *thread;
476 
478  private: bool stop;
479 
481  private: EntityPtr selectedEntity;
482 
484  private: std::string name;
485 
487  private: common::Time simTime;
488 
490  private: common::Time pauseTime;
491 
493  private: common::Time startTime;
494 
496  private: bool pause;
497 
499  private: int stepInc;
500 
502  private: event::Connection_V connections;
503 
505  private: transport::NodePtr node;
506 
508  private: transport::PublisherPtr selectionPub;
509 
511  private: transport::PublisherPtr statPub;
512 
514  private: transport::PublisherPtr diagPub;
515 
517  private: transport::PublisherPtr responsePub;
518 
520  private: transport::PublisherPtr modelPub;
521 
523  private: transport::PublisherPtr guiPub;
524 
526  private: transport::PublisherPtr lightPub;
527 
529  private: transport::PublisherPtr posePub;
530 
532  private: transport::PublisherPtr poseLocalPub;
533 
535  private: transport::SubscriberPtr controlSub;
536 
538  private: transport::SubscriberPtr factorySub;
539 
541  private: transport::SubscriberPtr jointSub;
542 
544  private: transport::SubscriberPtr modelSub;
545 
547  private: transport::SubscriberPtr requestSub;
548 
550  private: msgs::WorldStatistics worldStatsMsg;
551 
553  private: msgs::Scene sceneMsg;
554 
556  private: void (World::*modelUpdateFunc)();
557 
559  private: common::Time prevStatTime;
560 
562  private: common::Time pauseStartTime;
563 
565  private: common::Time realTimeOffset;
566 
568  private: boost::recursive_mutex *receiveMutex;
569 
571  private: boost::mutex *loadModelMutex;
572 
577  private: boost::mutex *setWorldPoseMutex;
578 
585  private: boost::recursive_mutex *worldUpdateMutex;
586 
588  private: sdf::ElementPtr sdf;
589 
591  private: std::vector<WorldPluginPtr> plugins;
592 
594  private: std::list<std::string> deleteEntity;
595 
599  public: std::list<Entity*> dirtyPoses;
600 
602  private: std::list<msgs::Request> requestMsgs;
603 
605  private: std::list<msgs::Factory> factoryMsgs;
606 
608  private: std::list<msgs::Model> modelMsgs;
609 
611  private: bool needsReset;
612 
614  private: bool resetAll;
615 
617  private: bool resetTimeOnly;
618 
620  private: bool resetModelOnly;
621 
623  private: bool initialized;
624 
626  private: bool loaded;
627 
629  private: bool enablePhysicsEngine;
630 
632  private: RayShapePtr testRay;
633 
635  private: bool pluginsLoaded;
636 
638  private: common::Time sleepOffset;
639 
641  private: common::Time prevProcessMsgsTime;
642 
644  private: common::Time processMsgsPeriod;
645 
647  private: std::deque<WorldState> states[2];
648 
650  private: int currentStateBuffer;
651 
652  private: WorldState prevStates[2];
653  private: int stateToggle;
654 
655  private: sdf::ElementPtr logPlayStateSDF;
656  private: WorldState logPlayState;
657 
660  private: sdf::SDFPtr factorySDF;
661 
663  private: std::set<ModelPtr> publishModelPoses;
664 
666  private: common::UpdateInfo updateInfo;
667 
669  private: uint64_t iterations;
670 
672  private: uint64_t stopIterations;
673 
675  private: boost::condition_variable logCondition;
676 
679  private: boost::condition_variable logContinueCondition;
680 
682  private: uint64_t logPrevIteration;
683 
685  private: common::Time logRealTime;
686 
688  private: boost::mutex logMutex;
689 
691  private: boost::mutex logBufferMutex;
692 
694  private: boost::mutex entityDeleteMutex;
695 
697  private: boost::thread *logThread;
698 
700  private: Model_V models;
701  };
703  }
704 }
705 #endif