Program Listing for File ExecutableBase.h

Return to documentation for file (include/mola_kernel/interfaces/ExecutableBase.h)

/* -------------------------------------------------------------------------
 *   A Modular Optimization framework for Localization and mApping  (MOLA)
 * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
 * See LICENSE for license information.
 * ------------------------------------------------------------------------- */
#pragma once

#include <mola_kernel/Yaml.h>
#include <mrpt/rtti/CObject.h>
#include <mrpt/system/COutputLogger.h>
#include <mrpt/system/CTimeLogger.h>

#include <functional>
#include <memory>
#include <mutex>
#include <optional>
#include <string>
#include <vector>

namespace mola
{
using Profiler            = mrpt::system::CTimeLogger;
using ProfilerEntry       = mrpt::system::CTimeLoggerEntry;
using ProfilerSaverAtDtor = mrpt::system::CTimeLoggerSaveAtDtor;

class ExecutableBase : public mrpt::system::COutputLogger,  // for logging
                       public mrpt::rtti::CObject,  // RTTI helpers
                       std::enable_shared_from_this<ExecutableBase>
{
    // This macro defines `Ptr=shared_ptr<T>`, among other types and methods.
    DEFINE_VIRTUAL_MRPT_OBJECT(ExecutableBase)

   public:
    ExecutableBase();
    virtual ~ExecutableBase();

    static Ptr Factory(const std::string& classname);

    Ptr getAsPtr() { return shared_from_this(); }

    virtual void initialize(const Yaml& cfg) = 0;

    virtual void spinOnce() = 0;

    virtual int launchOrderPriority() const { return 50; }

    virtual void onQuit() {}
    std::function<Ptr(const std::string&)> nameServer_;

    template <class Interface>
    std::vector<Ptr> findService() const;

    void        setModuleInstanceName(const std::string& s);
    std::string getModuleInstanceName() const;
    std::optional<ProfilerSaverAtDtor> profiler_dtor_save_stats_;

    Profiler profiler_{false};

    [[nodiscard]] bool requestedShutdown() const
    {
        auto lck = mrpt::lockHelper(requested_system_shutdown_mtx_);
        return requested_system_shutdown_;
    }

   protected:
    void requestShutdown()
    {
        auto lck = mrpt::lockHelper(requested_system_shutdown_mtx_);
        requested_system_shutdown_ = true;
    }

   private:
    std::string module_instance_name{"unnamed"};
    bool        requested_system_shutdown_ = false;
    std::mutex  requested_system_shutdown_mtx_;
};

// Impl:
template <class Interface>
std::vector<ExecutableBase::Ptr> ExecutableBase::findService() const
{
    std::vector<ExecutableBase::Ptr> ret;
    if (!nameServer_) return ret;
    for (size_t idx = 0;; ++idx)
    {
        using namespace std::string_literals;
        const auto req = "["s + std::to_string(idx);
        auto       mod = nameServer_(req);
        if (!mod) break;  // end of list of modules
        if (std::dynamic_pointer_cast<Interface>(mod))
            ret.emplace_back(std::move(mod));
    }
    return ret;
}

#define MOLA_REGISTER_MODULE(_classname) \
    mrpt::rtti::registerClass(CLASS_ID(_classname))

}  // namespace mola