Program Listing for File multi_library_class_loader.hpp

Return to documentation for file (include/class_loader/multi_library_class_loader.hpp)

/*
 * Software License Agreement (BSD License)
 *
 * 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 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 CLASS_LOADER__MULTI_LIBRARY_CLASS_LOADER_HPP_
#define CLASS_LOADER__MULTI_LIBRARY_CLASS_LOADER_HPP_

#include <cstddef>
#include <map>
#include <memory>
#include <string>
#include <vector>

// TODO(mikaelarguedas) remove this once console_bridge complies with this
// see https://github.com/ros/console_bridge/issues/55
#ifdef __clang__
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wgnu-zero-variadic-macro-arguments"
#endif
#include "console_bridge/console.h"
#ifdef __clang__
# pragma clang diagnostic pop
#endif

#include "class_loader/class_loader.hpp"
#include "class_loader/visibility_control.hpp"

namespace class_loader
{

typedef std::string LibraryPath;
typedef std::map<LibraryPath, class_loader::ClassLoader *> LibraryToClassLoaderMap;
typedef std::vector<ClassLoader *> ClassLoaderVector;

class MultiLibraryClassLoaderImpl;

class CLASS_LOADER_PUBLIC MultiLibraryClassLoader
{
public:
  explicit MultiLibraryClassLoader(bool enable_ondemand_loadunload);

  virtual ~MultiLibraryClassLoader();

  template<class Base>
  std::shared_ptr<Base> createInstance(const std::string & class_name)
  {
    CONSOLE_BRIDGE_logDebug(
      "class_loader::MultiLibraryClassLoader: "
      "Attempting to create instance of class type %s.",
      class_name.c_str());
    ClassLoader * loader = getClassLoaderForClass<Base>(class_name);
    if (nullptr == loader) {
      throw class_loader::CreateClassException(
              "MultiLibraryClassLoader: Could not create object of class type " +
              class_name +
              " as no factory exists for it. Make sure that the library exists and " +
              "was explicitly loaded through MultiLibraryClassLoader::loadLibrary()");
    }

    return loader->createInstance<Base>(class_name);
  }

  template<class Base>
  std::shared_ptr<Base> createInstance(
    const std::string & class_name, const std::string & library_path)
  {
    ClassLoader * loader = getClassLoaderForLibrary(library_path);
    if (nullptr == loader) {
      throw class_loader::NoClassLoaderExistsException(
              "Could not create instance as there is no ClassLoader in "
              "MultiLibraryClassLoader bound to library " + library_path +
              " Ensure you called MultiLibraryClassLoader::loadLibrary()");
    }
    return loader->createInstance<Base>(class_name);
  }


  template<class Base>
  ClassLoader::UniquePtr<Base> createUniqueInstance(const std::string & class_name)
  {
    CONSOLE_BRIDGE_logDebug(
      "class_loader::MultiLibraryClassLoader: Attempting to create instance of class type %s.",
      class_name.c_str());
    ClassLoader * loader = getClassLoaderForClass<Base>(class_name);
    if (nullptr == loader) {
      throw class_loader::CreateClassException(
              "MultiLibraryClassLoader: Could not create object of class type " + class_name +
              " as no factory exists for it. "
              "Make sure that the library exists and was explicitly loaded through "
              "MultiLibraryClassLoader::loadLibrary()");
    }
    return loader->createUniqueInstance<Base>(class_name);
  }


  template<class Base>
  ClassLoader::UniquePtr<Base>
  createUniqueInstance(const std::string & class_name, const std::string & library_path)
  {
    ClassLoader * loader = getClassLoaderForLibrary(library_path);
    if (nullptr == loader) {
      throw class_loader::NoClassLoaderExistsException(
              "Could not create instance as there is no ClassLoader in "
              "MultiLibraryClassLoader bound to library " + library_path +
              " Ensure you called MultiLibraryClassLoader::loadLibrary()");
    }
    return loader->createUniqueInstance<Base>(class_name);
  }

  template<class Base>
  Base * createUnmanagedInstance(const std::string & class_name)
  {
    ClassLoader * loader = getClassLoaderForClass<Base>(class_name);
    if (nullptr == loader) {
      throw class_loader::CreateClassException(
              "MultiLibraryClassLoader: Could not create class of type " + class_name);
    }
    return loader->createUnmanagedInstance<Base>(class_name);
  }

  template<class Base>
  Base * createUnmanagedInstance(const std::string & class_name, const std::string & library_path)
  {
    ClassLoader * loader = getClassLoaderForLibrary(library_path);
    if (nullptr == loader) {
      throw class_loader::NoClassLoaderExistsException(
              "Could not create instance as there is no ClassLoader in MultiLibraryClassLoader "
              "bound to library " + library_path +
              " Ensure you called MultiLibraryClassLoader::loadLibrary()");
    }
    return loader->createUnmanagedInstance<Base>(class_name);
  }

  template<class Base>
  bool isClassAvailable(const std::string & class_name) const
  {
    std::vector<std::string> available_classes = getAvailableClasses<Base>();
    return available_classes.end() != std::find(
      available_classes.begin(), available_classes.end(), class_name);
  }

  bool isLibraryAvailable(const std::string & library_path) const;

  template<class Base>
  std::vector<std::string> getAvailableClasses() const
  {
    std::vector<std::string> available_classes;
    for (auto & loader : getAllAvailableClassLoaders()) {
      std::vector<std::string> loader_classes = loader->getAvailableClasses<Base>();
      available_classes.insert(
        available_classes.end(), loader_classes.begin(), loader_classes.end());
    }
    return available_classes;
  }

  template<class Base>
  std::vector<std::string> getAvailableClassesForLibrary(const std::string & library_path)
  {
    ClassLoader * loader = getClassLoaderForLibrary(library_path);
    if (nullptr == loader) {
      throw class_loader::NoClassLoaderExistsException(
              "There is no ClassLoader in MultiLibraryClassLoader bound to library " +
              library_path +
              " Ensure you called MultiLibraryClassLoader::loadLibrary()");
    }
    return loader->getAvailableClasses<Base>();
  }

  std::vector<std::string> getRegisteredLibraries() const;

  void loadLibrary(const std::string & library_path);

  int unloadLibrary(const std::string & library_path);

private:
  bool isOnDemandLoadUnloadEnabled() const;

  ClassLoader * getClassLoaderForLibrary(const std::string & library_path);


  template<typename Base>
  ClassLoader * getClassLoaderForClass(const std::string & class_name)
  {
    ClassLoaderVector loaders = getAllAvailableClassLoaders();
    for (ClassLoaderVector::iterator i = loaders.begin(); i != loaders.end(); ++i) {
      if (!(*i)->isLibraryLoaded()) {
        (*i)->loadLibrary();
      }
      if ((*i)->isClassAvailable<Base>(class_name)) {
        return *i;
      }
    }
    return nullptr;
  }

  ClassLoaderVector getAllAvailableClassLoaders() const;

  void shutdownAllClassLoaders();

  MultiLibraryClassLoaderImpl * impl_;
};


}  // namespace class_loader
#endif  // CLASS_LOADER__MULTI_LIBRARY_CLASS_LOADER_HPP_