class_loader_imp.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 *********************************************************************/
36 
37 #ifndef PLUGINLIB__CLASS_LOADER_IMP_HPP_
38 #define PLUGINLIB__CLASS_LOADER_IMP_HPP_
39 
40 #include <cstdlib>
41 #include <list>
42 #include <map>
43 #include <memory>
44 #include <sstream>
45 #include <stdexcept>
46 #include <string>
47 #include <utility>
48 #include <vector>
49 
50 #include "boost/algorithm/string.hpp"
51 #include "boost/bind.hpp"
52 #include "boost/filesystem.hpp"
53 #include "boost/foreach.hpp"
55 
56 #include "ros/package.h"
57 
58 #include "./class_loader.hpp"
59 
60 #ifdef _WIN32
61 const std::string os_pathsep(";"); // NOLINT
62 #else
63 const std::string os_pathsep(":"); // NOLINT
64 #endif
65 
66 namespace
67 {
68 std::vector<std::string> catkinFindLib()
69 {
70  std::vector<std::string> lib_paths;
71  const char * env = std::getenv("CMAKE_PREFIX_PATH");
72  if (env) {
73  std::string env_catkin_prefix_paths(env);
74  std::vector<std::string> catkin_prefix_paths;
75  boost::split(catkin_prefix_paths, env_catkin_prefix_paths, boost::is_any_of(os_pathsep));
76  BOOST_FOREACH(std::string catkin_prefix_path, catkin_prefix_paths) {
77  boost::filesystem::path path(catkin_prefix_path);
78  boost::filesystem::path lib("lib");
79  lib_paths.push_back((path / lib).string());
80  }
81  }
82  return lib_paths;
83 }
84 
85 } // namespace
86 
87 namespace pluginlib
88 {
89 template<class T>
91  std::string package, std::string base_class, std::string attrib_name,
92  std::vector<std::string> plugin_xml_paths)
93 : plugin_xml_paths_(plugin_xml_paths),
94  package_(package),
95  base_class_(base_class),
96  attrib_name_(attrib_name),
97  // NOTE: The parameter to the class loader enables/disables on-demand class
98  // loading/unloading.
99  // Leaving it off for now... libraries will be loaded immediately and won't
100  // be unloaded until class loader is destroyed or force unload.
101  lowlevel_class_loader_(false)
102  /***************************************************************************/
103 {
104  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Creating ClassLoader, base = %s, address = %p",
105  base_class.c_str(), this);
106  if (ros::package::getPath(package_).empty()) {
107  throw pluginlib::ClassLoaderException("Unable to find package: " + package_);
108  }
109 
110  if (0 == plugin_xml_paths_.size()) {
112  }
114  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
115  "Finished constructring ClassLoader, base = %s, address = %p",
116  base_class.c_str(), this);
117 }
118 
119 template<class T>
121 /***************************************************************************/
122 {
123  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Destroying ClassLoader, base = %s, address = %p",
124  getBaseClassType().c_str(), this);
125 }
126 
127 
128 template<class T>
129 T * ClassLoader<T>::createClassInstance(const std::string & lookup_name, bool auto_load)
130 /***************************************************************************/
131 {
132  // Note: This method is deprecated
133  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
134  "In deprecated call createClassInstance(), lookup_name = %s, auto_load = %i.",
135  (lookup_name.c_str()), auto_load);
136 
137  if (auto_load && !isClassLoaded(lookup_name)) {
138  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
139  "Autoloading class library before attempting to create instance.");
140  loadLibraryForClass(lookup_name);
141  }
142 
143  try {
144  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
145  "Attempting to create instance through low-level MultiLibraryClassLoader...");
147  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance created with object pointer = %p", obj);
148 
149  return obj;
150  } catch (const class_loader::CreateClassException & ex) {
151  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "CreateClassException about to be raised for class %s",
152  lookup_name.c_str());
153  throw pluginlib::CreateClassException(ex.what());
154  }
155 }
156 
157 template<class T>
158 boost::shared_ptr<T> ClassLoader<T>::createInstance(const std::string & lookup_name)
159 /***************************************************************************/
160 {
161  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create managed instance for class %s.",
162  lookup_name.c_str());
163 
164  if (!isClassLoaded(lookup_name)) {
165  loadLibraryForClass(lookup_name);
166  }
167 
168  try {
169  std::string class_type = getClassType(lookup_name);
170  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s",
171  lookup_name.c_str(), class_type.c_str());
172 
174 
175  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "boost::shared_ptr to object of real type %s created.",
176  class_type.c_str());
177 
178  return obj;
179  } catch (const class_loader::CreateClassException & ex) {
180  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
181  "Exception raised by low-level multi-library class loader when attempting "
182  "to create instance of class %s.",
183  lookup_name.c_str());
184  throw pluginlib::CreateClassException(ex.what());
185  }
186 }
187 
188 #if __cplusplus >= 201103L
189 template<class T>
190 UniquePtr<T> ClassLoader<T>::createUniqueInstance(const std::string & lookup_name)
191 {
192  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
193  "Attempting to create managed (unique) instance for class %s.",
194  lookup_name.c_str());
195 
196  if (!isClassLoaded(lookup_name)) {
197  loadLibraryForClass(lookup_name);
198  }
199 
200  try {
201  std::string class_type = getClassType(lookup_name);
202  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s",
203  lookup_name.c_str(), class_type.c_str());
204 
205  UniquePtr<T> obj = lowlevel_class_loader_.createUniqueInstance<T>(class_type);
206 
207  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "std::unique_ptr to object of real type %s created.",
208  class_type.c_str());
209 
210  return obj;
211  } catch (const class_loader::CreateClassException & ex) {
212  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
213  "Exception raised by low-level multi-library class loader when attempting "
214  "to create instance of class %s.",
215  lookup_name.c_str());
216  throw pluginlib::CreateClassException(ex.what());
217  }
218 }
219 #endif
220 
221 template<class T>
222 T * ClassLoader<T>::createUnmanagedInstance(const std::string & lookup_name)
223 /***************************************************************************/
224 {
225  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create UNMANAGED instance for class %s.",
226  lookup_name.c_str());
227 
228  if (!isClassLoaded(lookup_name)) {
229  loadLibraryForClass(lookup_name);
230  }
231 
232  T * instance = 0;
233  try {
234  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
235  "Attempting to create instance through low level multi-library class loader.");
236  std::string class_type = getClassType(lookup_name);
237  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s",
238  lookup_name.c_str(), class_type.c_str());
239  instance = lowlevel_class_loader_.createUnmanagedInstance<T>(class_type);
240  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance of type %s created.", class_type.c_str());
241  } catch (const class_loader::CreateClassException & ex) {
242  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
243  "Exception raised by low-level multi-library class loader when attempting "
244  "to create UNMANAGED instance of class %s.",
245  lookup_name.c_str());
246  throw pluginlib::CreateClassException(ex.what());
247  }
248  return instance;
249 }
250 
251 template<class T>
252 std::vector<std::string> ClassLoader<T>::getPluginXmlPaths(
253  const std::string & package,
254  const std::string & attrib_name,
255  bool force_recrawl)
256 /***************************************************************************/
257 {
258  // Pull possible files from manifests of packages which depend on this package and export class
259  std::vector<std::string> paths;
260  ros::package::getPlugins(package, attrib_name, paths, force_recrawl);
261  return paths;
262 }
263 
264 template<class T>
265 std::map<std::string, ClassDesc> ClassLoader<T>::determineAvailableClasses(
266  const std::vector<std::string> & plugin_xml_paths)
267 /***************************************************************************/
268 {
269  // mas - This method requires major refactoring...
270  // not only is it really long and confusing but a lot of the comments do not
271  // seem to be correct.
272  // With time I keep correcting small things, but a good rewrite is needed.
273 
274  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Entering determineAvailableClasses()...");
275  std::map<std::string, ClassDesc> classes_available;
276 
277  // Walk the list of all plugin XML files (variable "paths") that are exported by the build system
278  for (std::vector<std::string>::const_iterator it = plugin_xml_paths.begin();
279  it != plugin_xml_paths.end(); ++it)
280  {
281  try {
282  processSingleXMLPluginFile(*it, classes_available);
283  } catch (const pluginlib::InvalidXMLException & e) {
284  ROS_ERROR_NAMED("pluginlib.ClassLoader",
285  "Skipped loading plugin with error: %s.",
286  e.what());
287  }
288  }
289 
290  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exiting determineAvailableClasses()...");
291  return classes_available;
292 }
293 
294 template<class T>
295 std::string ClassLoader<T>::extractPackageNameFromPackageXML(const std::string & package_xml_path)
296 /***************************************************************************/
297 {
298  tinyxml2::XMLDocument document;
299  document.LoadFile(package_xml_path.c_str());
300  tinyxml2::XMLElement * doc_root_node = document.FirstChildElement("package");
301  if (NULL == doc_root_node) {
302  ROS_ERROR_NAMED("pluginlib.ClassLoader",
303  "Could not find a root element for package manifest at %s.",
304  package_xml_path.c_str());
305  return "";
306  }
307 
308  assert(document.RootElement() == doc_root_node);
309 
310  tinyxml2::XMLElement * package_name_node = doc_root_node->FirstChildElement("name");
311  if (NULL == package_name_node) {
312  ROS_ERROR_NAMED("pluginlib.ClassLoader",
313  "package.xml at %s does not have a <name> tag! Cannot determine package "
314  "which exports plugin.",
315  package_xml_path.c_str());
316  return "";
317  }
318 
319  return package_name_node->GetText();
320 }
321 
322 template<class T>
323 std::vector<std::string> ClassLoader<T>::getCatkinLibraryPaths()
324 /***************************************************************************/
325 {
326  return catkinFindLib();
327 }
328 
329 template<class T>
331  const std::string & library_name,
332  const std::string & exporting_package_name)
333 /***************************************************************************/
334 {
335  // Catkin-rosbuild Backwards Compatability Rules - Note library_name may be prefixed with
336  // relative path (e.g. "/lib/libFoo")
337  // 1. Try catkin library paths (catkin_find --libs) + library_name + extension
338  // 2. Try catkin library paths
339  // (catkin_find -- libs) + stripAllButFileFromPath(library_name) + extension
340  // 3. Try export_pkg/library_name + extension
341 
342  std::vector<std::string> all_paths;
343  std::vector<std::string> all_paths_without_extension = getCatkinLibraryPaths();
344  all_paths_without_extension.push_back(getROSBuildLibraryPath(exporting_package_name));
345  bool debug_library_suffix = (0 == class_loader::systemLibrarySuffix().compare(0, 1, "d"));
346  std::string non_debug_suffix;
347  if (debug_library_suffix) {
348  non_debug_suffix = class_loader::systemLibrarySuffix().substr(1);
349  } else {
350  non_debug_suffix = class_loader::systemLibrarySuffix();
351  }
352  std::string library_name_with_extension = library_name + non_debug_suffix;
353  std::string stripped_library_name = stripAllButFileFromPath(library_name);
354  std::string stripped_library_name_with_extension = stripped_library_name + non_debug_suffix;
355 
356  const std::string path_separator = getPathSeparator();
357 
358  for (unsigned int c = 0; c < all_paths_without_extension.size(); c++) {
359  std::string current_path = all_paths_without_extension.at(c);
360  all_paths.push_back(current_path + path_separator + library_name_with_extension);
361  all_paths.push_back(current_path + path_separator + stripped_library_name_with_extension);
362  // We're in debug mode, try debug libraries as well
363  if (debug_library_suffix) {
364  all_paths.push_back(
365  current_path + path_separator + library_name + class_loader::systemLibrarySuffix());
366  all_paths.push_back(
367  current_path + path_separator + stripped_library_name +
369  }
370  }
371 
372  return all_paths;
373 }
374 
375 template<class T>
376 bool ClassLoader<T>::isClassLoaded(const std::string & lookup_name)
377 /***************************************************************************/
378 {
379  return lowlevel_class_loader_.isClassAvailable<T>(getClassType(lookup_name));
380 }
381 
382 template<class T>
384 /***************************************************************************/
385 {
386  return base_class_;
387 }
388 
389 template<class T>
390 std::string ClassLoader<T>::getClassDescription(const std::string & lookup_name)
391 /***************************************************************************/
392 {
393  ClassMapIterator it = classes_available_.find(lookup_name);
394  if (it != classes_available_.end()) {
395  return it->second.description_;
396  }
397  return "";
398 }
399 
400 template<class T>
401 std::string ClassLoader<T>::getClassType(const std::string & lookup_name)
402 /***************************************************************************/
403 {
404  ClassMapIterator it = classes_available_.find(lookup_name);
405  if (it != classes_available_.end()) {
406  return it->second.derived_class_;
407  }
408  return "";
409 }
410 
411 template<class T>
412 std::string ClassLoader<T>::getClassLibraryPath(const std::string & lookup_name)
413 /***************************************************************************/
414 {
415  if (classes_available_.find(lookup_name) == classes_available_.end()) {
416  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.",
417  lookup_name.c_str());
418  return "";
419  }
420  ClassMapIterator it = classes_available_.find(lookup_name);
421  std::string library_name = it->second.library_name_;
422  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s maps to library %s in classes_available_.",
423  lookup_name.c_str(), library_name.c_str());
424 
425  std::vector<std::string> paths_to_try =
426  getAllLibraryPathsToTry(library_name, it->second.package_);
427 
428  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
429  "Iterating through all possible paths where %s could be located...",
430  library_name.c_str());
431  for (std::vector<std::string>::const_iterator it = paths_to_try.begin(); it != paths_to_try.end();
432  it++)
433  {
434  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Checking path %s ", it->c_str());
435  if (boost::filesystem::exists(*it)) {
436  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Library %s found at explicit path %s.",
437  library_name.c_str(), it->c_str());
438  return *it;
439  }
440  }
441  return "";
442 }
443 
444 template<class T>
445 std::string ClassLoader<T>::getClassPackage(const std::string & lookup_name)
446 /***************************************************************************/
447 {
448  ClassMapIterator it = classes_available_.find(lookup_name);
449  if (it != classes_available_.end()) {
450  return it->second.package_;
451  }
452  return "";
453 }
454 
455 template<class T>
456 std::vector<std::string> ClassLoader<T>::getPluginXmlPaths()
457 /***************************************************************************/
458 {
459  return plugin_xml_paths_;
460 }
461 
462 template<class T>
463 std::vector<std::string> ClassLoader<T>::getDeclaredClasses()
464 /***************************************************************************/
465 {
466  std::vector<std::string> lookup_names;
467  for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); ++it) {
468  lookup_names.push_back(it->first);
469  }
470 
471  return lookup_names;
472 }
473 
474 template<class T>
475 std::string ClassLoader<T>::getErrorStringForUnknownClass(const std::string & lookup_name)
476 /***************************************************************************/
477 {
478  std::string declared_types;
479  std::vector<std::string> types = getDeclaredClasses();
480  for (unsigned int i = 0; i < types.size(); i++) {
481  declared_types = declared_types + std::string(" ") + types[i];
482  }
483  return "According to the loaded plugin descriptions the class " + lookup_name +
484  " with base class type " + base_class_ + " does not exist. Declared types are " +
485  declared_types;
486 }
487 
488 template<class T>
489 std::string ClassLoader<T>::getName(const std::string & lookup_name)
490 /***************************************************************************/
491 {
492  // remove the package name to get the raw plugin name
493  std::vector<std::string> split;
494  boost::split(split, lookup_name, boost::is_any_of("/:"));
495  return split.back();
496 }
497 
498 template<class T>
499 std::string
500 ClassLoader<T>::getPackageFromPluginXMLFilePath(const std::string & plugin_xml_file_path)
501 /***************************************************************************/
502 {
503  // Note: This method takes an input a path to a plugin xml file and must determine which
504  // package the XML file came from. This is not necessariliy the same thing as the member
505  // variable "package_". The plugin xml file can be located anywhere in the source tree for a
506  // package
507 
508  // rosbuild:
509  // 1. Find nearest encasing manifest.xml
510  // 2. Once found, the name of the folder containg the manifest should be the
511  // package name we are looking for
512  // 3. Confirm package is findable with rospack
513 
514  // catkin:
515  // 1. Find nearest encasing package.xml
516  // 2. Extract name of package from package.xml
517 
518  std::string package_name;
519  boost::filesystem::path p(plugin_xml_file_path);
520  boost::filesystem::path parent = p.parent_path();
521 
522  // Figure out exactly which package the passed XML file is exported by.
523  while (true) {
524  if (boost::filesystem::exists(parent / "package.xml")) {
525  std::string package_file_path = (boost::filesystem::path(parent / "package.xml")).string();
526  return extractPackageNameFromPackageXML(package_file_path);
527  } else if (boost::filesystem::exists(parent / "manifest.xml")) {
528 #if BOOST_FILESYSTEM_VERSION >= 3
529  std::string package = parent.filename().string();
530 #else
531  std::string package = parent.filename();
532 #endif
533  std::string package_path = ros::package::getPath(package);
534 
535  // package_path is a substr of passed plugin xml path
536  if (0 == plugin_xml_file_path.find(package_path)) {
537  package_name = package;
538  break;
539  }
540  }
541 
542  // Recursive case - hop one folder up
543  parent = parent.parent_path().string();
544 
545  // Base case - reached root and cannot find what we're looking for
546  if (parent.string().empty()) {
547  return "";
548  }
549  }
550 
551  return package_name;
552 }
553 
554 template<class T>
556 /***************************************************************************/
557 {
558 #if BOOST_FILESYSTEM_VERSION >= 3
559  return boost::filesystem::path("/").native();
560 #else
561  return boost::filesystem::path("/").external_file_string();
562 #endif
563 }
564 
565 
566 template<class T>
567 std::string ClassLoader<T>::getPluginManifestPath(const std::string & lookup_name)
568 /***************************************************************************/
569 {
570  ClassMapIterator it = classes_available_.find(lookup_name);
571  if (it != classes_available_.end()) {
572  return it->second.plugin_manifest_path_;
573  }
574  return "";
575 }
576 
577 
578 template<class T>
579 std::vector<std::string> ClassLoader<T>::getRegisteredLibraries()
580 /***************************************************************************/
581 {
583 }
584 
585 template<class T>
586 std::string ClassLoader<T>::getROSBuildLibraryPath(const std::string & exporting_package_name)
587 /***************************************************************************/
588 {
589  return ros::package::getPath(exporting_package_name);
590 }
591 
592 template<class T>
593 bool ClassLoader<T>::isClassAvailable(const std::string & lookup_name)
594 /***************************************************************************/
595 {
596  return classes_available_.find(lookup_name) != classes_available_.end();
597 }
598 
599 template<class T>
600 std::string ClassLoader<T>::joinPaths(const std::string & path1, const std::string & path2)
601 /***************************************************************************/
602 {
603  boost::filesystem::path p1(path1);
604  return (p1 / path2).string();
605 }
606 
607 template<class T>
608 void ClassLoader<T>::loadLibraryForClass(const std::string & lookup_name)
609 /***************************************************************************/
610 {
611  ClassMapIterator it = classes_available_.find(lookup_name);
612  if (it == classes_available_.end()) {
613  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.",
614  lookup_name.c_str());
616  }
617 
618  std::string library_path = getClassLibraryPath(lookup_name);
619  if ("" == library_path) {
620  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "No path could be found to the library containing %s.",
621  lookup_name.c_str());
622  std::ostringstream error_msg;
623  error_msg << "Could not find library corresponding to plugin " << lookup_name <<
624  ". Make sure the plugin description XML file has the correct name of the "
625  "library and that the library actually exists.";
626  throw pluginlib::LibraryLoadException(error_msg.str());
627  }
628 
629  try {
630  lowlevel_class_loader_.loadLibrary(library_path);
631  it->second.resolved_library_path_ = library_path;
632  } catch (const class_loader::LibraryLoadException & ex) {
633  std::string error_string =
634  "Failed to load library " + library_path + ". "
635  "Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the "
636  "library code, and that names are consistent between this macro and your XML. "
637  "Error string: " + ex.what();
638  throw pluginlib::LibraryLoadException(error_string);
639  }
640 }
641 
642 template<class T>
644  const std::string & xml_file, std::map<std::string,
645  ClassDesc> & classes_available)
646 /***************************************************************************/
647 {
648  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Processing xml file %s...", xml_file.c_str());
649  tinyxml2::XMLDocument document;
650  document.LoadFile(xml_file.c_str());
651  tinyxml2::XMLElement * config = document.RootElement();
652  if (NULL == config) {
654  "XML Document '" + xml_file +
655  "' has no Root Element. This likely means the XML is malformed or missing.");
656  return;
657  }
658  if (!(strcmp(config->Value(), "library") == 0 ||
659  strcmp(config->Value(), "class_libraries") == 0))
660  {
662  "The XML document '" + xml_file + "' given to add must have either \"library\" or "
663  "\"class_libraries\" as the root tag");
664  return;
665  }
666  // Step into the filter list if necessary
667  if (strcmp(config->Value(), "class_libraries") == 0) {
668  config = config->FirstChildElement("library");
669  }
670 
671  tinyxml2::XMLElement * library = config;
672  while (library != NULL) {
673  std::string library_path = library->Attribute("path");
674  if (0 == library_path.size()) {
675  ROS_ERROR_NAMED("pluginlib.ClassLoader",
676  "Failed to find Path Attirbute in library element in %s", xml_file.c_str());
677  continue;
678  }
679 
680  std::string package_name = getPackageFromPluginXMLFilePath(xml_file);
681  if ("" == package_name) {
682  ROS_ERROR_NAMED("pluginlib.ClassLoader",
683  "Could not find package manifest (neither package.xml or deprecated "
684  "manifest.xml) at same directory level as the plugin XML file %s. "
685  "Plugins will likely not be exported properly.\n)",
686  xml_file.c_str());
687  }
688 
689  tinyxml2::XMLElement * class_element = library->FirstChildElement("class");
690  while (class_element) {
691  std::string derived_class;
692  if (class_element->Attribute("type") != NULL) {
693  derived_class = std::string(class_element->Attribute("type"));
694  } else {
696  "Class could not be loaded. Attribute 'type' in class tag is missing.");
697  }
698 
699  std::string base_class_type;
700  if (class_element->Attribute("base_class_type") != NULL) {
701  base_class_type = std::string(class_element->Attribute("base_class_type"));
702  } else {
704  "Class could not be loaded. Attribute 'base_class_type' in class tag is missing.");
705  }
706 
707  std::string lookup_name;
708  if (class_element->Attribute("name") != NULL) {
709  lookup_name = class_element->Attribute("name");
710  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
711  "XML file specifies lookup name (i.e. magic name) = %s.",
712  lookup_name.c_str());
713  } else {
714  ROS_DEBUG_NAMED("pluginlib.ClassLoader",
715  "XML file has no lookup name (i.e. magic name) for class %s, "
716  "assuming lookup_name == real class name.",
717  derived_class.c_str());
718  lookup_name = derived_class;
719  }
720 
721  // make sure that this class is of the right type before registering it
722  if (base_class_type == base_class_) {
723  // register class here
724  tinyxml2::XMLElement * description = class_element->FirstChildElement("description");
725  std::string description_str;
726  if (description) {
727  description_str = description->GetText() ? description->GetText() : "";
728  } else {
729  description_str = "No 'description' tag for this plugin in plugin description file.";
730  }
731 
732  classes_available.insert(std::pair<std::string, ClassDesc>(lookup_name,
733  ClassDesc(lookup_name, derived_class, base_class_type, package_name, description_str,
734  library_path, xml_file)));
735  }
736 
737  // step to next class_element
738  class_element = class_element->NextSiblingElement("class");
739  }
740  library = library->NextSiblingElement("library");
741  }
742 }
743 
744 template<class T>
746 /***************************************************************************/
747 {
748  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Refreshing declared classes.");
749  // determine classes not currently loaded for removal
750  std::list<std::string> remove_classes;
751  for (std::map<std::string, ClassDesc>::const_iterator it = classes_available_.begin();
752  it != classes_available_.end(); it++)
753  {
754  std::string resolved_library_path = it->second.resolved_library_path_;
755  std::vector<std::string> open_libs = lowlevel_class_loader_.getRegisteredLibraries();
756  if (std::find(open_libs.begin(), open_libs.end(), resolved_library_path) != open_libs.end()) {
757  remove_classes.push_back(it->first);
758  }
759  }
760 
761  while (!remove_classes.empty()) {
762  classes_available_.erase(remove_classes.front());
763  remove_classes.pop_front();
764  }
765 
766  // add new classes
768  std::map<std::string, ClassDesc> updated_classes = determineAvailableClasses(plugin_xml_paths_);
769  for (std::map<std::string, ClassDesc>::const_iterator it = updated_classes.begin();
770  it != updated_classes.end(); it++)
771  {
772  if (classes_available_.find(it->first) == classes_available_.end()) {
773  classes_available_.insert(std::pair<std::string, ClassDesc>(it->first, it->second));
774  }
775  }
776 }
777 
778 template<class T>
779 std::string ClassLoader<T>::stripAllButFileFromPath(const std::string & path)
780 /***************************************************************************/
781 {
782  std::string only_file;
783  size_t c = path.find_last_of(getPathSeparator());
784  if (std::string::npos == c) {
785  return path;
786  } else {
787  return path.substr(c, path.size());
788  }
789 }
790 
791 template<class T>
792 int ClassLoader<T>::unloadLibraryForClass(const std::string & lookup_name)
793 /***************************************************************************/
794 {
795  ClassMapIterator it = classes_available_.find(lookup_name);
796  if (it != classes_available_.end() && it->second.resolved_library_path_ != "UNRESOLVED") {
797  std::string library_path = it->second.resolved_library_path_;
798  ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to unload library %s for class %s",
799  library_path.c_str(), lookup_name.c_str());
800  return unloadClassLibraryInternal(library_path);
801  } else {
803  }
804 }
805 
806 template<class T>
807 int ClassLoader<T>::unloadClassLibraryInternal(const std::string & library_path)
808 /***************************************************************************/
809 {
810  return lowlevel_class_loader_.unloadLibrary(library_path);
811 }
812 
813 } // namespace pluginlib
814 
815 #endif // PLUGINLIB__CLASS_LOADER_IMP_HPP_
virtual std::string getClassType(const std::string &lookup_name)
Given the lookup name of a class, return the type of the derived class associated with it...
virtual std::string getPluginManifestPath(const std::string &lookup_name)
Given the name of a class, return the path of the associated plugin manifest.
std::map< std::string, ClassDesc > determineAvailableClasses(const std::vector< std::string > &plugin_xml_paths)
Return the available classes.
const std::string os_pathsep(":")
Thrown when pluginlib is unable to instantiate a class loader.
Definition: exceptions.hpp:78
string package
class_loader::MultiLibraryClassLoader lowlevel_class_loader_
std::string getPathSeparator()
Get the standard path separator for the native OS (e.g. "/" on *nix, "\" on Windows).
std::string getPackageFromPluginXMLFilePath(const std::string &path)
Get the package name from a path to a plugin XML file.
std::string getROSBuildLibraryPath(const std::string &exporting_package_name)
Given a package name, return the path where rosbuild thinks plugins are installed.
virtual int unloadLibraryForClass(const std::string &lookup_name)
Decrement the counter for the library containing a class with a given name.
virtual std::string getClassDescription(const std::string &lookup_name)
Given the lookup name of a class, return its description.
int unloadLibrary(const std::string &library_path)
virtual void loadLibraryForClass(const std::string &lookup_name)
Attempt to load the library containing a class with a given name.
virtual std::string getClassLibraryPath(const std::string &lookup_name)
Given the name of a class, return the path to its associated library.
virtual std::string getBaseClassType() const
Given the lookup name of a class, return the type of the associated base class.
T * createUnmanagedInstance(const std::string &lookup_name)
Create an instance of a desired class.
std::vector< std::string > plugin_xml_paths_
virtual std::string getClassPackage(const std::string &lookup_name)
Given the name of a class, return name of the containing package.
std::string systemLibrarySuffix()
bool isClassLoaded(const std::string &lookup_name)
Check if the library for a given class is currently loaded.
std::string extractPackageNameFromPackageXML(const std::string &package_xml_path)
Open a package.xml file and extract the package name (i.e. contents of <name> tag).
std::map< std::string, ClassDesc >::iterator ClassMapIterator
#define ROS_DEBUG_NAMED(name,...)
Storage for information about a given class.
Definition: class_desc.hpp:46
void loadLibrary(const std::string &library_path)
Thrown when pluginlib is unable to unload the library associated with a given plugin.
Definition: exceptions.hpp:89
virtual void refreshDeclaredClasses()
Refresh the list of all available classes for this ClassLoader&#39;s base class type. ...
std::string joinPaths(const std::string &path1, const std::string &path2)
Join two filesystem paths together utilzing appropriate path separator.
std::vector< std::string > getDeclaredClasses()
Return a list of all available classes for this ClassLoader&#39;s base class type.
std::vector< std::string > getAllLibraryPathsToTry(const std::string &library_name, const std::string &exporting_package_name)
Get a list of paths to try to find a library.
std::vector< std::string > getCatkinLibraryPaths()
Return the paths where libraries are installed according to the Catkin build system.
std::vector< std::string > getRegisteredLibraries()
virtual std::vector< std::string > getRegisteredLibraries()
Return the libraries that are registered and can be loaded.
Thrown when pluginlib is unable to load a plugin XML file.
Definition: exceptions.hpp:56
virtual std::string getName(const std::string &lookup_name)
Strip the package name off of a lookup name.
ROSLIB_DECL std::string getPath(const std::string &package_name)
ROSLIB_DECL void getPlugins(const std::string &package, const std::string &attribute, V_string &plugins, bool force_recrawl=false)
std::vector< std::string > getPluginXmlPaths()
Return a list of all available plugin manifest paths for this ClassLoader&#39;s base class type...
std::string stripAllButFileFromPath(const std::string &path)
Strip all but the filename from an explicit file path.
ClassLoader(std::string package, std::string base_class, std::string attrib_name=std::string("plugin"), std::vector< std::string > plugin_xml_paths=std::vector< std::string >())
#define ROS_ERROR_NAMED(name,...)
A class to help manage and load classes.
Thrown when pluginlib is unable to load the library associated with a given plugin.
Definition: exceptions.hpp:67
virtual bool isClassAvailable(const std::string &lookup_name)
Check if the class associated with a plugin name is available to be loaded.
std::map< std::string, ClassDesc > classes_available_
int unloadClassLibraryInternal(const std::string &library_path)
Helper function for unloading a shared library.
Thrown when pluginlib is unable to create the class associated with a given plugin.
Definition: exceptions.hpp:100
boost::shared_ptr< Base > createInstance(const std::string &class_name)
std::string getErrorStringForUnknownClass(const std::string &lookup_name)
Return an error message for an unknown class.
void processSingleXMLPluginFile(const std::string &xml_file, std::map< std::string, ClassDesc > &class_available)
Parse a plugin XML file.
bool isClassAvailable(const std::string &class_name)
Base * createUnmanagedInstance(const std::string &class_name)


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Mon Jun 10 2019 14:15:48