gazebo_ros_paths_plugin.cpp
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 
00022 /* Desc: External interfaces for Gazebo
00023  * Author: John Hsu adapted original gazebo main.cc by Nate Koenig
00024  * Date: 25 Apr 2010
00025  * SVN: $Id: main.cc 8598 2010-03-22 21:59:24Z hsujohnhsu $
00026  */
00027 
00028 #include <boost/shared_ptr.hpp>
00029 #include <boost/algorithm/string.hpp>
00030 
00031 #include <common/SystemPaths.hh>
00032 #include <common/Plugin.hh>
00033 
00034 #include <ros/ros.h>
00035 #include <ros/package.h>
00036 
00037 #include <map>
00038 
00039 namespace gazebo
00040 {
00041 
00042   typedef std::vector<std::string> V_string;
00043   typedef std::map<std::string, std::string> M_string;
00044 
00045   class GazeboRosPathsPlugin : public SystemPlugin
00046   {
00047     public:
00048     GazeboRosPathsPlugin()
00049     {
00050       this->LoadPaths();
00051     }
00052 
00053     ~GazeboRosPathsPlugin()
00054     {
00055     };
00056 
00057     void Init()
00058     {
00059     }
00060 
00061     void Load(int argc, char** argv)
00062     {
00063     }
00064 
00065     /* copying ros::package::command() and ros::package::getPlugins() in here due to */
00066     /* a bug with compiler flag -Bsymbolic-functions                                 */
00067     /* see ticket https://code.ros.org/trac/ros/ticket/2977                          */
00068     /* this flag needs to be removed from new catkin debbuild before we can resume   */
00069     /* usage or ros::package::getPlugins() library from roslib (libroslib.so).       */
00070     void rosPackageCommandDebug(const std::string& cmd, V_string& output)
00071     {
00072       std::string out_string = ros::package::command(cmd);
00073       V_string full_list;
00074       boost::split(full_list, out_string, boost::is_any_of("\r\n"));
00075 
00076       // strip empties
00077       V_string::iterator it = full_list.begin();
00078       V_string::iterator end = full_list.end();
00079       for (; it != end; ++it)
00080       {
00081         if (!it->empty())
00082         {
00083           output.push_back(*it);
00084         }
00085       }
00086     }
00087     /* copying ros::package::command() and ros::package::getPlugins() in here due to */
00088     /* a bug with compiler flag -Bsymbolic-functions                                 */
00089     /* see ticket https://code.ros.org/trac/ros/ticket/2977                          */
00090     /* this flag needs to be removed from new catkin debbuild before we can resume   */
00091     /* usage or ros::package::getPlugins() library from roslib (libroslib.so).       */
00092     void rosPackageGetPluginsDebug(const std::string& package, const std::string& attribute, V_string& plugins)
00093     {
00094       M_string plugins_map;
00095       rosPackageGetPluginsDebug(package, attribute, plugins_map);
00096       M_string::iterator it = plugins_map.begin();
00097       M_string::iterator end = plugins_map.end();
00098       for (; it != end; ++it)
00099       {
00100         plugins.push_back(it->second);
00101       }
00102     }
00103     /* copying ros::package::command() and ros::package::getPlugins() in here due to */
00104     /* a bug with compiler flag -Bsymbolic-functions                                 */
00105     /* see ticket https://code.ros.org/trac/ros/ticket/2977                          */
00106     /* this flag needs to be removed from new catkin debbuild before we can resume   */
00107     /* usage or ros::package::getPlugins() library from roslib (libroslib.so).       */
00108     void rosPackageGetPluginsDebug(const std::string& package, const std::string& attribute, M_string& plugins)
00109     {
00110       V_string lines;
00111       rosPackageCommandDebug("plugins --attrib=" + attribute + " " + package, lines);
00112 
00113       V_string::iterator it = lines.begin();
00114       V_string::iterator end = lines.end();
00115       for (; it != end; ++it)
00116       {
00117         V_string tokens;
00118         boost::split(tokens, *it, boost::is_any_of(" "));
00119 
00120         if (tokens.size() >= 2)
00121         {
00122           std::string package = tokens[0];
00123           std::string rest = boost::join(V_string(tokens.begin() + 1, tokens.end()), " ");
00124           plugins[package] = rest;
00125         }
00126       }
00127     }
00128     void LoadPaths()
00129     {
00130 
00131       /* This is commented out because we are now using system installed OGRE,
00132          and sourcing gazebo installed setup.sh in ${CMAKE_INSTALL_PREFIX}/share/gazebo/setup.sh
00133       // setting Gazebo Path/Resources Configurations
00134       //   GAZEBO_RESOURCE_PATH, GAZEBO_PLUGIN_PATH and OGRE_RESOURCE_PATH for
00135       //   GazeboConfig::gazeboPaths, GazeboConfig::pluginPaths and GazeboConfig::ogrePaths
00136       // by adding paths to GazeboConfig based on ros::package
00137       // optional: setting environment variables according to ROS
00138       //           e.g. setenv("OGRE_RESOURCE_PATH",ogre_package_path.c_str(),1);
00139       // set ogre library paths by searching for package named ogre
00140       gazebo::common::SystemPaths::Instance()->ClearOgrePaths();
00141       gazebo::common::SystemPaths::Instance()->ogrePathsFromEnv = false;
00142       std::string ogre_package_name("ogre"); // @todo: un hardcode this???
00143       std::string ogre_package_path = ros::package::getPath(ogre_package_name)+std::string("/ogre/lib/OGRE");
00144       if (ogre_package_path.empty())
00145         ROS_DEBUG("Package[%s] does not exist, assuming user must have set OGRE_RESOURCE_PATH already.",ogre_package_name.c_str());
00146       else
00147       {
00148         ROS_DEBUG("ogre path %s",ogre_package_path.c_str());
00149         gazebo::common::SystemPaths::Instance()->AddOgrePaths(ogre_package_path);
00150       }
00151       */
00152 
00153       // set gazebo media paths by adding all packages that exports "gazebo_media_path" for gazebo
00154       //gazebo::common::SystemPaths::Instance()->ClearGazeboPaths();
00155       gazebo::common::SystemPaths::Instance()->gazeboPathsFromEnv = false;
00156       std::vector<std::string> gazebo_media_paths;
00157       rosPackageGetPluginsDebug("gazebo","gazebo_media_path",gazebo_media_paths);
00158       for (std::vector<std::string>::iterator iter=gazebo_media_paths.begin(); iter != gazebo_media_paths.end(); iter++)
00159       {
00160         ROS_DEBUG("med path %s",iter->c_str());
00161         gazebo::common::SystemPaths::Instance()->AddGazeboPaths(iter->c_str());
00162       }
00163 
00164       // set gazebo plugins paths by adding all packages that exports "plugin_path" for gazebo
00165       //gazebo::common::SystemPaths::Instance()->ClearPluginPaths();
00166       gazebo::common::SystemPaths::Instance()->pluginPathsFromEnv = false;
00167       std::vector<std::string> plugin_paths;
00168       rosPackageGetPluginsDebug("gazebo","plugin_path",plugin_paths);
00169       for (std::vector<std::string>::iterator iter=plugin_paths.begin(); iter != plugin_paths.end(); iter++)
00170       {
00171         ROS_DEBUG("plugin path %s",(*iter).c_str());
00172         gazebo::common::SystemPaths::Instance()->AddPluginPaths(iter->c_str());
00173       }
00174 
00175       // set model paths by adding all packages that exports "gazebo_model_path" for gazebo
00176       //gazebo::common::SystemPaths::Instance()->ClearModelPaths();
00177       gazebo::common::SystemPaths::Instance()->modelPathsFromEnv = false;
00178       std::vector<std::string> model_paths;
00179       rosPackageGetPluginsDebug("gazebo","gazebo_model_path",model_paths);
00180       for (std::vector<std::string>::iterator iter=model_paths.begin(); iter != model_paths.end(); iter++)
00181       {
00182         ROS_DEBUG("model path %s",(*iter).c_str());
00183         gazebo::common::SystemPaths::Instance()->AddModelPaths(iter->c_str());
00184       }
00185 
00186       // set .gazeborc path to something else, so we don't pick up default ~/.gazeborc
00187       std::string gazeborc = ros::package::getPath("gazebo")+"/.do_not_use_gazeborc";
00188       setenv("GAZEBORC",gazeborc.c_str(),1);
00189 
00190     }
00191     private:
00192 
00193   };
00194 
00195 // Register this plugin with the simulator
00196 GZ_REGISTER_SYSTEM_PLUGIN(GazeboRosPathsPlugin)
00197 
00198 }
00199 


gazebo
Author(s): Nate Koenig, Andrew Howard, with contributions from many others. See web page for a full credits llist.
autogenerated on Mon Oct 6 2014 12:15:20