From a23fd3a977738cb344bb3b385af80f7bff3478b2 Mon Sep 17 00:00:00 2001 From: pum1k <55055380+pum1k@users.noreply.github.com> Date: Wed, 17 Dec 2025 17:22:00 +0100 Subject: [PATCH] Add support for passing arguments to constructors - added InterfaceTraits type trait that can be used to define the constructor arguments used by the derived classes - changed class loaders to pass arguments to the derived classes based on the information stored in InterfaceTraits Signed-off-by: pum1k <55055380+pum1k@users.noreply.github.com> --- include/class_loader/class_loader.hpp | 38 ++-- include/class_loader/class_loader_core.hpp | 44 ++--- include/class_loader/interface_traits.hpp | 167 ++++++++++++++++++ include/class_loader/meta_object.hpp | 81 ++++++--- .../multi_library_class_loader.hpp | 59 +++++-- test/CMakeLists.txt | 8 +- test/base.hpp | 24 +++ test/plugins3.cpp | 67 +++++++ test/unique_ptr_test.cpp | 30 ++++ test/utest.cpp | 46 +++++ 10 files changed, 488 insertions(+), 76 deletions(-) create mode 100644 include/class_loader/interface_traits.hpp create mode 100644 test/plugins3.cpp diff --git a/include/class_loader/class_loader.hpp b/include/class_loader/class_loader.hpp index b0af5b69..fb7d9dd4 100644 --- a/include/class_loader/class_loader.hpp +++ b/include/class_loader/class_loader.hpp @@ -39,6 +39,7 @@ #include #include #include +#include #include // TODO(mikaelarguedas) remove this once console_bridge complies with this @@ -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 to newly created plugin object */ - template - std::shared_ptr createInstance(const std::string & derived_class_name) + template, bool> = true> + std::shared_ptr createInstance(const std::string & derived_class_name, Args &&... args) { return std::shared_ptr( - createRawInstance(derived_class_name, true), + createRawInstance(derived_class_name, true, std::forward(args)...), std::bind(&ClassLoader::onPluginDeletion, this, std::placeholders::_1) ); } @@ -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 to newly created plugin object. */ - template - UniquePtr createUniqueInstance(const std::string & derived_class_name) + template, bool> = true> + UniquePtr createUniqueInstance(const std::string & derived_class_name, Args &&... args) { - Base * raw = createRawInstance(derived_class_name, true); + Base * raw = createRawInstance(derived_class_name, true, std::forward(args)...); return std::unique_ptr>( raw, std::bind(&ClassLoader::onPluginDeletion, this, std::placeholders::_1) @@ -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 - Base * createUnmanagedInstance(const std::string & derived_class_name) + template, bool> = true> + Base * createUnmanagedInstance(const std::string & derived_class_name, Args &&... args) { - return createRawInstance(derived_class_name, false); + return createRawInstance(derived_class_name, false, std::forward(args)...); } /** @@ -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 - Base * createRawInstance(const std::string & derived_class_name, bool managed) + template, bool> = true> + Base * createRawInstance(const std::string & derived_class_name, bool managed, Args &&... args) { if (!managed) { this->setUnmanagedInstanceBeenCreated(true); @@ -324,7 +337,8 @@ class ClassLoader loadLibrary(); } - Base * obj = class_loader::impl::createInstance(derived_class_name, this); + Base * obj = class_loader::impl::createInstance(derived_class_name, this, + std::forward(args)...); assert(obj != NULL); // Unreachable assertion if createInstance() throws on failure. if (managed) { diff --git a/include/class_loader/class_loader_core.hpp b/include/class_loader/class_loader_core.hpp index f41a87f6..1e402f6f 100644 --- a/include/class_loader/class_loader_core.hpp +++ b/include/class_loader/class_loader_core.hpp @@ -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" @@ -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 -Base * createInstance(const std::string & derived_class_name, ClassLoader * loader) +template, bool> = true> +Base * createInstance(const std::string & derived_class_name, ClassLoader * loader, Args &&... args) { AbstractMetaObject * factory = nullptr; @@ -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)...); + } 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)...); } 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( diff --git a/include/class_loader/interface_traits.hpp b/include/class_loader/interface_traits.hpp new file mode 100644 index 00000000..41eb49b5 --- /dev/null +++ b/include/class_loader/interface_traits.hpp @@ -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 + +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 + * { + * // derived classes will be instantiated with two parameters (string and unique_ptr) + * using constructor_signature = BaseWithInterfaceCtor(std::string, std::unique_ptr); + * }; + * \endcode + */ +template +struct InterfaceTraits +{ +}; + +namespace impl +{ + +template +struct interface_constructor_signature_impl +{ + using type = T(); +}; + +template +struct interface_constructor_signature_impl::constructor_signature>> +{ + using type = typename InterfaceTraits::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 = interface_constructor_signature::type; + */ +template +struct interface_constructor_signature +{ + /** + * @brief InterfaceTraits::constructor_signature if present, otherwise the + * default value (see InterfaceTraits). + */ + using type = typename impl::interface_constructor_signature_impl::type; +}; + +/** + * @brief Helper type alias @ref interface_constructor_signature::type + * @see interface_constructor_signature + */ +template +using interface_constructor_signature_t = + typename interface_constructor_signature::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 = + * @ref is_interface_constructible "is_interface_constructible::value" + */ +template +struct is_interface_constructible + : std::is_invocable, Args...> +{ +}; + +/** + * @brief Helper variable template for @ref is_interface_constructible "is_interface_constructible::value" + * @see is_interface_constructible + */ +template +constexpr bool is_interface_constructible_v = + is_interface_constructible::value; + +} // namespace class_loader + +#endif // CLASS_LOADER__INTERFACE_TRAITS_HPP_ diff --git a/include/class_loader/meta_object.hpp b/include/class_loader/meta_object.hpp index 24801936..ad4cacf3 100644 --- a/include/class_loader/meta_object.hpp +++ b/include/class_loader/meta_object.hpp @@ -36,8 +36,10 @@ #include #include +#include #include +#include "class_loader/interface_traits.hpp" #include "class_loader/visibility_control.hpp" namespace class_loader @@ -152,6 +154,27 @@ class CLASS_LOADER_PUBLIC AbstractMetaObjectBase AbstractMetaObjectBaseImpl * impl_; }; +template +class AbstractMetaObjectImpl { + static_assert(false, "Base template selected."); +}; + +template +class AbstractMetaObjectImpl: public AbstractMetaObjectBase { +protected: + using AbstractMetaObjectBase::AbstractMetaObjectBase; + +public: + /** + * @brief Defines the factory interface that the MetaObject must implement. + * + * @return A pointer of parametric type B to a newly created object. + */ + virtual B * create(Args... args) const = 0; + /// Create a new instance of a class. + /// Cannot be used for singletons. +}; + /** * @class AbstractMetaObject * @brief Abstract base class for factories where polymorphic type variable indicates base class for @@ -160,8 +183,10 @@ class CLASS_LOADER_PUBLIC AbstractMetaObjectBase * @parm B The base class interface for the plugin */ template -class AbstractMetaObject : public AbstractMetaObjectBase +class AbstractMetaObject : public AbstractMetaObjectImpl> { + using Base = AbstractMetaObjectImpl>; + public: /** * @brief A constructor for this class @@ -169,25 +194,42 @@ class AbstractMetaObject : public AbstractMetaObjectBase * @param name The literal name of the class. */ AbstractMetaObject(const std::string & class_name, const std::string & base_class_name) - : AbstractMetaObjectBase(class_name, base_class_name, typeid(B).name()) + : Base(class_name, base_class_name, typeid(B).name()) { } - /** - * @brief Defines the factory interface that the MetaObject must implement. - * - * @return A pointer of parametric type B to a newly created object. - */ - virtual B * create() const = 0; - /// Create a new instance of a class. - /// Cannot be used for singletons. - private: AbstractMetaObject(); AbstractMetaObject(const AbstractMetaObject &); AbstractMetaObject & operator=(const AbstractMetaObject &); }; +template +class MetaObjectImpl { + static_assert(false, "Base template selected."); +}; + +template +class MetaObjectImpl: public AbstractMetaObject +{ +protected: + using AbstractMetaObject::AbstractMetaObject; + +public: + static_assert(std::is_constructible_v, + "Plugin must be constructible with arguments defined by the interface."); + /** + * @brief The factory interface to generate an object. The object has type C in reality, though a + * pointer of the base class type is returned. + * + * @return A pointer to a newly created plugin with the base class type (type parameter B) + */ + B * create(Args... args) const override + { + return new C(std::forward(args)...); + } +}; + /** * @class MetaObject * @brief The actual factory. @@ -196,26 +238,17 @@ class AbstractMetaObject : public AbstractMetaObjectBase * @parm B The base class interface for the plugin */ template -class MetaObject : public AbstractMetaObject +class MetaObject : public MetaObjectImpl> { + using Base = MetaObjectImpl>; + public: /** * @brief Constructor for the class */ MetaObject(const std::string & class_name, const std::string & base_class_name) - : AbstractMetaObject(class_name, base_class_name) - { - } - - /** - * @brief The factory interface to generate an object. The object has type C in reality, though a - * pointer of the base class type is returned. - * - * @return A pointer to a newly created plugin with the base class type (type parameter B) - */ - B * create() const + : Base(class_name, base_class_name) { - return new C; } }; diff --git a/include/class_loader/multi_library_class_loader.hpp b/include/class_loader/multi_library_class_loader.hpp index f04afc8f..e78c8b78 100644 --- a/include/class_loader/multi_library_class_loader.hpp +++ b/include/class_loader/multi_library_class_loader.hpp @@ -36,6 +36,7 @@ #include #include #include +#include #include // TODO(mikaelarguedas) remove this once console_bridge complies with this @@ -87,10 +88,13 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * * @param Base - polymorphic type indicating base class * @param class_name - the name of the concrete plugin class we want to instantiate + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) * @return A std::shared_ptr to newly created plugin */ - template - std::shared_ptr createInstance(const std::string & class_name) + template, bool> = true> + std::shared_ptr createInstance(const std::string & class_name, Args &&... args) { CONSOLE_BRIDGE_logDebug( "class_loader::MultiLibraryClassLoader: " @@ -105,7 +109,7 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader "was explicitly loaded through MultiLibraryClassLoader::loadLibrary()"); } - return loader->createInstance(class_name); + return loader->createInstance(class_name, std::forward(args)...); } /** @@ -115,11 +119,14 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * @param Base - polymorphic type indicating base class * @param class_name - the name of the concrete plugin class we want to instantiate * @param library_path - the library from which we want to create the plugin + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) * @return A std::shared_ptr to newly created plugin */ - template + template, bool> = true> std::shared_ptr createInstance( - const std::string & class_name, const std::string & library_path) + const std::string & class_name, const std::string & library_path, Args &&... args) { ClassLoader * loader = getClassLoaderForLibrary(library_path); if (nullptr == loader) { @@ -128,7 +135,7 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader "MultiLibraryClassLoader bound to library " + library_path + " Ensure you called MultiLibraryClassLoader::loadLibrary()"); } - return loader->createInstance(class_name); + return loader->createInstance(class_name, std::forward(args)...); } /// Creates an instance of an object of given class name with ancestor class Base @@ -138,10 +145,13 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * * @param Base - polymorphic type indicating base class * @param class_name - the name of the concrete plugin class we want to instantiate + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) * @return A unique pointer to newly created plugin */ - template - ClassLoader::UniquePtr createUniqueInstance(const std::string & class_name) + template, bool> = true> + ClassLoader::UniquePtr createUniqueInstance(const std::string & class_name, Args &&... args) { CONSOLE_BRIDGE_logDebug( "class_loader::MultiLibraryClassLoader: Attempting to create instance of class type %s.", @@ -154,7 +164,7 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader "Make sure that the library exists and was explicitly loaded through " "MultiLibraryClassLoader::loadLibrary()"); } - return loader->createUniqueInstance(class_name); + return loader->createUniqueInstance(class_name, std::forward(args)...); } /// Creates an instance of an object of given class name with ancestor class Base @@ -164,11 +174,16 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * @param Base - polymorphic type indicating base class * @param class_name - the name of the concrete plugin class we want to instantiate * @param library_path - the library from which we want to create the plugin + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) * @return A unique pointer to newly created plugin */ - template + template, bool> = true> ClassLoader::UniquePtr - createUniqueInstance(const std::string & class_name, const std::string & library_path) + createUniqueInstance( + const std::string & class_name, const std::string & library_path, + Args &&... args) { ClassLoader * loader = getClassLoaderForLibrary(library_path); if (nullptr == loader) { @@ -177,7 +192,7 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader "MultiLibraryClassLoader bound to library " + library_path + " Ensure you called MultiLibraryClassLoader::loadLibrary()"); } - return loader->createUniqueInstance(class_name); + return loader->createUniqueInstance(class_name, std::forward(args)...); } /** @@ -188,17 +203,20 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * * @param Base - polymorphic type indicating base class * @param class_name - the name of the concrete plugin class we want to instantiate + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) * @return An unmanaged Base* to newly created plugin */ - template - Base * createUnmanagedInstance(const std::string & class_name) + template, bool> = true> + Base * createUnmanagedInstance(const std::string & class_name, Args &&... args) { ClassLoader * loader = getClassLoaderForClass(class_name); if (nullptr == loader) { throw class_loader::CreateClassException( "MultiLibraryClassLoader: Could not create class of type " + class_name); } - return loader->createUnmanagedInstance(class_name); + return loader->createUnmanagedInstance(class_name, std::forward(args)...); } /** @@ -209,9 +227,14 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader * @param Base - polymorphic type indicating Base class * @param class_name - name of class for which we want to create instance * @param library_path - the fully qualified path to the runtime library + * @param args - arguments for the constructor of the derived class (types defined + * by InterfaceTraits of the Base class) */ - template - Base * createUnmanagedInstance(const std::string & class_name, const std::string & library_path) + template, bool> = true> + Base * createUnmanagedInstance( + const std::string & class_name, const std::string & library_path, + Args &&... args) { ClassLoader * loader = getClassLoaderForLibrary(library_path); if (nullptr == loader) { @@ -220,7 +243,7 @@ class CLASS_LOADER_PUBLIC MultiLibraryClassLoader "bound to library " + library_path + " Ensure you called MultiLibraryClassLoader::loadLibrary()"); } - return loader->createUnmanagedInstance(class_name); + return loader->createUnmanagedInstance(class_name, std::forward(args)...); } /** diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index c57ae6e4..d9a02a42 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -15,6 +15,10 @@ add_library(${PROJECT_NAME}_TestPlugins2 EXCLUDE_FROM_ALL SHARED plugins2.cpp) target_link_libraries(${PROJECT_NAME}_TestPlugins2 ${PROJECT_NAME}) class_loader_hide_library_symbols(${PROJECT_NAME}_TestPlugins2) +add_library(${PROJECT_NAME}_TestPlugins3 EXCLUDE_FROM_ALL SHARED plugins3.cpp) +target_link_libraries(${PROJECT_NAME}_TestPlugins3 ${PROJECT_NAME}) +class_loader_hide_library_symbols(${PROJECT_NAME}_TestPlugins3) + # These plugins are loaded using dlopen() with RTLD_GLOBAL in utest and may cause side effects # in other tests if they are used elsewhere. add_library(${PROJECT_NAME}_TestGlobalPlugins EXCLUDE_FROM_ALL SHARED global_plugins.cpp) @@ -50,6 +54,7 @@ if(TARGET ${PROJECT_NAME}_utest) add_dependencies(${PROJECT_NAME}_utest ${PROJECT_NAME}_TestPlugins1 ${PROJECT_NAME}_TestPlugins2 + ${PROJECT_NAME}_TestPlugins3 ${PROJECT_NAME}_TestGlobalPlugins) endif() @@ -72,7 +77,8 @@ if(TARGET ${PROJECT_NAME}_unique_ptr_test) endif() add_dependencies(${PROJECT_NAME}_unique_ptr_test ${PROJECT_NAME}_TestPlugins1 - ${PROJECT_NAME}_TestPlugins2) + ${PROJECT_NAME}_TestPlugins2 + ${PROJECT_NAME}_TestPlugins3) endif() add_subdirectory(fviz_case_study) diff --git a/test/base.hpp b/test/base.hpp index d8f0033f..d9dc3e0d 100644 --- a/test/base.hpp +++ b/test/base.hpp @@ -30,6 +30,11 @@ #ifndef BASE_HPP_ #define BASE_HPP_ +#include +#include + +#include "class_loader/interface_traits.hpp" + // This was originally at 1000, but arm32 platforms we have tested on are not able to // successfully spin up 1000 threads in this test process. Using 500 as a reliably passing number. static constexpr size_t STRESS_TEST_NUM_THREADS = 500; @@ -41,4 +46,23 @@ class Base virtual void saySomething() = 0; }; +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; +}; + +template<> +struct class_loader::InterfaceTraits +{ + // - string to check that arguments are not mixed up with class names and + // that they do not create ambiguous calls + // - unique_ptr to check that the construction works correctly with move only types + using constructor_signature = BaseWithInterfaceCtor(std::string, std::unique_ptr); +}; + #endif // BASE_HPP_ diff --git a/test/plugins3.cpp b/test/plugins3.cpp new file mode 100644 index 00000000..6c06838b --- /dev/null +++ b/test/plugins3.cpp @@ -0,0 +1,67 @@ +/* + * 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. + */ + +#include "class_loader/register_macro.hpp" + +#include "./base.hpp" + +class Identity : public BaseWithInterfaceCtor +{ +public: + explicit Identity(std::string name, std::unique_ptr number) + : BaseWithInterfaceCtor(name), number_(*number) {} + + int get_number() override + { + return number_; + } + +private: + int number_; +}; + +class Double : public BaseWithInterfaceCtor +{ +public: + explicit Double(std::string name, std::unique_ptr number) + : BaseWithInterfaceCtor(name), number_(*number) {} + + int get_number() override + { + return 2 * number_; + } + +private: + int number_; +}; + +CLASS_LOADER_REGISTER_CLASS(Identity, BaseWithInterfaceCtor) +CLASS_LOADER_REGISTER_CLASS(Double, BaseWithInterfaceCtor) diff --git a/test/unique_ptr_test.cpp b/test/unique_ptr_test.cpp index 55a8172d..9b133ca7 100644 --- a/test/unique_ptr_test.cpp +++ b/test/unique_ptr_test.cpp @@ -45,6 +45,7 @@ const std::string LIBRARY_1 = class_loader::systemLibraryFormat("class_loader_TestPlugins1"); // NOLINT const std::string LIBRARY_2 = class_loader::systemLibraryFormat("class_loader_TestPlugins2"); // NOLINT +const std::string LIBRARY_3 = class_loader::systemLibraryFormat("class_loader_TestPlugins3"); // NOLINT using class_loader::ClassLoader; @@ -87,6 +88,25 @@ TEST(ClassLoaderUniquePtrTest, basicLoadTwiceSameTime) { } } +TEST(ClassLoaderUniquePtrTest, constructorLoad) { + try { + ClassLoader loader1(LIBRARY_3, false); + ASSERT_EQ(loader1.createUniqueInstance("Identity", "identity 1", + std::make_unique(1))->get_number(), 1); + ASSERT_EQ(loader1.createUniqueInstance("Identity", "identity 2", + std::make_unique(10))->get_number(), + 10); + ASSERT_EQ(loader1.createUniqueInstance("Double", "double 1", + std::make_unique(1))->get_number(), 2); + ASSERT_EQ(loader1.createUniqueInstance("Double", "double 2", + std::make_unique(10))->get_number(), 20); + ASSERT_NO_THROW(class_loader::impl::printDebugInfoToScreen()); + SUCCEED(); + } catch (class_loader::ClassLoaderException & e) { + FAIL() << "ClassLoaderException: " << e.what() << "\n"; + } +} + TEST(ClassLoaderUniquePtrTest, basicLoadFailures) { ClassLoader loader1(LIBRARY_1, false); ClassLoader loader2("", false); @@ -242,10 +262,20 @@ void testMultiClassLoader(bool lazy) class_loader::MultiLibraryClassLoader loader(lazy); loader.loadLibrary(LIBRARY_1); loader.loadLibrary(LIBRARY_2); + loader.loadLibrary(LIBRARY_3); for (int i = 0; i < 2; ++i) { loader.createUniqueInstance("Cat")->saySomething(); loader.createUniqueInstance("Dog")->saySomething(); loader.createUniqueInstance("Robot")->saySomething(); + ASSERT_EQ(loader.createUniqueInstance("Identity", "identity 1", + std::make_unique(1))->get_number(), 1); + ASSERT_EQ(loader.createUniqueInstance("Identity", "identity 2", + std::make_unique(10))->get_number(), + 10); + ASSERT_EQ(loader.createUniqueInstance("Double", "double 1", + std::make_unique(1))->get_number(), 2); + ASSERT_EQ(loader.createUniqueInstance("Double", "double 2", + std::make_unique(10))->get_number(), 20); } } catch (class_loader::ClassLoaderException & e) { FAIL() << "ClassLoaderException: " << e.what() << "\n"; diff --git a/test/utest.cpp b/test/utest.cpp index f83296a5..2870f6b5 100644 --- a/test/utest.cpp +++ b/test/utest.cpp @@ -49,6 +49,7 @@ const std::string LIBRARY_1 = class_loader::systemLibraryFormat("class_loader_TestPlugins1"); // NOLINT const std::string LIBRARY_2 = class_loader::systemLibraryFormat("class_loader_TestPlugins2"); // NOLINT +const std::string LIBRARY_3 = class_loader::systemLibraryFormat("class_loader_TestPlugins3"); // NOLINT // These are loaded with dlopen() and RTLD_GLOBAL in loadUnloadLoadFromGraveyard and may cause // unexpected side-effects if used elsewhere @@ -99,6 +100,25 @@ TEST(ClassLoaderTest, basicLoadTwiceSameTime) { SUCCEED(); } +TEST(ClassLoaderTest, constructorLoad) { + try { + class_loader::ClassLoader loader1(LIBRARY_3, false); + ASSERT_NO_THROW(class_loader::impl::printDebugInfoToScreen()); + ASSERT_EQ(loader1.createInstance("Identity", "identity 1", + std::make_unique(1))->get_number(), 1); + ASSERT_EQ(loader1.createInstance("Identity", "identity 2", + std::make_unique(10))->get_number(), 10); + ASSERT_EQ(loader1.createInstance("Double", "double 1", + std::make_unique(1))->get_number(), 2); + ASSERT_EQ(loader1.createInstance("Double", "double 2", + std::make_unique(10))->get_number(), 20); + } catch (class_loader::ClassLoaderException & e) { + FAIL() << "ClassLoaderException: " << e.what() << "\n"; + } + + SUCCEED(); +} + // Requires separate namespace so static variables are isolated TEST(ClassLoaderUnmanagedTest, basicLoadUnmanaged) { try { @@ -114,6 +134,23 @@ TEST(ClassLoaderUnmanagedTest, basicLoadUnmanaged) { SUCCEED(); } +// Requires separate namespace so static variables are isolated +TEST(ClassLoaderUnmanagedTest, constructorLoadUnmanaged) { + try { + class_loader::ClassLoader loader1(LIBRARY_3, false); + BaseWithInterfaceCtor * unmanaged_instance = + loader1.createUnmanagedInstance("Identity", "identity", + std::make_unique(1)); + ASSERT_NE(unmanaged_instance, nullptr); + ASSERT_EQ(unmanaged_instance->get_number(), 1); + delete unmanaged_instance; + } catch (class_loader::ClassLoaderException & e) { + FAIL() << "ClassLoaderException: " << e.what() << "\n"; + } + + SUCCEED(); +} + TEST(ClassLoaderUniquePtrTest, basicLoadFailures) { class_loader::ClassLoader loader1(LIBRARY_1, false); class_loader::ClassLoader loader2("", false); @@ -348,10 +385,19 @@ void testMultiClassLoader(bool lazy) class_loader::MultiLibraryClassLoader loader(lazy); loader.loadLibrary(LIBRARY_1); loader.loadLibrary(LIBRARY_2); + loader.loadLibrary(LIBRARY_3); for (int i = 0; i < 2; ++i) { loader.createInstance("Cat")->saySomething(); loader.createInstance("Dog")->saySomething(); loader.createInstance("Robot")->saySomething(); + ASSERT_EQ(loader.createInstance("Identity", "identity 1", + std::make_unique(1))->get_number(), 1); + ASSERT_EQ(loader.createInstance("Identity", "identity 2", + std::make_unique(10))->get_number(), 10); + ASSERT_EQ(loader.createInstance("Double", "double 1", + std::make_unique(1))->get_number(), 2); + ASSERT_EQ(loader.createInstance("Double", "double 2", + std::make_unique(10))->get_number(), 20); } } catch (class_loader::ClassLoaderException & e) { FAIL() << "ClassLoaderException: " << e.what() << "\n";