17 #ifndef _PHYSICSIFACE_HH_ 18 #define _PHYSICSIFACE_HH_ 62 bool has_world(
const std::string &_name =
"");
122 void run_worlds(
unsigned int _iterations = 0);
138 void remove_worlds();
143 bool worlds_running();
148 uint32_t getUniqueId();
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:90
WorldPtr create_world(const std::string &_name="")
Create a world given a name.
bool load()
Setup gazebo::SystemPlugin's and call gazebo::transport::init.
void run_world(WorldPtr _world, unsigned int _iterations=0)
Run world by calling World::Run() given a pointer to it.
Forward declarations for the common classes.
Definition: Animation.hh:26
std::function< void(const std::string &, const msgs::PosesStamped &)> UpdateScenePosesFunc
Function signature for API that updates scene poses.
Definition: PhysicsTypes.hh:252
void init_worlds() GAZEBO_DEPRECATED(11.0)
initialize multiple worlds stored in static variable gazebo::g_worlds
bool has_world(const std::string &_name="")
checks if the world with this name exists.
void stop_world(WorldPtr _world)
Stop world by calling World::Stop() given a pointer to it.
void init_world(WorldPtr _world) GAZEBO_DEPRECATED(11.0)
Init world given a pointer to it.
default namespace for gazebo
void pause_world(WorldPtr _world, bool _pause)
Pause world by calling World::SetPaused.
void pause_worlds(bool pause)
pause multiple worlds stored in static variable gazebo::g_worlds
void run_worlds(unsigned int _iterations=0)
Run multiple worlds stored in static variable gazebo::g_worlds.
void load_worlds(sdf::ElementPtr _sdf)
load multiple worlds from single sdf::Element pointer
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:328
WorldPtr get_world(const std::string &_name="")
Returns a pointer to a world by name.
bool fini()
Finalize transport by calling gazebo::transport::fini.
void load_world(WorldPtr _world, sdf::ElementPtr _sdf)
Load world from sdf::Element pointer.