Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 26 additions & 12 deletions include/class_loader/class_loader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <memory>
#include <mutex>
#include <string>
#include <utility>
#include <vector>

// TODO(mikaelarguedas) remove this once console_bridge complies with this
Expand Down Expand Up @@ -119,13 +120,16 @@ class ClassLoader
* if the library is not yet loaded (which typically happens when in "On Demand Load/Unload" mode).
*
* @param derived_class_name The name of the class we want to create (@see getAvailableClasses())
* @param args Arguments for the constructor of the derived class (types defined
* by InterfaceTraits of the Base class)
* @return A std::shared_ptr<Base> to newly created plugin object
*/
template<class Base>
std::shared_ptr<Base> createInstance(const std::string & derived_class_name)
template<class Base, class ... Args,
std::enable_if_t<is_interface_constructible_v<Base, Args...>, bool> = true>
std::shared_ptr<Base> createInstance(const std::string & derived_class_name, Args &&... args)
{
return std::shared_ptr<Base>(
createRawInstance<Base>(derived_class_name, true),
createRawInstance<Base>(derived_class_name, true, std::forward<Args>(args)...),
std::bind(&ClassLoader::onPluginDeletion<Base>, this, std::placeholders::_1)
);
}
Expand All @@ -141,12 +145,15 @@ class ClassLoader
*
* @param derived_class_name
* The name of the class we want to create (@see getAvailableClasses()).
* @param args Arguments for the constructor of the derived class (types defined
* by InterfaceTraits of the Base class)
* @return A std::unique_ptr<Base> to newly created plugin object.
*/
template<class Base>
UniquePtr<Base> createUniqueInstance(const std::string & derived_class_name)
template<class Base, class ... Args,
std::enable_if_t<is_interface_constructible_v<Base, Args...>, bool> = true>
UniquePtr<Base> createUniqueInstance(const std::string & derived_class_name, Args &&... args)
{
Base * raw = createRawInstance<Base>(derived_class_name, true);
Base * raw = createRawInstance<Base>(derived_class_name, true, std::forward<Args>(args)...);
return std::unique_ptr<Base, DeleterType<Base>>(
raw,
std::bind(&ClassLoader::onPluginDeletion<Base>, this, std::placeholders::_1)
Expand All @@ -164,12 +171,15 @@ class ClassLoader
*
* @param derived_class_name
* The name of the class we want to create (@see getAvailableClasses()).
* @param args Arguments for the constructor of the derived class (types defined
* by InterfaceTraits of the Base class)
* @return An unmanaged (i.e. not a shared_ptr) Base* to newly created plugin object.
*/
template<class Base>
Base * createUnmanagedInstance(const std::string & derived_class_name)
template<class Base, class ... Args,
std::enable_if_t<is_interface_constructible_v<Base, Args...>, bool> = true>
Base * createUnmanagedInstance(const std::string & derived_class_name, Args &&... args)
{
return createRawInstance<Base>(derived_class_name, false);
return createRawInstance<Base>(derived_class_name, false, std::forward<Args>(args)...);
}

/**
Expand Down Expand Up @@ -297,10 +307,13 @@ class ClassLoader
* @param managed
* If true, the returned pointer is assumed to be wrapped in a smart
* pointer by the caller.
* @param args Arguments for the constructor of the derived class (types defined
* by InterfaceTraits of the Base class)
* @return A Base* to newly created plugin object.
*/
template<class Base>
Base * createRawInstance(const std::string & derived_class_name, bool managed)
template<class Base, class ... Args,
std::enable_if_t<is_interface_constructible_v<Base, Args...>, bool> = true>
Base * createRawInstance(const std::string & derived_class_name, bool managed, Args &&... args)
{
if (!managed) {
this->setUnmanagedInstanceBeenCreated(true);
Expand All @@ -324,7 +337,8 @@ class ClassLoader
loadLibrary();
}

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

if (managed) {
Expand Down
44 changes: 23 additions & 21 deletions include/class_loader/class_loader_core.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@
#endif

#include "class_loader/exceptions.hpp"
#include "class_loader/interface_traits.hpp"
#include "class_loader/meta_object.hpp"
#include "class_loader/visibility_control.hpp"

Expand Down Expand Up @@ -344,10 +345,13 @@ registerPlugin(const std::string & class_name, const std::string & base_class_na
*
* @param derived_class_name - The name of the derived class (unmangled)
* @param loader - The ClassLoader whose scope we are within
* @param args - Arguments for the constructor of the derived class (types defined
* by InterfaceTraits of the Base class)
* @return A pointer to newly created plugin, note caller is responsible for object destruction
*/
template<typename Base>
Base * createInstance(const std::string & derived_class_name, ClassLoader * loader)
template<typename Base, class ... Args,
std::enable_if_t<is_interface_constructible_v<Base, Args...>, bool> = true>
Base * createInstance(const std::string & derived_class_name, ClassLoader * loader, Args &&... args)
{
AbstractMetaObject<Base> * factory = nullptr;

Expand All @@ -363,28 +367,26 @@ Base * createInstance(const std::string & derived_class_name, ClassLoader * load

Base * obj = nullptr;
if (factory != nullptr && factory->isOwnedBy(loader)) {
obj = factory->create();
obj = factory->create(std::forward<Args>(args)...);
} else if (factory && factory->isOwnedBy(nullptr)) {
CONSOLE_BRIDGE_logDebug(
"%s",
"class_loader.impl: ALERT!!! "
"A metaobject (i.e. factory) exists for desired class, but has no owner. "
"This implies that the library containing the class was dlopen()ed by means other than "
"through the class_loader interface. "
"This can happen if you build plugin libraries that contain more than just plugins "
"(i.e. normal code your app links against) -- that intrinsically will trigger a dlopen() "
"prior to main(). "
"You should isolate your plugins into their own library, otherwise it will not be "
"possible to shutdown the library!");

obj = factory->create(std::forward<Args>(args)...);
}

if (nullptr == obj) { // Was never created
if (factory && factory->isOwnedBy(nullptr)) {
CONSOLE_BRIDGE_logDebug(
"%s",
"class_loader.impl: ALERT!!! "
"A metaobject (i.e. factory) exists for desired class, but has no owner. "
"This implies that the library containing the class was dlopen()ed by means other than "
"through the class_loader interface. "
"This can happen if you build plugin libraries that contain more than just plugins "
"(i.e. normal code your app links against) -- that intrinsically will trigger a dlopen() "
"prior to main(). "
"You should isolate your plugins into their own library, otherwise it will not be "
"possible to shutdown the library!");

obj = factory->create();
} else {
throw class_loader::CreateClassException(
"Could not create instance of type " + derived_class_name);
}
throw class_loader::CreateClassException(
"Could not create instance of type " + derived_class_name);
}

CONSOLE_BRIDGE_logDebug(
Expand Down
167 changes: 167 additions & 0 deletions include/class_loader/interface_traits.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,167 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2025, Multi-robot Systems (MRS) group at Czech Technical University in Prague
* 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 holder 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 HOLDER 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__INTERFACE_TRAITS_HPP_
#define CLASS_LOADER__INTERFACE_TRAITS_HPP_

#include <type_traits>

namespace class_loader
{

/**
* @brief Customization point that allows setting additional properties of
* an interface class.
*
* @tparam T Base class for which the traits are defined
*
* Users can crete specializations of this class for the base type for which
* the properties should be set. Properties are optional and therefore might not
* exist in a given specialization. To access these properties, use their
* respective accessor traits which provide the default value when it is not
* specified.
*
* Supported properties:
* - `constructor_signature` (member type)
* - accessor: interface_constructor_signature
* - default: T()
* - defines the signature with which will the class loader instantiate the
* derived classes
* - example:
* \code
* using constructor_signature = T(double, int);
* \endcode
* defines that derived classes of class T (replace with the base class type
* used in this specialization) will be instantiated with `double` and `int`
* as their constructor arguments
*
* Example:
* \code
* class BaseWithInterfaceCtor
* {
* public:
* // constructor parameters for the base class do not need to match the derived classes
* explicit BaseWithInterfaceCtor(std::string) {}
* virtual ~BaseWithInterfaceCtor() = default;
*
* virtual int get_number() = 0;
* };
*
* // Specialize the class_loader::InterfaceTraits struct to define properties of your interface
* template<>
* struct class_loader::InterfaceTraits<BaseWithInterfaceCtor>
* {
* // derived classes will be instantiated with two parameters (string and unique_ptr<int>)
* using constructor_signature = BaseWithInterfaceCtor(std::string, std::unique_ptr<int>);
* };
* \endcode
*/
template<class T>
struct InterfaceTraits
{
};

namespace impl
{

template<class T, class = void>
struct interface_constructor_signature_impl
{
using type = T();
};

template<class T>
struct interface_constructor_signature_impl<T,
std::void_t<typename InterfaceTraits<T>::constructor_signature>>
{
using type = typename InterfaceTraits<T>::constructor_signature;
};

} // namespace impl

/**
* @brief Type trait for extracting the `constructor_signature` of
* InterfaceTraits.
*
* @tparam T same as in InterfaceTraits
*
* Helper type:\n
* @ref interface_constructor_signature_t<T> = interface_constructor_signature<T>::type;
*/
template<class T>
struct interface_constructor_signature
{
/**
* @brief InterfaceTraits<T>::constructor_signature if present, otherwise the
* default value (see InterfaceTraits).
*/
using type = typename impl::interface_constructor_signature_impl<T>::type;
};

/**
* @brief Helper type alias @ref interface_constructor_signature<T>::type
* @see interface_constructor_signature
*/
template<class T>
using interface_constructor_signature_t =
typename interface_constructor_signature<T>::type;

/**
* @brief Type trait for checking whether plugins derived from T can be
* constructed with specified arguments.
*
* @tparam Base same as in InterfaceTraits
* @tparam Args list of arguments to check
*
* Contains static constexpr member variable `value` that is true if plugins
* derived from `T` can be constructed using `Args`, false otherwise.
*
* Helper variable template:\n
* @ref is_interface_constructible_v<T, Args...> =
* @ref is_interface_constructible "is_interface_constructible<T, Args...>::value"
*/
template<class Base, class ... Args>
struct is_interface_constructible
: std::is_invocable<interface_constructor_signature_t<Base>, Args...>
{
};

/**
* @brief Helper variable template for @ref is_interface_constructible "is_interface_constructible<T, Args...>::value"
* @see is_interface_constructible
*/
template<class Base, class ... Args>
constexpr bool is_interface_constructible_v =
is_interface_constructible<Base, Args...>::value;

} // namespace class_loader

#endif // CLASS_LOADER__INTERFACE_TRAITS_HPP_
Loading