Program Listing for File MolaLauncherApp.h

Return to documentation for file (include/mola_launcher/MolaLauncherApp.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/interfaces/ExecutableBase.h>
#include <mrpt/containers/yaml.h>
#include <mrpt/system/COutputLogger.h>
#include <mrpt/system/CTimeLogger.h>

#include <atomic>
#include <condition_variable>
#include <map>
#include <thread>
#include <vector>

namespace mola
{
class MolaLauncherApp : public mrpt::system::COutputLogger
{
   public:
    MolaLauncherApp();
    virtual ~MolaLauncherApp();

    void setup(
        const mrpt::containers::yaml&     cfg,
        const std::optional<std::string>& basePath = std::nullopt);

    void spin();

    void shutdown();

    void addPathModuleLibs(const std::string& path);

    void addPathModuleSources(const std::string& path);

    std::vector<std::string> getModuleLibPaths() const
    {
        return lib_search_paths_;
    }

    std::vector<std::string> getModuleSourcePaths() const
    {
        return shared_search_paths_;
    }

    std::vector<std::string> getLoadedModules();

    std::string findModuleSharedDir(const std::string& moduleName) const;

    void scanAndLoadLibraries();

    using module_name_t        = std::string;
    using module_shared_path_t = std::string;

    std::map<module_name_t, module_shared_path_t>
        scanForModuleSharedDirectories() const;

    mrpt::system::CTimeLogger profiler_{true, "MolaLauncherApp"};

    std::optional<ProfilerSaverAtDtor> profiler_dtor_save_stats_;

    struct Parameters
    {
        bool enforce_initialize_one_at_a_time{false};
    };

    Parameters launcher_params_;

   private:
    struct InfoPerRunningThread
    {
        Yaml                yaml_cfg_block;
        ExecutableBase::Ptr impl;
        std::thread         executor;
        std::string         name;
        double              execution_rate{10.0};
        int                 launch_priority{0};
        std::atomic_bool    initialization_done{false};
        std::atomic_bool    this_thread_must_end{false};
    };
    std::map<std::string, InfoPerRunningThread> running_threads_;

    std::condition_variable thread_launch_condition_;
    std::mutex thread_launch_init_mtx_;

    std::atomic<int> pending_initializations_{0};

    void executor_thread(InfoPerRunningThread& rds);

    std::atomic_bool threads_must_end_{false};
    std::thread::id  spin_thread_id_;
    std::atomic_bool spin_is_running_{false};

    std::vector<std::string> lib_search_paths_{};

    std::vector<std::string> shared_search_paths_{};

    ExecutableBase::Ptr nameServerImpl(const std::string& name);

    void internal_spin_tasks();

    template <typename T>
    void stopAllThreadsOfType()
    {
        // signal them to end:
        for (auto& th : running_threads_)
        {
            InfoPerRunningThread& rds = th.second;
            if (auto p = dynamic_cast<T*>(rds.impl.get()); p != nullptr)
            {
                if (!rds.executor.joinable() || rds.this_thread_must_end)
                    continue;  // nothing to do

                rds.this_thread_must_end = true;
                MRPT_LOG_DEBUG_FMT(
                    "stopAllThreadsOfType<>: Requesting end of thread '%s'.",
                    rds.name.c_str());
                // and wait for them:
                if (rds.executor.joinable())
                {
                    rds.executor.join();
                    MRPT_LOG_DEBUG_FMT(
                        "stopAllThreadsOfType<>: thread '%s' successfully "
                        "ended.",
                        rds.name.c_str());
                }
            }
        }
        MRPT_LOG_DEBUG("stopAllThreadsOfType<> done.");
    }
};

}  // namespace mola