Program Listing for File class_loader.hpp

Return to documentation for file (include/class_loader/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__CLASS_LOADER_HPP_
#define CLASS_LOADER__CLASS_LOADER_HPP_

#include <algorithm>
#include <cassert>
#include <cstddef>
#include <functional>
#include <memory>
#include <mutex>
#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_core.hpp"
#include "class_loader/register_macro.hpp"
#include "class_loader/visibility_control.hpp"

namespace class_loader
{


CLASS_LOADER_PUBLIC
std::string systemLibraryFormat(const std::string & library_name);

class ClassLoader
{
public:
  template<typename Base>
  using DeleterType = std::function<void (Base *)>;

  template<typename Base>
  using UniquePtr = std::unique_ptr<Base, DeleterType<Base>>;

  CLASS_LOADER_PUBLIC
  explicit ClassLoader(const std::string & library_path, bool ondemand_load_unload = false);

  CLASS_LOADER_PUBLIC
  virtual ~ClassLoader();

  template<class Base>
  std::vector<std::string> getAvailableClasses() const
  {
    return class_loader::impl::getAvailableClasses<Base>(this);
  }

  template<class Base>
  std::shared_ptr<Base> createInstance(const std::string & derived_class_name)
  {
    return std::shared_ptr<Base>(
      createRawInstance<Base>(derived_class_name, true),
      std::bind(&ClassLoader::onPluginDeletion<Base>, this, std::placeholders::_1)
    );
  }


  template<class Base>
  UniquePtr<Base> createUniqueInstance(const std::string & derived_class_name)
  {
    Base * raw = createRawInstance<Base>(derived_class_name, true);
    return std::unique_ptr<Base, DeleterType<Base>>(
      raw,
      std::bind(&ClassLoader::onPluginDeletion<Base>, this, std::placeholders::_1)
    );
  }


  template<class Base>
  Base * createUnmanagedInstance(const std::string & derived_class_name)
  {
    return createRawInstance<Base>(derived_class_name, false);
  }

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

  CLASS_LOADER_PUBLIC
  const std::string & getLibraryPath() const;

  CLASS_LOADER_PUBLIC
  bool isLibraryLoaded() const;

  CLASS_LOADER_PUBLIC
  bool isLibraryLoadedByAnyClassloader() const;

  CLASS_LOADER_PUBLIC
  bool isOnDemandLoadUnloadEnabled() const;

  CLASS_LOADER_PUBLIC
  void loadLibrary();

  CLASS_LOADER_PUBLIC
  int unloadLibrary();

private:
  template<class Base>
  void onPluginDeletion(Base * obj)
  {
    CONSOLE_BRIDGE_logDebug(
      "class_loader::ClassLoader: Calling onPluginDeletion() for obj ptr = %p.\n",
      reinterpret_cast<void *>(obj));
    if (nullptr == obj) {
      return;
    }
    std::lock_guard<std::recursive_mutex> lock(plugin_ref_count_mutex_);
    delete (obj);
    assert(plugin_ref_count_ > 0);
    --plugin_ref_count_;
    if (plugin_ref_count_ == 0 && isOnDemandLoadUnloadEnabled()) {
      if (!ClassLoader::hasUnmanagedInstanceBeenCreated()) {
        unloadLibraryInternal(false);
      } else {
        CONSOLE_BRIDGE_logWarn(
          "class_loader::ClassLoader: "
          "Cannot unload library %s even though last shared pointer went out of scope. "
          "This is because createUnmanagedInstance was used within the scope of this process, "
          "perhaps by a different ClassLoader. "
          "Library will NOT be closed.",
          getLibraryPath().c_str());
      }
    }
  }


  template<class Base>
  Base * createRawInstance(const std::string & derived_class_name, bool managed)
  {
    if (!managed) {
      this->setUnmanagedInstanceBeenCreated(true);
    }

    if (
      managed &&
      ClassLoader::hasUnmanagedInstanceBeenCreated() &&
      isOnDemandLoadUnloadEnabled())
    {
      CONSOLE_BRIDGE_logInform(
        "%s",
        "class_loader::ClassLoader: "
        "An attempt is being made to create a managed plugin instance (i.e. boost::shared_ptr), "
        "however an unmanaged instance was created within this process address space. "
        "This means libraries for the managed instances will not be shutdown automatically on "
        "final plugin destruction if on demand (lazy) loading/unloading mode is used."
      );
    }
    if (!isLibraryLoaded()) {
      loadLibrary();
    }

    Base * obj = class_loader::impl::createInstance<Base>(derived_class_name, this);
    assert(obj != NULL);  // Unreachable assertion if createInstance() throws on failure.

    if (managed) {
      std::lock_guard<std::recursive_mutex> lock(plugin_ref_count_mutex_);
      ++plugin_ref_count_;
    }

    return obj;
  }

  CLASS_LOADER_PUBLIC
  static bool hasUnmanagedInstanceBeenCreated();

  CLASS_LOADER_PUBLIC
  static void setUnmanagedInstanceBeenCreated(bool state);

  CLASS_LOADER_PUBLIC
  int unloadLibraryInternal(bool lock_plugin_ref_count);

private:
  bool ondemand_load_unload_;
  std::string library_path_;
  int load_ref_count_;
  std::recursive_mutex load_ref_count_mutex_;
  int plugin_ref_count_;
  std::recursive_mutex plugin_ref_count_mutex_;
  static bool has_unmananged_instance_been_created_;
};

}  // namespace class_loader


#endif  // CLASS_LOADER__CLASS_LOADER_HPP_