GazeboPluginLoader.cpp
Go to the documentation of this file.
00001 #include <gazebo_world_plugin_loader/GazeboPluginLoader.h>
00002 
00003 #include <gazebo/physics/World.hh>
00004 #include <gazebo/physics/PhysicsIface.hh>
00005 
00006 using gazebo::GazeboPluginLoader;
00007 
00008 GZ_REGISTER_SYSTEM_PLUGIN(GazeboPluginLoader)
00009 
00010 GazeboPluginLoader::GazeboPluginLoader() : 
00011     SystemPlugin()
00012 {
00013     update_connection = event::Events::ConnectWorldCreated(boost::bind(&GazeboPluginLoader::onWorldCreate, this));
00014 }
00015 
00016 void GazeboPluginLoader::Load(int argc, char ** argv){
00017 }
00018 
00019 void GazeboPluginLoader::onWorldCreate(){
00020     ROS_INFO("On-World-Create: Reading list of Gazebo world plugins to be loaded from parameters...");
00021 
00022     ros::NodeHandle node("/gazebo_state_plugins");
00023 
00024     ROS_INFO_STREAM("Reading parameters from namespace "<<node.getNamespace());
00025 
00026     std::string world_name;
00027     node.getParam("world_name", world_name);
00028     ROS_INFO_STREAM("Loading plugins for world '"<<world_name<<"'");
00029 
00030     physics::WorldPtr world = gazebo::physics::get_world(world_name);
00031     if (!world)
00032     {
00033         ROS_ERROR("Could not obtain pointer to world from system plugin, so won't be able to load plugins");
00034         return;
00035     }
00036 
00037     XmlRpc::XmlRpcValue world_plugins;
00038     node.getParam("world_plugins", world_plugins);
00039     if (world_plugins.getType() != XmlRpc::XmlRpcValue::TypeArray)
00040     {
00041       ROS_ERROR("Parameter world_plugins should be specified as an array. Gazebo world plugins won't be loaded.");
00042       return;
00043     }
00044 
00045     /* get the list of names */
00046     for (int i = 0 ; i < world_plugins.size() ; ++i)
00047     {
00048       if (!world_plugins[i].hasMember("name") || !world_plugins[i].hasMember("file"))
00049       {
00050             ROS_ERROR("World plugin parameter specification should have 'name' and 'file'. Gazebo world plugins won't be loaded.");
00051             continue;
00052       }
00053       std::string name=world_plugins[i]["name"];
00054       std::string file=world_plugins[i]["file"];
00055       sdf::ElementPtr _sdf;  // will be initialized to NULL
00056       world->LoadPlugin(file, name, _sdf);
00057     }
00058 
00059     ROS_INFO("Eligible plugins loaded.");
00060 }


gazebo_world_plugin_loader
Author(s): Jennifer Buehler
autogenerated on Tue May 7 2019 03:29:33