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 #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 
258  public: void StepWorld(int _steps) GAZEBO_DEPRECATED(3.0);
259 
262  public: void Step(unsigned int _steps);
263 
268  public: void LoadPlugin(const std::string &_filename,
269  const std::string &_name,
270  sdf::ElementPtr _sdf);
271 
274  public: void RemovePlugin(const std::string &_name);
275 
278  public: boost::mutex *GetSetWorldPoseMutex() const
279  {return this->setWorldPoseMutex;}
280 
283  public: bool GetEnablePhysicsEngine()
284  {return this->enablePhysicsEngine;}
285 
288  public: void EnablePhysicsEngine(bool _enable)
289  {this->enablePhysicsEngine = _enable;}
290 
292  public: void UpdateStateSDF();
293 
296  public: bool IsLoaded() const;
297 
300  public: void ClearModels();
301 
306  public: void PublishModelPose(physics::ModelPtr _model);
307 
310  public: uint32_t GetIterations() const;
311 
314  public: msgs::Scene GetSceneMsg() const;
315 
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 OnRequest(ConstRequestPtr &_msg);
380 
383  private: void SetSelectedEntityCB(const std::string &_name);
384 
389  private: void BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity);
390 
393  private: void JointLog(ConstJointPtr &_msg);
394 
397  private: void OnFactoryMsg(ConstFactoryPtr &_data);
398 
401  private: void OnModelMsg(ConstModelPtr &_msg);
402 
404  private: void ModelUpdateTBB();
405 
407  private: void ModelUpdateSingleLoop();
408 
411  private: void LoadPlugin(sdf::ElementPtr _sdf);
412 
416  private: void FillModelMsg(msgs::Model &_msg, ModelPtr _model);
417 
420  private: void ProcessEntityMsgs();
421 
424  private: void ProcessRequestMsgs();
425 
428  private: void ProcessFactoryMsgs();
429 
433  private: void RemoveModel(const std::string &_name);
434 
437  private: void ProcessModelMsgs();
438 
440  private: bool OnLog(std::ostringstream &_stream);
441 
443  private: void ProcessMessages();
444 
446  private: void PublishWorldStats();
447 
449  private: void LogWorker();
450 
453  private: void OnLightMsg(ConstLightPtr &_msg);
454 
456  private: common::Time prevStepWallTime;
457 
459  private: PhysicsEnginePtr physicsEngine;
460 
462  private: common::SphericalCoordinatesPtr sphericalCoordinates;
463 
465  private: BasePtr rootElement;
466 
468  private: boost::thread *thread;
469 
471  private: bool stop;
472 
474  private: EntityPtr selectedEntity;
475 
477  private: std::string name;
478 
480  private: common::Time simTime;
481 
483  private: common::Time pauseTime;
484 
486  private: common::Time startTime;
487 
489  private: bool pause;
490 
492  private: int stepInc;
493 
495  private: event::Connection_V connections;
496 
498  private: transport::NodePtr node;
499 
501  private: transport::PublisherPtr selectionPub;
502 
504  private: transport::PublisherPtr statPub;
505 
507  private: transport::PublisherPtr diagPub;
508 
510  private: transport::PublisherPtr responsePub;
511 
513  private: transport::PublisherPtr modelPub;
514 
516  private: transport::PublisherPtr guiPub;
517 
519  private: transport::PublisherPtr lightPub;
520 
522  private: transport::PublisherPtr posePub;
523 
525  private: transport::PublisherPtr poseLocalPub;
526 
528  private: transport::SubscriberPtr controlSub;
529 
531  private: transport::SubscriberPtr factorySub;
532 
534  private: transport::SubscriberPtr jointSub;
535 
537  private: transport::SubscriberPtr lightSub;
538 
540  private: transport::SubscriberPtr modelSub;
541 
543  private: transport::SubscriberPtr requestSub;
544 
546  private: msgs::WorldStatistics worldStatsMsg;
547 
549  private: msgs::Scene sceneMsg;
550 
552  private: void (World::*modelUpdateFunc)();
553 
555  private: common::Time prevStatTime;
556 
558  private: common::Time pauseStartTime;
559 
561  private: common::Time realTimeOffset;
562 
564  private: boost::recursive_mutex *receiveMutex;
565 
567  private: boost::mutex *loadModelMutex;
568 
573  private: boost::mutex *setWorldPoseMutex;
574 
581  private: boost::recursive_mutex *worldUpdateMutex;
582 
584  private: sdf::ElementPtr sdf;
585 
587  private: std::vector<WorldPluginPtr> plugins;
588 
590  private: std::list<std::string> deleteEntity;
591 
595  public: std::list<Entity*> dirtyPoses;
596 
598  private: std::list<msgs::Request> requestMsgs;
599 
601  private: std::list<msgs::Factory> factoryMsgs;
602 
604  private: std::list<msgs::Model> modelMsgs;
605 
607  private: bool needsReset;
608 
610  private: bool resetAll;
611 
613  private: bool resetTimeOnly;
614 
616  private: bool resetModelOnly;
617 
619  private: bool initialized;
620 
622  private: bool loaded;
623 
625  private: bool enablePhysicsEngine;
626 
628  private: RayShapePtr testRay;
629 
631  private: bool pluginsLoaded;
632 
634  private: common::Time sleepOffset;
635 
637  private: common::Time prevProcessMsgsTime;
638 
640  private: common::Time processMsgsPeriod;
641 
643  private: std::deque<WorldState> states[2];
644 
646  private: int currentStateBuffer;
647 
648  private: WorldState prevStates[2];
649  private: int stateToggle;
650 
651  private: sdf::ElementPtr logPlayStateSDF;
652  private: WorldState logPlayState;
653 
656  private: sdf::SDFPtr factorySDF;
657 
659  private: std::set<ModelPtr> publishModelPoses;
660 
662  private: common::UpdateInfo updateInfo;
663 
665  private: uint64_t iterations;
666 
668  private: uint64_t stopIterations;
669 
671  private: boost::condition_variable logCondition;
672 
675  private: boost::condition_variable logContinueCondition;
676 
678  private: uint64_t logPrevIteration;
679 
681  private: common::Time logRealTime;
682 
684  private: boost::mutex logMutex;
685 
687  private: boost::mutex logBufferMutex;
688 
690  private: boost::mutex entityDeleteMutex;
691 
693  private: boost::thread *logThread;
694 
696  private: Model_V models;
697 
703  public: void RunBlocking(unsigned int _iterations = 0);
704  };
706  }
707 }
708 #endif