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/enable_shared_from_this.hpp>
31 #include <boost/shared_ptr.hpp>
32 
34 
35 #include "gazebo/msgs/msgs.hh"
36 
39 #include "gazebo/common/Event.hh"
40 
41 #include "gazebo/physics/Base.hh"
44 #include "gazebo/sdf/sdf.hh"
45 
46 namespace boost
47 {
48  class thread;
49  class mutex;
50  class recursive_mutex;
51 }
52 
53 namespace gazebo
54 {
55  namespace physics
56  {
59 
68  class World : public boost::enable_shared_from_this<World>
69  {
74  public: explicit World(const std::string &_name = "");
75 
77  public: ~World();
78 
83  public: void Load(sdf::ElementPtr _sdf);
84 
89  public: void Save(const std::string &_filename);
90 
94  public: void Init();
95 
99  public: void Run();
100 
104  public: void Stop();
105 
109  public: void Fini();
110 
112  public: void Clear();
113 
116  public: std::string GetName() const;
117 
122  public: PhysicsEnginePtr GetPhysicsEngine() const;
123 
126  public: unsigned int GetModelCount() const;
127 
134  public: ModelPtr GetModel(unsigned int _index) const;
135 
138  public: Model_V GetModels() const;
139 
145  public: void ResetEntities(Base::EntityType _type = Base::BASE);
146 
148  public: void ResetTime();
149 
151  public: void Reset();
152 
157  public: EntityPtr GetSelectedEntity() const;
158 
162  public: void PrintEntityTree();
163 
167  public: common::Time GetSimTime() const;
168 
171  public: void SetSimTime(const common::Time &_t);
172 
175  public: common::Time GetPauseTime() const;
176 
179  public: common::Time GetStartTime() const;
180 
183  public: common::Time GetRealTime() const;
184 
187  public: bool IsPaused() const;
188 
191  public: void SetPaused(bool _p);
192 
199  public: BasePtr GetByName(const std::string &_name);
200 
207  public: ModelPtr GetModel(const std::string &_name);
208 
215  public: EntityPtr GetEntity(const std::string &_name);
216 
222  public: ModelPtr GetModelBelowPoint(const math::Vector3 &_pt);
223 
230  public: EntityPtr GetEntityBelowPoint(const math::Vector3 &_pt);
231 
234  public: void SetState(const WorldState &_state);
235 
240  public: void InsertModelFile(const std::string &_sdfFilename);
241 
246  public: void InsertModelString(const std::string &_sdfString);
247 
252  public: void InsertModelSDF(const sdf::SDF &_sdf);
253 
257  public: std::string StripWorldName(const std::string &_name) const;
258 
263  public: void EnableAllModels();
264 
269  public: void DisableAllModels();
270 
273  public: void StepWorld(int _steps);
274 
279  public: void LoadPlugin(const std::string &_filename,
280  const std::string &_name,
281  sdf::ElementPtr _sdf);
282 
285  public: void RemovePlugin(const std::string &_name);
286 
289  public: boost::mutex *GetSetWorldPoseMutex() const
290  {return this->setWorldPoseMutex;}
291 
294  public: bool GetEnablePhysicsEngine()
295  {return this->enablePhysicsEngine;}
296 
299  public: void EnablePhysicsEngine(bool _enable)
300  {this->enablePhysicsEngine = _enable;}
301 
303  public: void UpdateStateSDF();
304 
307  public: bool IsLoaded() const;
308 
313  public: void PublishModelPose(physics::ModelPtr _model);
314 
323  private: ModelPtr GetModelById(unsigned int _id);
325 
329  private: void LoadPlugins();
330 
334  private: void LoadEntities(sdf::ElementPtr _sdf, BasePtr _parent);
335 
340  private: ModelPtr LoadModel(sdf::ElementPtr _sdf, BasePtr _parent);
341 
346  private: ActorPtr LoadActor(sdf::ElementPtr _sdf, BasePtr _parent);
347 
352  private: RoadPtr LoadRoad(sdf::ElementPtr _sdf, BasePtr _parent);
353 
355  private: void RunLoop();
356 
358  private: void Step();
359 
361  private: void LogStep();
362 
364  private: void Update();
365 
368  private: void OnPause(bool _p);
369 
371  private: void OnStep();
372 
375  private: void OnControl(ConstWorldControlPtr &_data);
376 
379  private: void OnLogControl(ConstLogControlPtr &_data);
380 
383  private: void OnRequest(ConstRequestPtr &_msg);
384 
387  private: void SetSelectedEntityCB(const std::string &_name);
388 
393  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
394 
397  private: void JointLog(ConstJointPtr &_msg);
398 
401  private: void OnFactoryMsg(ConstFactoryPtr &_data);
402 
405  private: void OnModelMsg(ConstModelPtr &_msg);
406 
408  private: void ModelUpdateTBB();
409 
411  private: void ModelUpdateSingleLoop();
412 
415  private: void LoadPlugin(sdf::ElementPtr _sdf);
416 
420  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
421 
424  private: void ProcessEntityMsgs();
425 
428  private: void ProcessRequestMsgs();
429 
432  private: void ProcessFactoryMsgs();
433 
436  private: void ProcessModelMsgs();
437 
439  private: bool OnLog(std::ostringstream &_stream);
440 
442  private: void ProcessMessages();
443 
445  private: void PublishWorldStats();
446 
448  private: void PublishLogStatus();
449 
451  private: common::Time prevStepWallTime;
452 
454  private: PhysicsEnginePtr physicsEngine;
455 
457  private: BasePtr rootElement;
458 
460  private: boost::thread *thread;
461 
463  private: bool stop;
464 
466  private: EntityPtr selectedEntity;
467 
469  private: std::vector<google::protobuf::Message> messages;
470 
472  private: std::string name;
473 
475  private: common::Time simTime;
476 
478  private: common::Time pauseTime;
479 
481  private: common::Time startTime;
482 
484  private: bool pause;
485 
487  private: int stepInc;
488 
490  private: event::Connection_V connections;
491 
493  private: transport::NodePtr node;
494 
496  private: transport::PublisherPtr selectionPub;
497 
499  private: transport::PublisherPtr statPub;
500 
502  private: transport::PublisherPtr diagPub;
503 
505  private: transport::PublisherPtr responsePub;
506 
508  private: transport::PublisherPtr modelPub;
509 
511  private: transport::PublisherPtr guiPub;
512 
514  private: transport::PublisherPtr lightPub;
515 
517  private: transport::PublisherPtr posePub;
518 
520  private: transport::SubscriberPtr controlSub;
521 
523  private: transport::SubscriberPtr logControlSub;
524 
526  private: transport::PublisherPtr logStatusPub;
527 
529  private: transport::SubscriberPtr factorySub;
530 
532  private: transport::SubscriberPtr jointSub;
533 
535  private: transport::SubscriberPtr modelSub;
536 
538  private: transport::SubscriberPtr requestSub;
539 
541  private: msgs::WorldStatistics worldStatsMsg;
542 
544  private: msgs::Scene sceneMsg;
545 
547  private: void (World::*modelUpdateFunc)();
548 
550  private: common::Time statPeriod;
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;
642  private: WorldState prevStates[2];
643  private: int stateToggle;
644 
645  private: sdf::ElementPtr logPlayStateSDF;
646  private: WorldState logPlayState;
647 
650  private: sdf::SDFPtr factorySDF;
651 
653  private: std::set<ModelPtr> publishModelPoses;
654 
656  private: common::UpdateInfo updateInfo;
657 
659  private: uint64_t iterations;
660  };
662  }
663 }
664 #endif