pax_global_header00006660000000000000000000000064133112455470014517gustar00rootroot0000000000000052 comment=727a9b789c9be81bd70301bbdb4f31977f04e9d6 ros-pluginlib-1.12.1/000077500000000000000000000000001331124554700143675ustar00rootroot00000000000000ros-pluginlib-1.12.1/.gitignore000066400000000000000000000000401331124554700163510ustar00rootroot00000000000000build devel CMakeLists.txt.user ros-pluginlib-1.12.1/pluginlib/000077500000000000000000000000001331124554700163545ustar00rootroot00000000000000ros-pluginlib-1.12.1/pluginlib/CHANGELOG.rst000066400000000000000000000315241331124554700204020ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package pluginlib ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.1 (2018-04-27) ------------------- * [warning fix] remove deprecation warning until users are required to change code (`#115 `_) * [warning fix] move catkinFindLib implementation from anonymous namespace to getCatkinLibraryPaths (`#113 `_) * Contributors: Mikael Arguedas 1.12.0 (2018-03-14) ------------------- * [warning fix]Cherry-pick `#103 `_ to melodic-devel (`#105 `_) * [migration helper] provide a script to convert include statements to use new headers (`#104 `_) * [migration] use new class_loader headers and fix deprecation warnings (`#101 `_) * [bugfix] Continue loading classes on error (`#85 `_) (`#88 `_) * [style] Fix cpplint and lint_cmake errors (`#84 `_) * move pluginlib in its own folder (`#83 `_) * Contributors: Mikael Arguedas 1.11.0 (2017-07-27) ------------------- * Switch to Tinyxml2 (`#59 `_) * do not use popen to solve catkin_path. (`#49 `_) * switch to package format 2 (`#55 `_) * remove trailing whitespaces (`#54 `_) * Contributors: Dmitry Rozhkov, Koji Terada, Mikael Arguedas 1.10.5 (2017-03-27) ------------------- * Merge pull request `#47 `_ from ros/fix_conversion fix size_t to int conversion * fix int conversion * Contributors: Mikael Arguedas 1.10.4 (2016-09-20) ------------------- * Merge pull request `#42 `_ from delftrobotics-forks/unique-ptr Add std::unique_ptr API * Add unit test for unique_ptr API. * Simplify unit tests with ASSERT_THROW. * Add ClassLoader::createUniqueInstance. * Wrap long comment on createInstance and friend. * Throw exception if plugin.xml is broken (`#41 `_) * added test case for broken xml files with missing attributes of class tag * added checks if all needed attributes of the class tag are existing * removed comment and empty line * Contributors: Maarten de Vries, Mikael Arguedas, cwecht 1.10.3 (2016-06-22) ------------------- * Merge pull request `#40 `_ from ros/fix_warnings fix deprecated warnings in unit tests * fix deprecated warnings in unit tests * removed merge messages and redundant commits * Contributors: Mikael Arguedas 1.10.2 (2016-03-14) ------------------- * Remove Boost Software License from license tag `#35 `_ * Throw an exception if ClassLoader can't be instantiated due to an invalid package name `#34 `_ * Add ":" to split function within getName. `#33 `_ * Contributors: Esteve Fernandez, Jochen Sprickerhof, Mikael Arguedas, Mike O'Driscoll 1.10.1 (2014-12-23) ------------------- * Remove GTEST_FOUND from CMakeLists.txt * Check that GTest is installed before running tests. * Moved plugin_macro_update script to scripts directory. Made plugin_macro_update rosrunnable and removed it from global PATH `#29 `_ * Contributors: Esteve Fernandez 1.10.0 (2014-05-08 14:56) ------------------------- 1.9.25 (2014-05-08 20:37) ------------------------- * Use cmake_modules to find TinyXML `#26 `_ * Check for release libraries in debug builds `#25 `_ * update refreshDeclaredClasses to force recrawl (fix `#23 `_) * Contributors: Dirk Thomas, Esteve Fernandez 1.9.24 (2014-03-11) ------------------- * Remove invalid exception when no plugins are found `#22 `_ * Update maintainer field * Contributors: Dirk Thomas, Esteve Fernandez 1.9.23 (2013-10-04) ------------------- * expose plugin paths in ClassLoader `#21 `_ * Contributors: Dirk Thomas, Mirza Shah 1.9.22 (2013-08-21) ------------------- * Fixed use of __FILE_\_ macro in deprecation warning * Added libdl to plugin_tool link args...temporary fix * Contributors: Mirza Shah 1.9.21 (2013-07-14) ------------------- * Added file hint for deprecated warnings. `#16 `_ * check for CATKIN_ENABLE_TESTING * remove mainpage.dox * Contributors: Dane Powell, Dirk Thomas, Mirza Shah 1.9.20 (2013-04-18) ------------------- * Added another unit test for managed instance case. * Fixed a regression that broke unload call. Added a unit test for this case. * Contributors: Mirza Shah 1.9.19 (2013-03-23) ------------------- * Converted ROS_DEBUG and ROS_WARN calls to ROS_DEBUG_NAMED and ROS_WARN_NAMED calls `#13 `_ * Contributors: Dave Coleman, Mirza Shah 1.9.18 (2013-01-28) ------------------- * Support for boost filesystem v2 `#11 `_ * Added more debug information * Contributors: Mario Prats, Mirza Shah 1.9.17 (2012-12-27) ------------------- * More useful debug messages * Fixed incorrect debug message in plugin description XML parsing * Contributors: Mirza Shah 1.9.16 (2012-12-21) ------------------- * Removed old file * Annotated deprecation warning with more info * Made python script global installable * Added a script to recursively update deprecated pluginlib macro * added missing license header * modified dep type of catkin * Contributors: Aaron Blasdel, Dirk Thomas, Mirza Shah 1.9.15 (2012-12-13 17:22) ------------------------- * Updated registration macros to be easier and deprecated older ones. Also cleaned up code violating standard * Added wg copyright notice * Contributors: Mirza Shah 1.9.14 (2012-12-13 15:20) ------------------------- * lookup name (i.e. magic name) is now optional. Further cleanup...alphabetized methods, broke up some. * Contributors: Mirza Shah 1.9.13 (2012-12-11) ------------------- * Made robust to plugin package having different name from the folder it came from. ```#6 `_ * Contributors: Mirza Shah 1.9.2 (2012-10-25) ------------------ * fixed deps for downstream packages * Contributors: Dirk Thomas 1.9.1 (2012-10-24 22:02) ------------------------ * fix missing and redundant deps for downstream projects * Contributors: Dirk Thomas 1.9.0 (2012-10-24 18:31) ------------------------ * renamed test target * remove obsolete files * Fixed dependency in package.xml and minor touchups * Broke up code into further files * Catkinized pluginlib and completed integration more or less with class_loader. Heavy mods to pluginlib::ClassLoader to handle constraints of Catkin as well as delegate housekeeping to class_loader::ClassLoader * Updated to utilize newly renamed class_loader (formerly plugins) library with new file names, functions, identifiers, etc * Removed explicit dependency that should have been automatically imported from dependent package in CMakeLists.txt * Fixed unhandled exception to make all unit tests pass * Removed mention of console bridge in CMakeLists.txt, plugins now probably exports * Finished mods to utilize lower level plugins library. One test still failing, will get to that soon, but basics seem to be ok * Modding pluginlib to use new plugins library. Not done, but just doing it tosync with my laptop * Removed Poco and updated CMake and manifest files to depend on lower level plugins library * Contributors: Dirk Thomas, Mirza Shah, mirzashah 1.8.6 (2012-10-09) ------------------ * added missing boost include dirs and runtime dependency * updated cmake min version to 2.8.3 * Contributors: Dirk Thomas, Vincent Rabaud 1.8.5 (2012-10-01) ------------------ * add missing roslib dependency that happens in class_loader_imp.h * Contributors: Vincent Rabaud 1.8.4 (2012-09-30) ------------------ * updated to latest catkin * Contributors: Dirk Thomas 1.8.3 (2012-09-07) ------------------ * added tinyxml to project depends * Contributors: Dirk Thomas 1.8.2 (2012-09-06) ------------------ * updated pkg-config in manifest.xml * updated catkin variables * Contributors: Dirk Thomas 1.8.1 (2012-09-04) ------------------ * Missing LIBRARIES and DEPENDS specifiers from CMakeLists.txt, now added. * catkin-ized * updated api doc for load/create/unload methods * renamed new methods using shorter name for encouraged method * added cmake macro for hiding plugin symbols and respective rosbuild export * updated class loader according to updated REP 121 * add auto-unload for libraries using boost shared pointer * pluginlib: added a pure-virtual base class for ClassLoader called ClassLoaderBase, which is not templated. Only one function of ClassLoader is actually templated. This allows client code to not be templated where it doesn't need to be. * patch 4 for `#4887 `_ * ignore bin * accepting patch from ticket `#4887 `_ REP 116 implementation * add explicit link against tinyxml, because users of our libraries will need to link against it * link poco_lite with tinyxml * remove namespace to be compatible with tinyxml sysdep * removing back depend on common * removing rosdep.yaml, rule is in ros/rosdep.yaml * fixed tinyxml * converting to unary stack (separated from common) * applied patch from 4923, to support boost 1.46 * patch from Nick Butko osx compatability * adding unittest melonee forgot to commit * adding pluginlib tests * patch for osx linking `#4094 `_ * Fixed exception comments * Added Ubuntu platform tags to manifest * Fixing bug where the incorrect library path was passed to dlopen from pluginlib... oops. * fix in latest for `#4013 `_ to isolate boost filesystem calls into a library * patch from Wim `#3346 `_ reviewed by Eitan and I * Adding getName and isClassAvailable function calls to the class loader * inlining to avoid multiple definitions * macro deprecation * adding warning about deprecated macro PLUGINLIB_REGISTER_CLASS * pluginlib now takes pkg/type arguments, new macro PLUGINLIB_DECLARE_CLASS * pluginlib now robust to malformed manifests * Adding more descriptive error messages when libaries fail to load * Remove use of deprecated rosbuild macros * doc review completed http://www.ros.org/wiki/pluginlib/Reviews/2009-10-06_Doc_Review * fixing documentation link * fixing `#2894 `_ * Removing ROS_ERRORS in favor of adding information to the exceptions thrown * migration part 1 * Contributors: Dave Hershberger, Dirk Thomas, Ken Conley, Mirza Shah, Tully Foote, eitan, gerkey, kwc, mwise, rusu, tfoote, vpradeep, wheeler ros-pluginlib-1.12.1/pluginlib/CMakeLists.txt000066400000000000000000000031151331124554700211140ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(pluginlib) find_package(catkin REQUIRED COMPONENTS class_loader rosconsole roslib cmake_modules) find_package(Boost REQUIRED COMPONENTS filesystem system) find_package(TinyXML2 REQUIRED) catkin_package( INCLUDE_DIRS include CATKIN_DEPENDS class_loader rosconsole roslib DEPENDS Boost TinyXML2 ) if(CATKIN_ENABLE_TESTING) include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${TinyXML2_INCLUDE_DIRS}) add_library(test_plugins EXCLUDE_FROM_ALL SHARED test/test_plugins.cpp) catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp) if(TARGET ${PROJECT_NAME}_utest) target_link_libraries(${PROJECT_NAME}_utest ${TinyXML2_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_dependencies(${PROJECT_NAME}_utest test_plugins) endif() include(CheckCXXCompilerFlag) check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) if(COMPILER_SUPPORTS_CXX11) catkin_add_gtest(${PROJECT_NAME}_unique_ptr_test test/unique_ptr_test.cpp) if(TARGET ${PROJECT_NAME}_unique_ptr_test) target_link_libraries(${PROJECT_NAME}_unique_ptr_test ${TinyXML2_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) set_target_properties(${PROJECT_NAME}_unique_ptr_test PROPERTIES COMPILE_FLAGS -std=c++11 LINK_FLAGS -std=c++11) add_dependencies(${PROJECT_NAME}_unique_ptr_test test_plugins) endif() endif() endif() install(DIRECTORY include/pluginlib/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) install(PROGRAMS scripts/pluginlib_headers_migration.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ros-pluginlib-1.12.1/pluginlib/include/000077500000000000000000000000001331124554700177775ustar00rootroot00000000000000ros-pluginlib-1.12.1/pluginlib/include/pluginlib/000077500000000000000000000000001331124554700217645ustar00rootroot00000000000000ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_desc.h000066400000000000000000000034171331124554700242450ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_DESC_H_ #define PLUGINLIB__CLASS_DESC_H_ #include "./class_desc.hpp" #endif // PLUGINLIB__CLASS_DESC_H_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_desc.hpp000066400000000000000000000064421331124554700246060ustar00rootroot00000000000000/********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * *********************************************************************/ #ifndef PLUGINLIB__CLASS_DESC_HPP_ #define PLUGINLIB__CLASS_DESC_HPP_ #include namespace pluginlib { /// Storage for information about a given class. class ClassDesc { public: /** * \param lookup_name The lookup name of the class * \param derived_class The type of the derived class of the class * \param base_class The type of the class, corresponds to the type of the base class * \param package The package the class lives in * \param description A description for the class * \param library_name The name of the containing library for the class (not a full path!) * \param plugin_manifest_path The path to the plugin manifest file */ ClassDesc( const std::string & lookup_name, const std::string & derived_class, const std::string & base_class, const std::string & package, const std::string & description, const std::string & library_name, const std::string & plugin_manifest_path) : lookup_name_(lookup_name), derived_class_(derived_class), base_class_(base_class), package_(package), description_(description), library_name_(library_name), resolved_library_path_("UNRESOLVED"), plugin_manifest_path_(plugin_manifest_path) {} std::string lookup_name_; std::string derived_class_; std::string base_class_; std::string package_; std::string description_; std::string library_name_; std::string resolved_library_path_; // This is set by pluginlib::ClassLoader at load time. std::string plugin_manifest_path_; }; } // namespace pluginlib #endif // PLUGINLIB__CLASS_DESC_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_list_macros.h000066400000000000000000000034531331124554700256460ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LIST_MACROS_H_ #define PLUGINLIB__CLASS_LIST_MACROS_H_ #include "./class_list_macros.hpp" #endif // PLUGINLIB__CLASS_LIST_MACROS_H_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_list_macros.hpp000066400000000000000000000045361331124554700262110ustar00rootroot00000000000000/********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * *********************************************************************/ #ifndef PLUGINLIB__CLASS_LIST_MACROS_HPP_ #define PLUGINLIB__CLASS_LIST_MACROS_HPP_ #include /// Register a class with class loader to effectively export it for plugin loading later. /** * \def PLUGINLIB_EXPORT_CLASS(class_type, base_class_type) * \param class_type The real class name with namespace qualifier (e.g. Animals::Lion) * \param base_class_type The real base class type from which class_type inherits */ #define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type) \ CLASS_LOADER_REGISTER_CLASS(class_type, base_class_type) #endif // PLUGINLIB__CLASS_LIST_MACROS_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader.h000066400000000000000000000034271331124554700245760ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LOADER_H_ #define PLUGINLIB__CLASS_LOADER_H_ #include "./class_loader.hpp" #endif // PLUGINLIB__CLASS_LOADER_H_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader.hpp000066400000000000000000000332361331124554700251370ustar00rootroot00000000000000/* * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LOADER_HPP_ #define PLUGINLIB__CLASS_LOADER_HPP_ #include #include #include #include "boost/algorithm/string.hpp" #include "class_loader/multi_library_class_loader.hpp" #include "pluginlib/class_desc.hpp" #include "pluginlib/class_loader_base.hpp" #include "pluginlib/exceptions.hpp" #include "ros/console.h" #include "ros/package.h" #include "tinyxml2.h" // NOLINT // Note: pluginlib has traditionally utilized a "lookup name" for classes that does not match its // real C++ name. // This was done due to limitations of how pluginlib was implemented. // As of version 1.9, a lookup name is no longer necessary and an attempt to the merge two concepts // is underway. namespace pluginlib { #if __cplusplus >= 201103L template using UniquePtr = class_loader::ClassLoader::UniquePtr; #endif /// A class to help manage and load classes. template class ClassLoader : public ClassLoaderBase { public: typedef typename std::map::iterator ClassMapIterator; public: /** * \param package The package containing the base class * \param base_class The type of the base class for classes to be loaded * \param attrib_name The attribute to search for in manifext.xml files, defaults to "plugin" * \param plugin_xml_paths The list of paths of plugin.xml files, defaults to be crawled via * ros::package::getPlugins() * \throws pluginlib::ClassLoaderException if package manifest cannot be found */ ClassLoader( std::string package, std::string base_class, std::string attrib_name = std::string("plugin"), std::vector plugin_xml_paths = std::vector()); ~ClassLoader(); /// Create an instance of a desired class, optionally loading the associated library too. /** * \param lookup_name The name of the class to load * \param auto_load Specifies whether or not to automatically load the * library containing the class, set to true by default. * \throws pluginlib::LibraryLoadException when the library associated * with the class cannot be loaded * \throws pluginlib::CreateClassException when the class cannot be instantiated * \return An instance of the class * \deprecated use either createInstance() or createUnmanagedInstance() */ __attribute__((deprecated)) T * createClassInstance( const std::string & lookup_name, bool auto_load = true); /// Create an instance of a desired class. /** * Implicitly calls loadLibraryForClass() to increment the library counter. * * Deleting the instance and calling unloadLibraryForClass() is automatically * handled by the shared pointer. * \param lookup_name The name of the class to load * \throws pluginlib::LibraryLoadException when the library associated with * the class cannot be loaded * \throws pluginlib::CreateClassException when the class cannot be instantiated * \return An instance of the class */ boost::shared_ptr createInstance(const std::string & lookup_name); #if __cplusplus >= 201103L /// Create an instance of a desired class. /** * Implicitly calls loadLibraryForClass() to increment the library counter. * * Deleting the instance and calling unloadLibraryForClass() is automatically * handled by the unique pointer. * * If you release the wrapped pointer you must manually call the original * deleter when you want to destroy the released pointer. * * \param lookup_name The name of the class to load. * \throws pluginlib::LibraryLoadException when the library associated with * the class cannot be loaded. * \throws pluginlib::CreateClassException when the class cannot be instantiated * \return An instance of the class */ UniquePtr createUniqueInstance(const std::string & lookup_name); #endif /// Create an instance of a desired class. /** * Implicitly calls loadLibraryForClass() to increment the library counter. * * \attention The ownership is transfered to the caller, which is responsible * for deleting the instance and calling unloadLibraryForClass() * (in order to decrement the associated library counter and unloading it * if it is no more used). * \param lookup_name The name of the class to load * \throws pluginlib::LibraryLoadException when the library associated with * the class cannot be loaded * \throws pluginlib::CreateClassException when the class cannot be instantiated * \return An instance of the class */ T * createUnmanagedInstance(const std::string & lookup_name); /// Return a list of all available plugin manifest paths for this ClassLoader's base class type. /** * \return A vector of strings corresponding to the paths of all available plugin manifests */ std::vector getPluginXmlPaths(); /// Return a list of all available classes for this ClassLoader's base class type. /** * \return A vector of strings corresponding to the names of all available classes */ std::vector getDeclaredClasses(); /// Strip the package name off of a lookup name. /** * \param lookup_name The name of the plugin * \return The name of the plugin stripped of the package name */ virtual std::string getName(const std::string & lookup_name); /// Given the lookup name of a class, return the type of the associated base class. /** * \return The type of the associated base class */ virtual std::string getBaseClassType() const; /// Given the lookup name of a class, return the type of the derived class associated with it. /** * \param lookup_name The name of the class * \return The name of the associated derived class */ virtual std::string getClassType(const std::string & lookup_name); /// Given the lookup name of a class, return its description. /** * \param lookup_name The lookup name of the class * \return The description of the class */ virtual std::string getClassDescription(const std::string & lookup_name); /// Given the name of a class, return the path to its associated library. /** * \param lookup_name The name of the class * \return The path to the associated library */ virtual std::string getClassLibraryPath(const std::string & lookup_name); /// Given the name of a class, return name of the containing package. /** * \param lookup_name The name of the class * \return The name of the containing package */ virtual std::string getClassPackage(const std::string & lookup_name); /// Given the name of a class, return the path of the associated plugin manifest. /** * \param lookup_name The name of the class * \return The path of the associated plugin manifest */ virtual std::string getPluginManifestPath(const std::string & lookup_name); /// Return the libraries that are registered and can be loaded. /** * \return A vector of strings corresponding to the names of registered libraries */ virtual std::vector getRegisteredLibraries(); /// Check if the library for a given class is currently loaded. /** * \param lookup_name The lookup name of the class to query * \return True if the class is loaded, false otherwise */ bool isClassLoaded(const std::string & lookup_name); /// Check if the class associated with a plugin name is available to be loaded. /** * \param lookup_name The name of the plugin * \return true if the plugin is available, false otherwise */ virtual bool isClassAvailable(const std::string & lookup_name); /// Attempt to load the library containing a class with a given name. /** * The counter for the library uses (refcount) is also incremented. * * \param lookup_name The lookup name of the class to load * \throws pluginlib::LibraryLoadException if the library for the * class cannot be loaded */ virtual void loadLibraryForClass(const std::string & lookup_name); /// Refresh the list of all available classes for this ClassLoader's base class type. /** * \throws pluginlib::LibraryLoadException if package manifest cannot be found */ virtual void refreshDeclaredClasses(); /// Decrement the counter for the library containing a class with a given name. /** * Also try to unload the library, If the counter reaches zero. * * \param lookup_name The lookup name of the class to unload * \throws pluginlib::LibraryUnloadException if the library for the * class cannot be unloaded * \return The number of pending unloads until the library is removed from memory */ virtual int unloadLibraryForClass(const std::string & lookup_name); private: /// Return the paths to plugin.xml files. /** * \throws pluginlib::LibraryLoadException if package manifest cannot be found * \return A vector of paths */ std::vector getPluginXmlPaths( const std::string & package, const std::string & attrib_name, bool force_recrawl = false); /// Return the available classes. /** * \param plugin_xml_paths The vector of paths of plugin.xml files * \throws pluginlib::LibraryLoadException if package manifest cannot be found * \return A map of class names and the corresponding descriptions */ std::map determineAvailableClasses( const std::vector & plugin_xml_paths); /// Open a package.xml file and extract the package name (i.e. contents of tag). /** * \param package_xml_path The path to the package.xml file * \return The name of the package if successful, otherwise an empty string */ std::string extractPackageNameFromPackageXML(const std::string & package_xml_path); /// Get a list of paths to try to find a library. /** * As we transition from rosbuild to Catkin build systems, plugins can be * found in the old rosbuild place (pkg_name/lib usually) or somewhere in the * Catkin build space. */ std::vector getAllLibraryPathsToTry( const std::string & library_name, const std::string & exporting_package_name); /// Return the paths where libraries are installed according to the Catkin build system. std::vector getCatkinLibraryPaths(); /// Return an error message for an unknown class. /** * \param lookup_name The name of the class * \return The error message */ std::string getErrorStringForUnknownClass(const std::string & lookup_name); /// Get the standard path separator for the native OS (e.g. "/" on *nix, "\" on Windows). std::string getPathSeparator(); /// Given a package name, return the path where rosbuild thinks plugins are installed. std::string getROSBuildLibraryPath(const std::string & exporting_package_name); /// Get the package name from a path to a plugin XML file. std::string getPackageFromPluginXMLFilePath(const std::string & path); /// Join two filesystem paths together utilzing appropriate path separator. std::string joinPaths(const std::string & path1, const std::string & path2); /// Parse a plugin XML file. /** * Also insert the appropriate ClassDesc entries into the passes * classes_available map. */ void processSingleXMLPluginFile( const std::string & xml_file, std::map & class_available); /// Strip all but the filename from an explicit file path. /** * \param path The path to strip * \return The basename of the path */ std::string stripAllButFileFromPath(const std::string & path); /// Helper function for unloading a shared library. /** * \param library_path The exact path to the library to unload * \return The number of pending unloads until the library is removed from memory */ int unloadClassLibraryInternal(const std::string & library_path); private: std::vector plugin_xml_paths_; // Map from library to class's descriptions described in XML. std::map classes_available_; std::string package_; std::string base_class_; std::string attrib_name_; class_loader::MultiLibraryClassLoader lowlevel_class_loader_; // The underlying classloader }; } // namespace pluginlib // Note: The implementation of the methods is in a separate file for clarity. #include "./class_loader_imp.hpp" #endif // PLUGINLIB__CLASS_LOADER_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader_base.h000066400000000000000000000034531331124554700255670ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LOADER_BASE_H_ #define PLUGINLIB__CLASS_LOADER_BASE_H_ #include "./class_loader_base.hpp" #endif // PLUGINLIB__CLASS_LOADER_BASE_H_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader_base.hpp000066400000000000000000000140011331124554700261160ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LOADER_BASE_HPP_ #define PLUGINLIB__CLASS_LOADER_BASE_HPP_ #include #include namespace pluginlib { /// Pure virtual base class of pluginlib::ClassLoader which is not templated. /** * This allows the writing of non-templated manager code * which can call all the administrative functions of ClassLoaders - * everything except createClassInstance(), createInstance() * and createUnmanagedInstance(). */ class ClassLoaderBase { public: /// Empty virtual destructor. virtual ~ClassLoaderBase() {} /// Return a list of all available plugin manifest paths. /** * \return A vector of strings corresponding to the paths of all available plugin manifests */ virtual std::vector getPluginXmlPaths() = 0; /// Return a list of all available classes for this ClassLoader's base class type. /** * \return A vector of strings corresponding to the names of all available classes */ virtual std::vector getDeclaredClasses() = 0; /// Refresh the list of all available classes for this ClassLoader's base class type. /** * \throws pluginlib::LibraryLoadException if package manifest cannot be found */ virtual void refreshDeclaredClasses() = 0; /// Strip the package name off of a lookup name. /** * \param lookup_name The name of the plugin * \return The name of the plugin stripped of the package name */ virtual std::string getName(const std::string & lookup_name) = 0; /// Check if the class associated with a plugin name is available to be loaded. /** * \param lookup_name The name of the plugin * \return True if the plugin is available, false otherwise */ virtual bool isClassAvailable(const std::string & lookup_name) = 0; /// Given the lookup name of a class, return the type of the derived class associated with it. /** * \param lookup_name The name of the class * \return The name of the associated derived class */ virtual std::string getClassType(const std::string & lookup_name) = 0; /// Given the lookup name of a class, return its description. /** * \param lookup_name The lookup name of the class * \return The description of the class */ virtual std::string getClassDescription(const std::string & lookup_name) = 0; /// Given the lookup name of a class, return the type of the associated base class. /** * \return The type of the associated base class */ virtual std::string getBaseClassType() const = 0; /// Given the name of a class, return name of the containing package. /** * \param lookup_name The name of the class * \return The name of the containing package */ virtual std::string getClassPackage(const std::string & lookup_name) = 0; /// Given the name of a class, return the path of the associated plugin manifest. /** * \param lookup_name The name of the class * \return The path of the associated plugin manifest */ virtual std::string getPluginManifestPath(const std::string & lookup_name) = 0; /// Check if a given class is currently loaded. /** * \param lookup_name The lookup name of the class to query * \return True if the class is loaded, false otherwise */ virtual bool isClassLoaded(const std::string & lookup_name) = 0; /// Attempt to load a class with a given name. /** * \param lookup_name The lookup name of the class to load * \throws pluginlib::LibraryLoadException if the library for the * class cannot be loaded */ virtual void loadLibraryForClass(const std::string & lookup_name) = 0; /// Attempt to unload a class with a given name. /** * \param lookup_name The lookup name of the class to unload * \throws pluginlib::LibraryUnloadException if the library for the class * cannot be unloaded * \return The number of pending unloads until the library is removed from memory */ virtual int unloadLibraryForClass(const std::string & lookup_name) = 0; /// Return the libraries that are registered and can be loaded. /** * \return A vector of strings corresponding to the names of registered libraries */ virtual std::vector getRegisteredLibraries() = 0; /// Given the name of a class, return the path to its associated library. /** * \param lookup_name The name of the class * \return The path to the associated library */ virtual std::string getClassLibraryPath(const std::string & lookup_name) = 0; }; } // namespace pluginlib #endif // PLUGINLIB__CLASS_LOADER_BASE_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader_imp.h000066400000000000000000000037431331124554700254440ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__CLASS_LOADER_IMP_H_ #define PLUGINLIB__CLASS_LOADER_IMP_H_ // *INDENT-OFF* (prevent uncrustify from adding indention below) #error Header is deprecated, \ but this file should never be included directly, include instead. #endif // PLUGINLIB__CLASS_LOADER_IMP_H_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/class_loader_imp.hpp000066400000000000000000000731761331124554700260130ustar00rootroot00000000000000/********************************************************************* * * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * *********************************************************************/ #ifndef PLUGINLIB__CLASS_LOADER_IMP_HPP_ #define PLUGINLIB__CLASS_LOADER_IMP_HPP_ #include #include #include #include #include #include #include #include #include #include "boost/algorithm/string.hpp" #include "boost/bind.hpp" #include "boost/filesystem.hpp" #include "boost/foreach.hpp" #include "class_loader/class_loader.hpp" #include "ros/package.h" #include "./class_loader.hpp" #ifdef _WIN32 const std::string os_pathsep(";"); // NOLINT #else const std::string os_pathsep(":"); // NOLINT #endif namespace pluginlib { template ClassLoader::ClassLoader( std::string package, std::string base_class, std::string attrib_name, std::vector plugin_xml_paths) : plugin_xml_paths_(plugin_xml_paths), package_(package), base_class_(base_class), attrib_name_(attrib_name), // NOTE: The parameter to the class loader enables/disables on-demand class // loading/unloading. // Leaving it off for now... libraries will be loaded immediately and won't // be unloaded until class loader is destroyed or force unload. lowlevel_class_loader_(false) /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Creating ClassLoader, base = %s, address = %p", base_class.c_str(), this); if (ros::package::getPath(package_).empty()) { throw pluginlib::ClassLoaderException("Unable to find package: " + package_); } if (0 == plugin_xml_paths_.size()) { plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_); } classes_available_ = determineAvailableClasses(plugin_xml_paths_); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Finished constructring ClassLoader, base = %s, address = %p", base_class.c_str(), this); } template ClassLoader::~ClassLoader() /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Destroying ClassLoader, base = %s, address = %p", getBaseClassType().c_str(), this); } template T * ClassLoader::createClassInstance(const std::string & lookup_name, bool auto_load) /***************************************************************************/ { // Note: This method is deprecated ROS_DEBUG_NAMED("pluginlib.ClassLoader", "In deprecated call createClassInstance(), lookup_name = %s, auto_load = %i.", (lookup_name.c_str()), auto_load); if (auto_load && !isClassLoaded(lookup_name)) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Autoloading class library before attempting to create instance."); loadLibraryForClass(lookup_name); } try { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create instance through low-level MultiLibraryClassLoader..."); T * obj = lowlevel_class_loader_.createUnmanagedInstance(getClassType(lookup_name)); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance created with object pointer = %p", obj); return obj; } catch (const class_loader::CreateClassException & ex) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "CreateClassException about to be raised for class %s", lookup_name.c_str()); throw pluginlib::CreateClassException(ex.what()); } } template boost::shared_ptr ClassLoader::createInstance(const std::string & lookup_name) /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create managed instance for class %s.", lookup_name.c_str()); if (!isClassLoaded(lookup_name)) { loadLibraryForClass(lookup_name); } try { std::string class_type = getClassType(lookup_name); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", lookup_name.c_str(), class_type.c_str()); boost::shared_ptr obj = lowlevel_class_loader_.createInstance(class_type); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "boost::shared_ptr to object of real type %s created.", class_type.c_str()); return obj; } catch (const class_loader::CreateClassException & ex) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exception raised by low-level multi-library class loader when attempting " "to create instance of class %s.", lookup_name.c_str()); throw pluginlib::CreateClassException(ex.what()); } } #if __cplusplus >= 201103L template UniquePtr ClassLoader::createUniqueInstance(const std::string & lookup_name) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create managed (unique) instance for class %s.", lookup_name.c_str()); if (!isClassLoaded(lookup_name)) { loadLibraryForClass(lookup_name); } try { std::string class_type = getClassType(lookup_name); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", lookup_name.c_str(), class_type.c_str()); UniquePtr obj = lowlevel_class_loader_.createUniqueInstance(class_type); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "std::unique_ptr to object of real type %s created.", class_type.c_str()); return obj; } catch (const class_loader::CreateClassException & ex) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exception raised by low-level multi-library class loader when attempting " "to create instance of class %s.", lookup_name.c_str()); throw pluginlib::CreateClassException(ex.what()); } } #endif template T * ClassLoader::createUnmanagedInstance(const std::string & lookup_name) /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create UNMANAGED instance for class %s.", lookup_name.c_str()); if (!isClassLoaded(lookup_name)) { loadLibraryForClass(lookup_name); } T * instance = 0; try { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create instance through low level multi-library class loader."); std::string class_type = getClassType(lookup_name); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", lookup_name.c_str(), class_type.c_str()); instance = lowlevel_class_loader_.createUnmanagedInstance(class_type); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance of type %s created.", class_type.c_str()); } catch (const class_loader::CreateClassException & ex) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exception raised by low-level multi-library class loader when attempting " "to create UNMANAGED instance of class %s.", lookup_name.c_str()); throw pluginlib::CreateClassException(ex.what()); } return instance; } template std::vector ClassLoader::getPluginXmlPaths( const std::string & package, const std::string & attrib_name, bool force_recrawl) /***************************************************************************/ { // Pull possible files from manifests of packages which depend on this package and export class std::vector paths; ros::package::getPlugins(package, attrib_name, paths, force_recrawl); return paths; } template std::map ClassLoader::determineAvailableClasses( const std::vector & plugin_xml_paths) /***************************************************************************/ { // mas - This method requires major refactoring... // not only is it really long and confusing but a lot of the comments do not // seem to be correct. // With time I keep correcting small things, but a good rewrite is needed. ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Entering determineAvailableClasses()..."); std::map classes_available; // Walk the list of all plugin XML files (variable "paths") that are exported by the build system for (std::vector::const_iterator it = plugin_xml_paths.begin(); it != plugin_xml_paths.end(); ++it) { try { processSingleXMLPluginFile(*it, classes_available); } catch (const pluginlib::InvalidXMLException & e) { ROS_ERROR_NAMED("pluginlib.ClassLoader", "Skipped loading plugin with error: %s.", e.what()); } } ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exiting determineAvailableClasses()..."); return classes_available; } template std::string ClassLoader::extractPackageNameFromPackageXML(const std::string & package_xml_path) /***************************************************************************/ { tinyxml2::XMLDocument document; document.LoadFile(package_xml_path.c_str()); tinyxml2::XMLElement * doc_root_node = document.FirstChildElement("package"); if (NULL == doc_root_node) { ROS_ERROR_NAMED("pluginlib.ClassLoader", "Could not find a root element for package manifest at %s.", package_xml_path.c_str()); return ""; } assert(document.RootElement() == doc_root_node); tinyxml2::XMLElement * package_name_node = doc_root_node->FirstChildElement("name"); if (NULL == package_name_node) { ROS_ERROR_NAMED("pluginlib.ClassLoader", "package.xml at %s does not have a tag! Cannot determine package " "which exports plugin.", package_xml_path.c_str()); return ""; } return package_name_node->GetText(); } template std::vector ClassLoader::getCatkinLibraryPaths() /***************************************************************************/ { std::vector lib_paths; const char * env = std::getenv("CMAKE_PREFIX_PATH"); if (env) { std::string env_catkin_prefix_paths(env); std::vector catkin_prefix_paths; boost::split(catkin_prefix_paths, env_catkin_prefix_paths, boost::is_any_of(os_pathsep)); BOOST_FOREACH(std::string catkin_prefix_path, catkin_prefix_paths) { boost::filesystem::path path(catkin_prefix_path); boost::filesystem::path lib("lib"); lib_paths.push_back((path / lib).string()); } } return lib_paths; } template std::vector ClassLoader::getAllLibraryPathsToTry( const std::string & library_name, const std::string & exporting_package_name) /***************************************************************************/ { // Catkin-rosbuild Backwards Compatability Rules - Note library_name may be prefixed with // relative path (e.g. "/lib/libFoo") // 1. Try catkin library paths (catkin_find --libs) + library_name + extension // 2. Try catkin library paths // (catkin_find -- libs) + stripAllButFileFromPath(library_name) + extension // 3. Try export_pkg/library_name + extension std::vector all_paths; std::vector all_paths_without_extension = getCatkinLibraryPaths(); all_paths_without_extension.push_back(getROSBuildLibraryPath(exporting_package_name)); bool debug_library_suffix = (0 == class_loader::systemLibrarySuffix().compare(0, 1, "d")); std::string non_debug_suffix; if (debug_library_suffix) { non_debug_suffix = class_loader::systemLibrarySuffix().substr(1); } else { non_debug_suffix = class_loader::systemLibrarySuffix(); } std::string library_name_with_extension = library_name + non_debug_suffix; std::string stripped_library_name = stripAllButFileFromPath(library_name); std::string stripped_library_name_with_extension = stripped_library_name + non_debug_suffix; const std::string path_separator = getPathSeparator(); for (unsigned int c = 0; c < all_paths_without_extension.size(); c++) { std::string current_path = all_paths_without_extension.at(c); all_paths.push_back(current_path + path_separator + library_name_with_extension); all_paths.push_back(current_path + path_separator + stripped_library_name_with_extension); // We're in debug mode, try debug libraries as well if (debug_library_suffix) { all_paths.push_back( current_path + path_separator + library_name + class_loader::systemLibrarySuffix()); all_paths.push_back( current_path + path_separator + stripped_library_name + class_loader::systemLibrarySuffix()); } } return all_paths; } template bool ClassLoader::isClassLoaded(const std::string & lookup_name) /***************************************************************************/ { return lowlevel_class_loader_.isClassAvailable(getClassType(lookup_name)); } template std::string ClassLoader::getBaseClassType() const /***************************************************************************/ { return base_class_; } template std::string ClassLoader::getClassDescription(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it != classes_available_.end()) { return it->second.description_; } return ""; } template std::string ClassLoader::getClassType(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it != classes_available_.end()) { return it->second.derived_class_; } return ""; } template std::string ClassLoader::getClassLibraryPath(const std::string & lookup_name) /***************************************************************************/ { if (classes_available_.find(lookup_name) == classes_available_.end()) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.", lookup_name.c_str()); return ""; } ClassMapIterator it = classes_available_.find(lookup_name); std::string library_name = it->second.library_name_; ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s maps to library %s in classes_available_.", lookup_name.c_str(), library_name.c_str()); std::vector paths_to_try = getAllLibraryPathsToTry(library_name, it->second.package_); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Iterating through all possible paths where %s could be located...", library_name.c_str()); for (std::vector::const_iterator it = paths_to_try.begin(); it != paths_to_try.end(); it++) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Checking path %s ", it->c_str()); if (boost::filesystem::exists(*it)) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Library %s found at explicit path %s.", library_name.c_str(), it->c_str()); return *it; } } return ""; } template std::string ClassLoader::getClassPackage(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it != classes_available_.end()) { return it->second.package_; } return ""; } template std::vector ClassLoader::getPluginXmlPaths() /***************************************************************************/ { return plugin_xml_paths_; } template std::vector ClassLoader::getDeclaredClasses() /***************************************************************************/ { std::vector lookup_names; for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); ++it) { lookup_names.push_back(it->first); } return lookup_names; } template std::string ClassLoader::getErrorStringForUnknownClass(const std::string & lookup_name) /***************************************************************************/ { std::string declared_types; std::vector types = getDeclaredClasses(); for (unsigned int i = 0; i < types.size(); i++) { declared_types = declared_types + std::string(" ") + types[i]; } return "According to the loaded plugin descriptions the class " + lookup_name + " with base class type " + base_class_ + " does not exist. Declared types are " + declared_types; } template std::string ClassLoader::getName(const std::string & lookup_name) /***************************************************************************/ { // remove the package name to get the raw plugin name std::vector split; boost::split(split, lookup_name, boost::is_any_of("/:")); return split.back(); } template std::string ClassLoader::getPackageFromPluginXMLFilePath(const std::string & plugin_xml_file_path) /***************************************************************************/ { // Note: This method takes an input a path to a plugin xml file and must determine which // package the XML file came from. This is not necessariliy the same thing as the member // variable "package_". The plugin xml file can be located anywhere in the source tree for a // package // rosbuild: // 1. Find nearest encasing manifest.xml // 2. Once found, the name of the folder containg the manifest should be the // package name we are looking for // 3. Confirm package is findable with rospack // catkin: // 1. Find nearest encasing package.xml // 2. Extract name of package from package.xml std::string package_name; boost::filesystem::path p(plugin_xml_file_path); boost::filesystem::path parent = p.parent_path(); // Figure out exactly which package the passed XML file is exported by. while (true) { if (boost::filesystem::exists(parent / "package.xml")) { std::string package_file_path = (boost::filesystem::path(parent / "package.xml")).string(); return extractPackageNameFromPackageXML(package_file_path); } else if (boost::filesystem::exists(parent / "manifest.xml")) { #if BOOST_FILESYSTEM_VERSION >= 3 std::string package = parent.filename().string(); #else std::string package = parent.filename(); #endif std::string package_path = ros::package::getPath(package); // package_path is a substr of passed plugin xml path if (0 == plugin_xml_file_path.find(package_path)) { package_name = package; break; } } // Recursive case - hop one folder up parent = parent.parent_path().string(); // Base case - reached root and cannot find what we're looking for if (parent.string().empty()) { return ""; } } return package_name; } template std::string ClassLoader::getPathSeparator() /***************************************************************************/ { #if BOOST_FILESYSTEM_VERSION >= 3 return boost::filesystem::path("/").native(); #else return boost::filesystem::path("/").external_file_string(); #endif } template std::string ClassLoader::getPluginManifestPath(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it != classes_available_.end()) { return it->second.plugin_manifest_path_; } return ""; } template std::vector ClassLoader::getRegisteredLibraries() /***************************************************************************/ { return lowlevel_class_loader_.getRegisteredLibraries(); } template std::string ClassLoader::getROSBuildLibraryPath(const std::string & exporting_package_name) /***************************************************************************/ { return ros::package::getPath(exporting_package_name); } template bool ClassLoader::isClassAvailable(const std::string & lookup_name) /***************************************************************************/ { return classes_available_.find(lookup_name) != classes_available_.end(); } template std::string ClassLoader::joinPaths(const std::string & path1, const std::string & path2) /***************************************************************************/ { boost::filesystem::path p1(path1); return (p1 / path2).string(); } template void ClassLoader::loadLibraryForClass(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it == classes_available_.end()) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.", lookup_name.c_str()); throw pluginlib::LibraryLoadException(getErrorStringForUnknownClass(lookup_name)); } std::string library_path = getClassLibraryPath(lookup_name); if ("" == library_path) { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "No path could be found to the library containing %s.", lookup_name.c_str()); std::ostringstream error_msg; error_msg << "Could not find library corresponding to plugin " << lookup_name << ". Make sure the plugin description XML file has the correct name of the " "library and that the library actually exists."; throw pluginlib::LibraryLoadException(error_msg.str()); } try { lowlevel_class_loader_.loadLibrary(library_path); it->second.resolved_library_path_ = library_path; } catch (const class_loader::LibraryLoadException & ex) { std::string error_string = "Failed to load library " + library_path + ". " "Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the " "library code, and that names are consistent between this macro and your XML. " "Error string: " + ex.what(); throw pluginlib::LibraryLoadException(error_string); } } template void ClassLoader::processSingleXMLPluginFile( const std::string & xml_file, std::map & classes_available) /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Processing xml file %s...", xml_file.c_str()); tinyxml2::XMLDocument document; document.LoadFile(xml_file.c_str()); tinyxml2::XMLElement * config = document.RootElement(); if (NULL == config) { throw pluginlib::InvalidXMLException( "XML Document '" + xml_file + "' has no Root Element. This likely means the XML is malformed or missing."); return; } if (!(strcmp(config->Value(), "library") == 0 || strcmp(config->Value(), "class_libraries") == 0)) { throw pluginlib::InvalidXMLException( "The XML document '" + xml_file + "' given to add must have either \"library\" or " "\"class_libraries\" as the root tag"); return; } // Step into the filter list if necessary if (strcmp(config->Value(), "class_libraries") == 0) { config = config->FirstChildElement("library"); } tinyxml2::XMLElement * library = config; while (library != NULL) { std::string library_path = library->Attribute("path"); if (0 == library_path.size()) { ROS_ERROR_NAMED("pluginlib.ClassLoader", "Failed to find Path Attirbute in library element in %s", xml_file.c_str()); continue; } std::string package_name = getPackageFromPluginXMLFilePath(xml_file); if ("" == package_name) { ROS_ERROR_NAMED("pluginlib.ClassLoader", "Could not find package manifest (neither package.xml or deprecated " "manifest.xml) at same directory level as the plugin XML file %s. " "Plugins will likely not be exported properly.\n)", xml_file.c_str()); } tinyxml2::XMLElement * class_element = library->FirstChildElement("class"); while (class_element) { std::string derived_class; if (class_element->Attribute("type") != NULL) { derived_class = std::string(class_element->Attribute("type")); } else { throw pluginlib::ClassLoaderException( "Class could not be loaded. Attribute 'type' in class tag is missing."); } std::string base_class_type; if (class_element->Attribute("base_class_type") != NULL) { base_class_type = std::string(class_element->Attribute("base_class_type")); } else { throw pluginlib::ClassLoaderException( "Class could not be loaded. Attribute 'base_class_type' in class tag is missing."); } std::string lookup_name; if (class_element->Attribute("name") != NULL) { lookup_name = class_element->Attribute("name"); ROS_DEBUG_NAMED("pluginlib.ClassLoader", "XML file specifies lookup name (i.e. magic name) = %s.", lookup_name.c_str()); } else { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "XML file has no lookup name (i.e. magic name) for class %s, " "assuming lookup_name == real class name.", derived_class.c_str()); lookup_name = derived_class; } // make sure that this class is of the right type before registering it if (base_class_type == base_class_) { // register class here tinyxml2::XMLElement * description = class_element->FirstChildElement("description"); std::string description_str; if (description) { description_str = description->GetText() ? description->GetText() : ""; } else { description_str = "No 'description' tag for this plugin in plugin description file."; } classes_available.insert(std::pair(lookup_name, ClassDesc(lookup_name, derived_class, base_class_type, package_name, description_str, library_path, xml_file))); } // step to next class_element class_element = class_element->NextSiblingElement("class"); } library = library->NextSiblingElement("library"); } } template void ClassLoader::refreshDeclaredClasses() /***************************************************************************/ { ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Refreshing declared classes."); // determine classes not currently loaded for removal std::list remove_classes; for (std::map::const_iterator it = classes_available_.begin(); it != classes_available_.end(); it++) { std::string resolved_library_path = it->second.resolved_library_path_; std::vector open_libs = lowlevel_class_loader_.getRegisteredLibraries(); if (std::find(open_libs.begin(), open_libs.end(), resolved_library_path) != open_libs.end()) { remove_classes.push_back(it->first); } } while (!remove_classes.empty()) { classes_available_.erase(remove_classes.front()); remove_classes.pop_front(); } // add new classes plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_, true); std::map updated_classes = determineAvailableClasses(plugin_xml_paths_); for (std::map::const_iterator it = updated_classes.begin(); it != updated_classes.end(); it++) { if (classes_available_.find(it->first) == classes_available_.end()) { classes_available_.insert(std::pair(it->first, it->second)); } } } template std::string ClassLoader::stripAllButFileFromPath(const std::string & path) /***************************************************************************/ { std::string only_file; size_t c = path.find_last_of(getPathSeparator()); if (std::string::npos == c) { return path; } else { return path.substr(c, path.size()); } } template int ClassLoader::unloadLibraryForClass(const std::string & lookup_name) /***************************************************************************/ { ClassMapIterator it = classes_available_.find(lookup_name); if (it != classes_available_.end() && it->second.resolved_library_path_ != "UNRESOLVED") { std::string library_path = it->second.resolved_library_path_; ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to unload library %s for class %s", library_path.c_str(), lookup_name.c_str()); return unloadClassLibraryInternal(library_path); } else { throw pluginlib::LibraryUnloadException(getErrorStringForUnknownClass(lookup_name)); } } template int ClassLoader::unloadClassLibraryInternal(const std::string & library_path) /***************************************************************************/ { return lowlevel_class_loader_.unloadLibrary(library_path); } } // namespace pluginlib #endif // PLUGINLIB__CLASS_LOADER_IMP_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/exceptions.hpp000066400000000000000000000067411331124554700246660ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__EXCEPTIONS_HPP_ #define PLUGINLIB__EXCEPTIONS_HPP_ #include #include namespace pluginlib { /// A base class for all pluginlib exceptions that inherits from std::runtime_exception. /** * \class PluginlibException */ class PluginlibException : public std::runtime_error { public: explicit PluginlibException(const std::string & error_desc) : std::runtime_error(error_desc) {} }; /// Thrown when pluginlib is unable to load a plugin XML file. /** * \class InvalidXMLException */ class InvalidXMLException : public PluginlibException { public: explicit InvalidXMLException(const std::string & error_desc) : PluginlibException(error_desc) {} }; /// Thrown when pluginlib is unable to load the library associated with a given plugin. /** * \class LibraryLoadException */ class LibraryLoadException : public PluginlibException { public: explicit LibraryLoadException(const std::string & error_desc) : PluginlibException(error_desc) {} }; /// Thrown when pluginlib is unable to instantiate a class loader. /** * \class ClassLoaderException */ class ClassLoaderException : public PluginlibException { public: explicit ClassLoaderException(const std::string & error_desc) : PluginlibException(error_desc) {} }; /// Thrown when pluginlib is unable to unload the library associated with a given plugin. /** * \class LibraryUnloadException */ class LibraryUnloadException : public PluginlibException { public: explicit LibraryUnloadException(const std::string & error_desc) : PluginlibException(error_desc) {} }; /// Thrown when pluginlib is unable to create the class associated with a given plugin. /** * \class CreateClassException */ class CreateClassException : public PluginlibException { public: explicit CreateClassException(const std::string & error_desc) : PluginlibException(error_desc) {} }; } // namespace pluginlib #endif // PLUGINLIB__EXCEPTIONS_HPP_ ros-pluginlib-1.12.1/pluginlib/include/pluginlib/pluginlib_exceptions.h000066400000000000000000000034551331124554700263720ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the copyright holders nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ #define PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ #include "./exceptions.hpp" #endif // PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ ros-pluginlib-1.12.1/pluginlib/package.xml000066400000000000000000000024741331124554700205000ustar00rootroot00000000000000 pluginlib 1.12.1 The pluginlib package provides tools for writing and dynamically loading plugins using the ROS build infrastructure. To work, these tools require plugin providers to register their plugins in the package.xml of their package. Mikael Arguedas BSD http://www.ros.org/wiki/pluginlib https://github.com/ros/pluginlib/issues https://github.com/ros/pluginlib Eitan Marder-Eppstein Tully Foote Dirk Thomas Mirza Shah catkin cmake_modules boost class_loader rosconsole roslib tinyxml2 ros-pluginlib-1.12.1/pluginlib/scripts/000077500000000000000000000000001331124554700200435ustar00rootroot00000000000000ros-pluginlib-1.12.1/pluginlib/scripts/pluginlib_headers_migration.py000077500000000000000000000061531331124554700261560ustar00rootroot00000000000000#!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2018, Open Source Robotics Foundation, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of the copyright holders nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # Run this script to update legacy pluginlib include statements # to utilize the new pluginlib headers. from __future__ import print_function import subprocess cmd = "find . -type f ! -name '*.svn-base' -a ! -name '*.hg' -a ! -name '*.git' -a " \ "\( -name '*.c*' -o -name '*.h*' \)" header_mappings = { 'pluginlib/class_desc.h': 'pluginlib/class_desc.hpp', 'pluginlib/class_list_macros.h': 'pluginlib/class_list_macros.hpp', 'pluginlib/class_loader_base.h': 'pluginlib/class_loader_base.hpp', 'pluginlib/class_loader.h': 'pluginlib/class_loader.hpp', 'pluginlib/class_loader_imp.h': 'pluginlib/class_loader_imp.hpp', 'pluginlib/pluginlib_exceptions.h': 'pluginlib/exceptions.hpp', } include_tokens = { '"': '"', '<': '>', } include_prefix = '#include ' sed_cmd_prefix = ' -exec sed -i \' s' sed_cmd_suffix = ' {} \; ' sed_separator = '@' full_cmd = cmd for old_header, new_header in header_mappings.iteritems(): for leading_token, ending_token in include_tokens.iteritems(): full_cmd += \ sed_cmd_prefix + sed_separator + \ include_prefix + leading_token + old_header + ending_token + sed_separator + \ include_prefix + leading_token + new_header + ending_token + sed_separator + \ "g'" + sed_cmd_suffix print("Looking for '%s' to replace with '%s'" % (old_header, new_header)) print('Running %s' % full_cmd) ret_code = subprocess.call(full_cmd, shell=True) if ret_code == 0: print('success') else: print('failure') ros-pluginlib-1.12.1/pluginlib/test/000077500000000000000000000000001331124554700173335ustar00rootroot00000000000000ros-pluginlib-1.12.1/pluginlib/test/test_base.h000066400000000000000000000035211331124554700214560ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef TEST_BASE_H_ #define TEST_BASE_H_ namespace test_base { class Fubar { public: virtual void initialize(double foo) = 0; virtual double result() = 0; virtual ~Fubar() {} protected: Fubar() {} }; } // namespace test_base #endif // TEST_BASE_H_ ros-pluginlib-1.12.1/pluginlib/test/test_plugins.cpp000066400000000000000000000034561331124554700225670ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include "./test_base.h" #include "test_plugins.h" // NOLINT PLUGINLIB_EXPORT_CLASS(test_plugins::Foo, test_base::Fubar) PLUGINLIB_EXPORT_CLASS(test_plugins::Bar, test_base::Fubar) ros-pluginlib-1.12.1/pluginlib/test/test_plugins.h000066400000000000000000000043321331124554700222260ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef TEST_PLUGINS_H_ #define TEST_PLUGINS_H_ #include #include "./test_base.h" namespace test_plugins { class Bar : public test_base::Fubar { public: Bar() {} void initialize(double foo) { foo_ = foo; } double result() { return 0.5 * foo_ * getBar(); } double getBar() { return sqrt((foo_ * foo_) - ((foo_ / 2) * (foo_ / 2))); } private: double foo_; }; class Foo : public test_base::Fubar { public: Foo() {} void initialize(double foo) { foo_ = foo; } double result() { return foo_ * foo_; } private: double foo_; }; } // namespace test_plugins #endif // TEST_PLUGINS_H_ ros-pluginlib-1.12.1/pluginlib/test/test_plugins.xml000066400000000000000000000010131331124554700225700ustar00rootroot00000000000000 This is a foo plugin. This is a bar plugin. This is a broken none plugin. ros-pluginlib-1.12.1/pluginlib/test/test_plugins_broken.xml000066400000000000000000000003131331124554700241320ustar00rootroot00000000000000 This is a foo plugin. ros-pluginlib-1.12.1/pluginlib/test/unique_ptr_test.cpp000066400000000000000000000074651331124554700233050ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include "./test_base.h" TEST(PluginlibUniquePtrTest, unknownPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); ASSERT_THROW(test_loader.createUniqueInstance("pluginlib/foobar"), pluginlib::LibraryLoadException); } TEST(PluginlibUniquePtrTest, misspelledPlugin) { pluginlib::ClassLoader bad_test_loader("pluginlib", "test_base::Fuba"); ASSERT_THROW(bad_test_loader.createUniqueInstance( "pluginlib/foo"), pluginlib::LibraryLoadException); } TEST(PluginlibTest, brokenPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); ASSERT_THROW(test_loader.createUniqueInstance("pluginlib/none"), pluginlib::PluginlibException); } TEST(PluginlibUniquePtrTest, workingPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); try { pluginlib::UniquePtr foo = test_loader.createUniqueInstance("pluginlib/foo"); foo->initialize(10.0); EXPECT_EQ(100.0, foo->result()); } catch (pluginlib::PluginlibException & ex) { FAIL() << "Throwing exception: " << ex.what(); return; } catch (...) { FAIL() << "Uncaught exception"; } } TEST(PluginlibUniquePtrTest, createUniqueInstanceAndUnloadLibrary) { ROS_INFO("Making the ClassLoader..."); pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); ROS_INFO("Instantiating plugin..."); { pluginlib::UniquePtr inst = pl.createUniqueInstance("pluginlib/foo"); } ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); if (pl.isClassLoaded("pluginlib/foo")) { ROS_INFO("Class is loaded"); } else { FAIL() << "Library containing class should be loaded but isn't."; } ROS_INFO("Trying to unload class with unloadLibraryForClass..."); try { pl.unloadLibraryForClass("pluginlib/foo"); } catch (pluginlib::PluginlibException & e) { FAIL() << "Could not unload library when I should be able to."; } ROS_INFO("Done."); } // Run all the tests that were declared with TEST() int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-pluginlib-1.12.1/pluginlib/test/utest.cpp000066400000000000000000000120641331124554700212060ustar00rootroot00000000000000/* * Copyright (c) 2012, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include "./test_base.h" TEST(PluginlibTest, unknownPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); ASSERT_THROW(test_loader.createInstance("pluginlib/foobar"), pluginlib::LibraryLoadException); } TEST(PluginlibTest, misspelledPlugin) { pluginlib::ClassLoader bad_test_loader("pluginlib", "test_base::Fuba"); ASSERT_THROW(bad_test_loader.createInstance("pluginlib/foo"), pluginlib::LibraryLoadException); } TEST(PluginlibTest, invalidPackage) { ASSERT_THROW(pluginlib::ClassLoader("pluginlib_bad", "test_base::Fubar"), pluginlib::ClassLoaderException); } TEST(PluginlibTest, brokenPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); ASSERT_THROW(test_loader.createInstance("pluginlib/none"), pluginlib::PluginlibException); } TEST(PluginlibTest, workingPlugin) { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); try { boost::shared_ptr foo = test_loader.createInstance("pluginlib/foo"); foo->initialize(10.0); EXPECT_EQ(100.0, foo->result()); } catch (pluginlib::PluginlibException & ex) { FAIL() << "Throwing exception: " << ex.what(); return; } catch (...) { FAIL() << "Uncaught exception"; } } TEST(PluginlibTest, createUnmanagedInstanceAndUnloadLibrary) { ROS_INFO("Making the ClassLoader..."); pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); ROS_INFO("Instantiating plugin..."); test_base::Fubar * inst = pl.createUnmanagedInstance("pluginlib/foo"); ROS_INFO("Deleting plugin..."); delete inst; ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); if (pl.isClassLoaded("pluginlib/foo")) { ROS_INFO("Class is loaded"); } else { FAIL() << "Library containing class should be loaded but isn't."; } ROS_INFO("Trying to unload class with unloadLibraryForClass..."); try { pl.unloadLibraryForClass("pluginlib/foo"); } catch (pluginlib::PluginlibException & e) { FAIL() << "Could not unload library when I should be able to."; } ROS_INFO("Done."); } TEST(PluginlibTest, createManagedInstanceAndUnloadLibrary) { ROS_INFO("Making the ClassLoader..."); pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); ROS_INFO("Instantiating plugin..."); { boost::shared_ptr inst = pl.createInstance("pluginlib/foo"); } ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); if (pl.isClassLoaded("pluginlib/foo")) { ROS_INFO("Class is loaded"); } else { FAIL() << "Library containing class should be loaded but isn't."; } ROS_INFO("Trying to unload class with unloadLibraryForClass..."); try { pl.unloadLibraryForClass("pluginlib/foo"); } catch (pluginlib::PluginlibException & e) { FAIL() << "Could not unload library when I should be able to."; } ROS_INFO("Done."); } TEST(PluginlibTest, brokenXML) { try { pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar", "plugin_test"); test_loader.createInstance("pluginlib/foo"); } catch (pluginlib::PluginlibException & ex) { SUCCEED(); return; } ADD_FAILURE() << "Didn't throw exception as expected"; } // Run all the tests that were declared with TEST() int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); }