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 <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 
113  public: void Clear();
114 
117  public: std::string GetName() const;
118 
123  public: PhysicsEnginePtr GetPhysicsEngine() const;
124 
128 
131  public: unsigned int GetModelCount() const;
132 
139  public: ModelPtr GetModel(unsigned int _index) const;
140 
143  public: Model_V GetModels() const;
144 
150  public: void ResetEntities(Base::EntityType _type = Base::BASE);
151 
153  public: void ResetTime();
154 
156  public: void Reset();
157 
162  public: EntityPtr GetSelectedEntity() const;
163 
167  public: void PrintEntityTree();
168 
172  public: common::Time GetSimTime() const;
173 
176  public: void SetSimTime(const common::Time &_t);
177 
180  public: common::Time GetPauseTime() const;
181 
184  public: common::Time GetStartTime() const;
185 
188  public: common::Time GetRealTime() const;
189 
192  public: bool IsPaused() const;
193 
196  public: void SetPaused(bool _p);
197 
204  public: BasePtr GetByName(const std::string &_name);
205 
212  public: ModelPtr GetModel(const std::string &_name);
213 
220  public: EntityPtr GetEntity(const std::string &_name);
221 
227  public: ModelPtr GetModelBelowPoint(const math::Vector3 &_pt);
228 
235  public: EntityPtr GetEntityBelowPoint(const math::Vector3 &_pt);
236 
239  public: void SetState(const WorldState &_state);
240 
245  public: void InsertModelFile(const std::string &_sdfFilename);
246 
251  public: void InsertModelString(const std::string &_sdfString);
252 
257  public: void InsertModelSDF(const sdf::SDF &_sdf);
258 
262  public: std::string StripWorldName(const std::string &_name) const;
263 
268  public: void EnableAllModels();
269 
274  public: void DisableAllModels();
275 
278  public: void StepWorld(int _steps);
279 
284  public: void LoadPlugin(const std::string &_filename,
285  const std::string &_name,
286  sdf::ElementPtr _sdf);
287 
290  public: void RemovePlugin(const std::string &_name);
291 
294  public: boost::mutex *GetSetWorldPoseMutex() const
295  {return this->setWorldPoseMutex;}
296 
299  public: bool GetEnablePhysicsEngine()
300  {return this->enablePhysicsEngine;}
301 
304  public: void EnablePhysicsEngine(bool _enable)
305  {this->enablePhysicsEngine = _enable;}
306 
308  public: void UpdateStateSDF();
309 
312  public: bool IsLoaded() const;
313 
318  public: void PublishModelPose(physics::ModelPtr _model);
319 
328  private: ModelPtr GetModelById(unsigned int _id);
330 
334  private: void LoadPlugins();
335 
339  private: void LoadEntities(sdf::ElementPtr _sdf, BasePtr _parent);
340 
345  private: ModelPtr LoadModel(sdf::ElementPtr _sdf, BasePtr _parent);
346 
351  private: ActorPtr LoadActor(sdf::ElementPtr _sdf, BasePtr _parent);
352 
357  private: RoadPtr LoadRoad(sdf::ElementPtr _sdf, BasePtr _parent);
358 
360  private: void RunLoop();
361 
363  private: void Step();
364 
366  private: void LogStep();
367 
369  private: void Update();
370 
373  private: void OnPause(bool _p);
374 
376  private: void OnStep();
377 
380  private: void OnControl(ConstWorldControlPtr &_data);
381 
384  private: void OnRequest(ConstRequestPtr &_msg);
385 
388  private: void SetSelectedEntityCB(const std::string &_name);
389 
394  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
395 
398  private: void JointLog(ConstJointPtr &_msg);
399 
402  private: void OnFactoryMsg(ConstFactoryPtr &_data);
403 
406  private: void OnModelMsg(ConstModelPtr &_msg);
407 
409  private: void ModelUpdateTBB();
410 
412  private: void ModelUpdateSingleLoop();
413 
416  private: void LoadPlugin(sdf::ElementPtr _sdf);
417 
421  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
422 
425  private: void ProcessEntityMsgs();
426 
429  private: void ProcessRequestMsgs();
430 
433  private: void ProcessFactoryMsgs();
434 
438  private: void RemoveModel(const std::string &_name);
439 
442  private: void ProcessModelMsgs();
443 
445  private: bool OnLog(std::ostringstream &_stream);
446 
448  private: void ProcessMessages();
449 
451  private: void PublishWorldStats();
452 
454  private: void LogWorker();
455 
457  private: common::Time prevStepWallTime;
458 
460  private: PhysicsEnginePtr physicsEngine;
461 
463  private: common::SphericalCoordinatesPtr sphericalCoordinates;
464 
466  private: BasePtr rootElement;
467 
469  private: boost::thread *thread;
470 
472  private: bool stop;
473 
475  private: EntityPtr selectedEntity;
476 
478  private: std::string name;
479 
481  private: common::Time simTime;
482 
484  private: common::Time pauseTime;
485 
487  private: common::Time startTime;
488 
490  private: bool pause;
491 
493  private: int stepInc;
494 
496  private: event::Connection_V connections;
497 
499  private: transport::NodePtr node;
500 
502  private: transport::PublisherPtr selectionPub;
503 
505  private: transport::PublisherPtr statPub;
506 
508  private: transport::PublisherPtr diagPub;
509 
511  private: transport::PublisherPtr responsePub;
512 
514  private: transport::PublisherPtr modelPub;
515 
517  private: transport::PublisherPtr guiPub;
518 
520  private: transport::PublisherPtr lightPub;
521 
523  private: transport::PublisherPtr posePub;
524 
526  private: transport::PublisherPtr poseLocalPub;
527 
529  private: transport::SubscriberPtr controlSub;
530 
532  private: transport::SubscriberPtr factorySub;
533 
535  private: transport::SubscriberPtr jointSub;
536 
538  private: transport::SubscriberPtr modelSub;
539 
541  private: transport::SubscriberPtr requestSub;
542 
544  private: msgs::WorldStatistics worldStatsMsg;
545 
547  private: msgs::Scene sceneMsg;
548 
550  private: void (World::*modelUpdateFunc)();
551 
553  private: common::Time prevStatTime;
554 
556  private: common::Time pauseStartTime;
557 
559  private: common::Time realTimeOffset;
560 
562  private: boost::recursive_mutex *receiveMutex;
563 
565  private: boost::mutex *loadModelMutex;
566 
571  private: boost::mutex *setWorldPoseMutex;
572 
579  private: boost::recursive_mutex *worldUpdateMutex;
580 
582  private: sdf::ElementPtr sdf;
583 
585  private: std::vector<WorldPluginPtr> plugins;
586 
588  private: std::list<std::string> deleteEntity;
589 
593  public: std::list<Entity*> dirtyPoses;
594 
596  private: std::list<msgs::Request> requestMsgs;
597 
599  private: std::list<msgs::Factory> factoryMsgs;
600 
602  private: std::list<msgs::Model> modelMsgs;
603 
605  private: bool needsReset;
606 
608  private: bool resetAll;
609 
611  private: bool resetTimeOnly;
612 
614  private: bool resetModelOnly;
615 
617  private: bool initialized;
618 
620  private: bool loaded;
621 
623  private: bool enablePhysicsEngine;
624 
626  private: RayShapePtr testRay;
627 
629  private: bool pluginsLoaded;
630 
632  private: common::Time sleepOffset;
633 
635  private: common::Time prevProcessMsgsTime;
636 
638  private: common::Time processMsgsPeriod;
639 
641  private: std::deque<WorldState> states[2];
642 
644  private: int currentStateBuffer;
645 
646  private: WorldState prevStates[2];
647  private: int stateToggle;
648 
649  private: sdf::ElementPtr logPlayStateSDF;
650  private: WorldState logPlayState;
651 
654  private: sdf::SDFPtr factorySDF;
655 
657  private: std::set<ModelPtr> publishModelPoses;
658 
660  private: common::UpdateInfo updateInfo;
661 
663  private: uint64_t iterations;
664 
666  private: uint64_t stopIterations;
667 
669  private: boost::condition_variable logCondition;
670 
673  private: boost::condition_variable logContinueCondition;
674 
676  private: uint64_t logPrevIteration;
677 
679  private: common::Time logRealTime;
680 
682  private: boost::mutex logMutex;
683 
685  private: boost::mutex logBufferMutex;
686 
688  private: boost::mutex entityDeleteMutex;
689 
691  private: boost::thread *logThread;
692 
694  private: Model_V models;
695  };
697  }
698 }
699 #endif