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


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Tue Jul 9 2024 02:50:20