package.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #include "ros/package.h"
00029 #include "rospack/rospack.h"
00030 
00031 #include <cstdio>
00032 #include <iostream>
00033 
00034 #include <boost/algorithm/string/split.hpp>
00035 #include <boost/algorithm/string/join.hpp>
00036 #include <boost/algorithm/string/classification.hpp>
00037 #include <boost/thread/mutex.hpp>
00038 
00039 namespace ros
00040 {
00041 namespace package
00042 {
00043 
00044 // Mutex used to lock calls into librospack, which is not thread-safe.
00045 static boost::mutex librospack_mutex;
00046 
00047 std::string command(const std::string& _cmd)
00048 {
00049   boost::mutex::scoped_lock lock(librospack_mutex);
00050   // static allows caching of results in between calls (in same process)
00051   static rospack::ROSPack rp;
00052   int ret;
00053   try
00054   {
00055     ret = rp.run(_cmd);
00056     if(ret == 0)
00057       return rp.getOutput();
00058     else {
00059       if ( !rp.is_quiet() )
00060         std::cerr << "ROSPack::run returned non-zero." << std::endl;
00061     }
00062   }
00063   catch(std::runtime_error &e)
00064   {
00065     if ( !rp.is_quiet() )
00066       std::cerr << "[rospack] " << e.what() << std::endl;
00067   }
00068   return std::string("");
00069 }
00070 
00071 void command(const std::string& cmd, V_string& output)
00072 {
00073   std::string out_string = command(cmd);
00074   V_string full_list;
00075   boost::split(full_list, out_string, boost::is_any_of("\r\n"));
00076 
00077   // strip empties
00078   V_string::iterator it = full_list.begin();
00079   V_string::iterator end = full_list.end();
00080   for (; it != end; ++it)
00081   {
00082     if (!it->empty())
00083     {
00084       output.push_back(*it);
00085     }
00086   }
00087 }
00088 
00089 std::string getPath(const std::string& package_name)
00090 {
00091   std::string path = command("find " + package_name);
00092 
00093   // scrape any newlines out of it
00094   for (size_t newline = path.find('\n'); newline != std::string::npos;
00095               newline = path.find('\n'))
00096   {
00097     path.erase(newline, 1);
00098   }
00099 
00100   return path;
00101 }
00102 
00103 bool getAll(V_string& packages)
00104 {
00105   command("list-names", packages);
00106 
00107   return true;
00108 }
00109 
00110 static void getPlugins(const std::string& package, const std::string& attribute, V_string& packages, V_string& plugins, bool force_recrawl)
00111 {
00112   if (force_recrawl)
00113   {
00114     command("profile");
00115   }
00116 
00117   V_string lines;
00118   command("plugins --attrib=" + attribute + " " + package, lines);
00119 
00120   V_string::iterator it = lines.begin();
00121   V_string::iterator end = lines.end();
00122   for (; it != end; ++it)
00123   {
00124     V_string tokens;
00125     boost::split(tokens, *it, boost::is_any_of(" "));
00126 
00127     if (tokens.size() >= 2)
00128     {
00129       std::string package = tokens[0];
00130       std::string rest = boost::join(V_string(tokens.begin() + 1, tokens.end()), " ");
00131       packages.push_back(package);
00132       plugins.push_back(rest);
00133     }
00134   }
00135 }
00136 
00137 void getPlugins(
00138   const std::string& name,
00139   const std::string& attribute,
00140   std::vector<std::pair<std::string, std::string> >& exports,
00141   bool force_recrawl
00142 )
00143 {
00144   V_string packages, plugins;
00145   getPlugins(name, attribute, packages, plugins, force_recrawl);
00146   // works on the assumption the previous call always return equal length package/plugin lists
00147   for (std::size_t i = 0; i < packages.size(); ++i ) {
00148     exports.push_back(std::pair<std::string, std::string>(packages[i], plugins[i]));
00149   }
00150 }
00151 
00152 void getPlugins(const std::string& package, const std::string& attribute, V_string& plugins, bool force_recrawl)
00153 {
00154   V_string packages;
00155   getPlugins(package, attribute, packages, plugins, force_recrawl);
00156 }
00157 
00158 void getPlugins(const std::string& package, const std::string& attribute, M_string& plugins, bool force_recrawl)
00159 {
00160   V_string packages, plugins_v;
00161   getPlugins(package, attribute, packages, plugins_v, force_recrawl);
00162   for (std::size_t i = 0 ; i < packages.size() ; ++i)
00163     plugins[packages[i]] = plugins_v[i];
00164 }
00165 
00166 } // namespace package
00167 } // namespace ros


roslib
Author(s): Ken Conley , Morgan Quigley , Josh Faust
autogenerated on Thu Mar 9 2017 05:00:42