All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties 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 #ifndef _WORLD_HH_
18 #define _WORLD_HH_
19 
20 #include <vector>
21 #include <list>
22 #include <set>
23 #include <deque>
24 #include <string>
25 #include <boost/thread.hpp>
26 #include <boost/enable_shared_from_this.hpp>
27 #include <boost/shared_ptr.hpp>
28 
29 #include <sdf/sdf.hh>
30 
32 
33 #include "gazebo/msgs/msgs.hh"
34 
37 #include "gazebo/common/Event.hh"
38 
39 #include "gazebo/physics/Base.hh"
42 #include "gazebo/util/system.hh"
43 
44 namespace gazebo
45 {
46  namespace physics
47  {
50 
59  class GAZEBO_VISIBLE World : public boost::enable_shared_from_this<World>
60  {
64  public: explicit World(const std::string &_name = "");
65 
67  public: ~World();
68 
72  public: void Load(sdf::ElementPtr _sdf);
73 
77  public: void Save(const std::string &_filename);
78 
81  public: void Init();
82 
87  public: void Run(unsigned int _iterations = 0);
88 
91  public: bool GetRunning() const;
92 
95  public: void Stop();
96 
99  public: void Fini();
100 
104  public: void Clear();
105 
108  public: std::string GetName() const;
109 
113  public: PhysicsEnginePtr GetPhysicsEngine() const;
114 
117  public: common::SphericalCoordinatesPtr GetSphericalCoordinates() const;
118 
121  public: unsigned int GetModelCount() const;
122 
128  public: ModelPtr GetModel(unsigned int _index) const;
129 
132  public: Model_V GetModels() const;
133 
138  public: void ResetEntities(Base::EntityType _type = Base::BASE);
139 
141  public: void ResetTime();
142 
144  public: void Reset();
145 
149  public: EntityPtr GetSelectedEntity() const;
150 
153  public: void PrintEntityTree();
154 
158  public: common::Time GetSimTime() const;
159 
162  public: void SetSimTime(const common::Time &_t);
163 
166  public: common::Time GetPauseTime() const;
167 
170  public: common::Time GetStartTime() const;
171 
174  public: common::Time GetRealTime() const;
175 
178  public: bool IsPaused() const;
179 
182  public: void SetPaused(bool _p);
183 
189  public: BasePtr GetByName(const std::string &_name);
190 
196  public: ModelPtr GetModel(const std::string &_name);
197 
203  public: EntityPtr GetEntity(const std::string &_name);
204 
212  public: ModelPtr GetModelBelowPoint(const math::Vector3 &_pt);
213 
219  public: EntityPtr GetEntityBelowPoint(const math::Vector3 &_pt);
220 
223  public: void SetState(const WorldState &_state);
224 
228  public: void InsertModelFile(const std::string &_sdfFilename);
229 
233  public: void InsertModelString(const std::string &_sdfString);
234 
238  public: void InsertModelSDF(const sdf::SDF &_sdf);
239 
243  public: std::string StripWorldName(const std::string &_name) const;
244 
248  public: void EnableAllModels();
249 
253  public: void DisableAllModels();
254 
257  public: void Step(unsigned int _steps);
258 
263  public: void LoadPlugin(const std::string &_filename,
264  const std::string &_name,
265  sdf::ElementPtr _sdf);
266 
269  public: void RemovePlugin(const std::string &_name);
270 
273  public: boost::mutex *GetSetWorldPoseMutex() const
274  {return this->setWorldPoseMutex;}
275 
278  public: bool GetEnablePhysicsEngine()
279  {return this->enablePhysicsEngine;}
280 
283  public: void EnablePhysicsEngine(bool _enable)
284  {this->enablePhysicsEngine = _enable;}
285 
287  public: void UpdateStateSDF();
288 
291  public: bool IsLoaded() const;
292 
295  public: void ClearModels();
296 
301  public: void PublishModelPose(physics::ModelPtr _model);
302 
305  public: uint32_t GetIterations() const;
306 
309  public: msgs::Scene GetSceneMsg() const;
310 
315  public: void RunBlocking(unsigned int _iterations = 0);
316 
321  public: void RemoveModel(ModelPtr _model);
322 
327  public: void RemoveModel(const std::string &_name);
328 
336  private: ModelPtr GetModelById(unsigned int _id);
338 
342  private: void LoadPlugins();
343 
347  private: void LoadEntities(sdf::ElementPtr _sdf, BasePtr _parent);
348 
353  private: ModelPtr LoadModel(sdf::ElementPtr _sdf, BasePtr _parent);
354 
359  private: ActorPtr LoadActor(sdf::ElementPtr _sdf, BasePtr _parent);
360 
365  private: RoadPtr LoadRoad(sdf::ElementPtr _sdf, BasePtr _parent);
366 
368  private: void RunLoop();
369 
371  private: void Step();
372 
374  private: void LogStep();
375 
377  private: void Update();
378 
381  private: void OnPause(bool _p);
382 
384  private: void OnStep();
385 
388  private: void OnControl(ConstWorldControlPtr &_data);
389 
392  private: void OnRequest(ConstRequestPtr &_msg);
393 
396  private: void SetSelectedEntityCB(const std::string &_name);
397 
402  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
403 
406  private: void JointLog(ConstJointPtr &_msg);
407 
410  private: void OnFactoryMsg(ConstFactoryPtr &_data);
411 
414  private: void OnModelMsg(ConstModelPtr &_msg);
415 
417  private: void ModelUpdateTBB();
418 
420  private: void ModelUpdateSingleLoop();
421 
424  private: void LoadPlugin(sdf::ElementPtr _sdf);
425 
429  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
430 
433  private: void ProcessEntityMsgs();
434 
437  private: void ProcessRequestMsgs();
438 
441  private: void ProcessFactoryMsgs();
442 
445  private: void ProcessModelMsgs();
446 
448  private: bool OnLog(std::ostringstream &_stream);
449 
451  private: void ProcessMessages();
452 
454  private: void PublishWorldStats();
455 
457  private: void LogWorker();
458 
461  private: void OnLightMsg(ConstLightPtr &_msg);
462 
464  private: common::Time prevStepWallTime;
465 
467  private: PhysicsEnginePtr physicsEngine;
468 
470  private: common::SphericalCoordinatesPtr sphericalCoordinates;
471 
473  private: BasePtr rootElement;
474 
476  private: boost::thread *thread;
477 
479  private: bool stop;
480 
482  private: EntityPtr selectedEntity;
483 
485  private: std::string name;
486 
488  private: common::Time simTime;
489 
491  private: common::Time pauseTime;
492 
494  private: common::Time startTime;
495 
497  private: bool pause;
498 
500  private: int stepInc;
501 
503  private: event::Connection_V connections;
504 
506  private: transport::NodePtr node;
507 
509  private: transport::PublisherPtr selectionPub;
510 
512  private: transport::PublisherPtr statPub;
513 
515  private: transport::PublisherPtr diagPub;
516 
518  private: transport::PublisherPtr responsePub;
519 
521  private: transport::PublisherPtr modelPub;
522 
524  private: transport::PublisherPtr guiPub;
525 
527  private: transport::PublisherPtr lightPub;
528 
530  private: transport::PublisherPtr posePub;
531 
533  private: transport::PublisherPtr poseLocalPub;
534 
536  private: transport::SubscriberPtr controlSub;
537 
539  private: transport::SubscriberPtr factorySub;
540 
542  private: transport::SubscriberPtr jointSub;
543 
545  private: transport::SubscriberPtr lightSub;
546 
548  private: transport::SubscriberPtr modelSub;
549 
551  private: transport::SubscriberPtr requestSub;
552 
554  private: msgs::WorldStatistics worldStatsMsg;
555 
557  private: msgs::Scene sceneMsg;
558 
560  private: void (World::*modelUpdateFunc)();
561 
563  private: common::Time prevStatTime;
564 
566  private: common::Time pauseStartTime;
567 
569  private: common::Time realTimeOffset;
570 
572  private: boost::recursive_mutex *receiveMutex;
573 
575  private: boost::mutex *loadModelMutex;
576 
581  private: boost::mutex *setWorldPoseMutex;
582 
589  private: boost::recursive_mutex *worldUpdateMutex;
590 
592  private: sdf::ElementPtr sdf;
593 
595  private: std::vector<WorldPluginPtr> plugins;
596 
598  private: std::list<std::string> deleteEntity;
599 
603  public: std::list<Entity*> dirtyPoses;
604 
606  private: std::list<msgs::Request> requestMsgs;
607 
609  private: std::list<msgs::Factory> factoryMsgs;
610 
612  private: std::list<msgs::Model> modelMsgs;
613 
615  private: bool needsReset;
616 
618  private: bool resetAll;
619 
621  private: bool resetTimeOnly;
622 
624  private: bool resetModelOnly;
625 
627  private: bool initialized;
628 
630  private: bool loaded;
631 
633  private: bool enablePhysicsEngine;
634 
636  private: RayShapePtr testRay;
637 
639  private: bool pluginsLoaded;
640 
642  private: common::Time sleepOffset;
643 
645  private: common::Time prevProcessMsgsTime;
646 
648  private: common::Time processMsgsPeriod;
649 
651  private: std::deque<WorldState> states[2];
652 
654  private: int currentStateBuffer;
655 
656  private: WorldState prevStates[2];
657  private: int stateToggle;
658 
659  private: sdf::ElementPtr logPlayStateSDF;
660  private: WorldState logPlayState;
661 
664  private: sdf::SDFPtr factorySDF;
665 
667  private: std::set<ModelPtr> publishModelPoses;
668 
670  private: common::UpdateInfo updateInfo;
671 
673  private: uint64_t iterations;
674 
676  private: uint64_t stopIterations;
677 
679  private: boost::condition_variable logCondition;
680 
683  private: boost::condition_variable logContinueCondition;
684 
686  private: uint64_t logPrevIteration;
687 
689  private: common::Time logRealTime;
690 
692  private: boost::mutex logMutex;
693 
695  private: boost::mutex logBufferMutex;
696 
698  private: boost::mutex entityDeleteMutex;
699 
701  private: boost::thread *logThread;
702 
704  private: Model_V models;
705 
708  private: boost::mutex factoryDeleteMutex;
709  };
711  }
712 }
713 #endif
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
void EnablePhysicsEngine(bool _enable)
enable/disable physics engine during World::Update.
Definition: World.hh:283
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:48
Forward declarations for transport.
Information for use in an update event.
Definition: UpdateInfo.hh:30
default namespace for gazebo
bool GetEnablePhysicsEngine()
check if physics engine is enabled/disabled.
Definition: World.hh:278
boost::shared_ptr< PhysicsEngine > PhysicsEnginePtr
Definition: PhysicsTypes.hh:106
The world provides access to all other object within a simulated environment.
Definition: World.hh:59
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:74
std::vector< ConnectionPtr > Connection_V
Definition: CommonTypes.hh:148
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:52
EntityType
Unique identifiers for all entity types.
Definition: Base.hh:78
boost::shared_ptr< Actor > ActorPtr
Definition: PhysicsTypes.hh:86
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
GAZEBO_VISIBLE void stop()
std::vector< ModelPtr > Model_V
Definition: PhysicsTypes.hh:166
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:44
Store state information of a physics::World object.
Definition: WorldState.hh:46
boost::mutex * GetSetWorldPoseMutex() const
Get the set world pose mutex.
Definition: World.hh:273
boost::shared_ptr< SphericalCoordinates > SphericalCoordinatesPtr
Definition: CommonTypes.hh:135
Base type.
Definition: Base.hh:80
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
std::list< Entity * > dirtyPoses
when physics engine makes an update and changes a link pose, this flag is set to trigger Entity::SetW...
Definition: World.hh:603
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43
boost::shared_ptr< RayShape > RayShapePtr
Definition: PhysicsTypes.hh:114
boost::shared_ptr< Road > RoadPtr
Definition: PhysicsTypes.hh:130