Program Listing for File KModel.h

Program Listing for File KModel.h#

Return to documentation for file (include/Karana/SOADyn/KModel.h)

/*
 * Copyright (c) 2024-2026 Karana Dynamics Pty Ltd. All rights reserved.
 *
 * NOTICE TO USER:
 *
 * This source code and/or documentation (the "Licensed Materials") is
 * the confidential and proprietary information of Karana Dynamics Inc.
 * Use of these Licensed Materials is governed by the terms and conditions
 * of a separate software license agreement between Karana Dynamics and the
 * Licensee ("License Agreement"). Unless expressly permitted under that
 * agreement, any reproduction, modification, distribution, or disclosure
 * of the Licensed Materials, in whole or in part, to any third party
 * without the prior written consent of Karana Dynamics is strictly prohibited.
 *
 * THE LICENSED MATERIALS ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND.
 * KARANA DYNAMICS DISCLAIMS ALL WARRANTIES, EXPRESS OR IMPLIED, INCLUDING
 * BUT NOT LIMITED TO WARRANTIES OF MERCHANTABILITY, NON-INFRINGEMENT, AND
 * FITNESS FOR A PARTICULAR PURPOSE.
 *
 * IN NO EVENT SHALL KARANA DYNAMICS BE LIABLE FOR ANY DAMAGES WHATSOEVER,
 * INCLUDING BUT NOT LIMITED TO LOSS OF PROFITS, DATA, OR USE, EVEN IF
 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGES, WHETHER IN CONTRACT, TORT,
 * OR OTHERWISE ARISING OUT OF OR IN CONNECTION WITH THE LICENSED MATERIALS.
 *
 * U.S. Government End Users: The Licensed Materials are a "commercial item"
 * as defined at 48 C.F.R. 2.101, and are provided to the U.S. Government
 * only as a commercial end item under the terms of this license.
 *
 * Any use of the Licensed Materials in individual or commercial software must
 * include, in the user documentation and internal source code comments,
 * this Notice, Disclaimer, and U.S. Government Use Provision.
 */

/**
 * @file
 * @brief Contains declarations for BaseKModel class, declarations and definitions for the
 * templatized KModel class, and declarations for associated classes, e.g., KModelParams,
 * KModelDiscreteStates, etc.
 */

#pragma once
#include "Karana/KCore/LockingBase.h"
#include "Karana/KCore/MsgLogger.h"
#include "Karana/SOADyn/StatePropagator.h"

namespace Karana::Models {

    namespace km = Karana::Math;
    namespace kc = Karana::Core;
    namespace kd = Karana::Dynamics;

    /** Enum for to track where a KModel output was updated */
    enum class OutputUpdateType {
        /// Output was updated before the hop.
        PRE_HOP,

        /// Output was updated before the derivative call but post-hop start.
        PRE_DERIV,

        /// Output was updated after the derivative call.
        POST_DERIV,

        /// Output was updated at the end of the hop.
        POST_HOP
    };

    /**
     * @class BaseKModel
     * @brief This BaseKModel serves as the base for all models. It implements common logic,
     * methods, etc. for both C++ and Python models. Determining which methods have been overloaded
     * is handled by the KModel classes. In C++ this is uses the curiously-recurring template
     * pattern (CRTP) and in Python we use object attributes. See the \sref{kmodels_sec} section for
     * more discussion about the KModel class.
     */
    class BaseKModel : public Karana::Core::LockingBase {
        // For access to _registerModel and _unregisterModel
        friend class kd::ModelManager;

        // For access to _setContinuousStates
        friend class kd::StatePropagator;

      public:
        /**
         * @brief BaseKModel constructor. The constructor is not meant to be called directly.
         *        Please use the create(...) method instead to create an instance.
         *
         * @param name - The name of the model
         * @param mm - The ModelManager associated with the model.
         */
        BaseKModel(std::string_view name, const kc::ks_ptr<kd::ModelManager> &mm);

        /**
         * @brief Get the next step time assuming that the provided time t is a time the model has a
         * step at.
         *
         * @param t - A time the model has a step at.
         * @return The next step time. If std::nullopt, then the model has no more step times.
         */
        virtual std::optional<km::Ktime> getNextModelStepTime(const km::Ktime &t) = 0;

        /**
         * @brief If a nextModelStepTime method exists, then this returns a warning. A model period
         * and nextModelStepTime cannot both be defined for a model.
         * @returns The model's period.
         */
        virtual km::Ktime getPeriod() = 0;

        /**
         * @brief The model_period defines the period at which the model runs. There are a few cases
         * to consider:
         *        1. The period is 0 and no nextModelStepTime method is defined. In this case, the
         * begin/postModelStep methods will run every time a simulation hop happens.
         *        2. The period is non-zero. In this case, the begin/postModelStep methods will run
         * at the specified period.
         *        3. The period is 0 and a nextModelStepTime method is defined. In this case, the
         * nextModelStepTime defines when these methods will run.
         * A model period and nextModelStepTime cannot both be defined for a model. If one tries to
         * set a model period for a model which has a nextModelStepTime, then an error will be
         * thrown.
         * @param t - The new model period.
         */
        virtual void setPeriod(const km::Ktime &t) = 0;

        /// The StatePropagator associated with this KModel.
        kc::ks_ptr<kd::ModelManager> model_manager;

        /// debug_model is a member variable used to enable/disable debug statements for this model.
        bool debug_model = false;

        /**
         * @brief Print a standard debug message.
         *
         * This creates json with debug information and passes it to the debug logger.
         *
         * @param msg The message to log.
         */
        virtual void stdDebugMsg(std::string_view msg);

      protected:
        /**
         * @brief Register the model with StatePropagator.
         */
        virtual void _registerModel() = 0;

        /**
         * @brief Unregister the model with the StatePropagator.
         */
        virtual void _unregisterModel() = 0;

        /**
         * @brief The model_period defines the period at which the model runs. There are a few cases
         * to consider:
         *        1. The period is 0 and no nextModelStepTime method is defined. In this case, the
         * begin/postModelStep methods will run every time a simulation hop happens.
         *        2. The period is non-zero. In this case, the begin/postModelStep methods will run
         * at the specified period.
         *        3. The period is 0 and a nextModelStepTime method is defined. In this case, the
         * nextModelStepTime defines when these methods will run.
         */
        km::Ktime _period{0};

        /// Boolean to track whether this model has been registered or not
        bool _registered = false;

        /// Boolean to track whether this model has continuous states or not. This is set in
        /// _registerModel.
        bool _has_continuous_states = false;

        /**
         * @brief Get model continuous states. Overridden by KModel if appropriate.
         * @returns The model's continuous states.
         */
        virtual const Eigen::Ref<const km::Vec> _getContinuousStates() const = 0;

        /**
         * @brief Get the derivative of the continuous states. Overridden by KModel if appropriate.
         * @returns The model's continuous states' derivatives.
         */
        virtual const Eigen::Ref<const km::Vec> _getContinuousStatesDeriv() = 0;

        /**
         * @brief Set the continuous model states.
         *
         * @param x The new continuous model states.
         */
        virtual void _setContinuousStates(const Eigen::Ref<const km::Vec> x) = 0;
    };

    /**
     * @class KModelParams
     * @brief A base class for model params. Derive from this and add any parameters for your model.
     *        Override the isReady method to check whether the parameters are set. See the
     * \sref{kmodel_params_sec} section for more discussion about the KModel class.
     */
    class KModelParams : public Karana::Core::Base {
      public:
        /**
         * @brief Constructor
         * @param name the model param name
         */
        KModelParams(std::string_view name)
            : Base(name){};

        bool isReady() const override {
            kc::warn("Your model params class does not override isReady. It should do this to "
                     "ensure all your "
                     "parameters are ready.");
            return true;
        };
    };

    /**
     * @class KModelDiscreteStates
     * @brief A base class for discrete model states. Derive from this and add any parameters for
     * your model. Override the isReady method to check whether the discrete states are set. See
     * the \sref{kmodel_discrete_states_sec} section for more discussion about the KModel class.
     */
    class KModelDiscreteStates : public Karana::Core::Base {
      public:
        /**
         * @brief Constructor
         * @param name the discrete model states
         */
        KModelDiscreteStates(std::string_view name)
            : Base(name){};

        bool isReady() const override {
            kc::warn("Your discrete model states class does not override isReady. It should do "
                     "this to "
                     "ensure it is ready.");
            return true;
        }
    };

    /**
     * @class KModelContinuousStates
     * @brief A base class for continuous model states. Derive from this and add any continuous
     * states for your model.
     *
     * Override the isReady method to check whether the continuous states
     * are set. Override the setX and getX to set and get the model continuous states.
     * Whenever the number of continuous states changes (the length of the vector from
     * getX changes), you MUST re-register the model. Neglecting to do so leads to
     * undefined behavior.
     * See the \sref{kmodel_continuous_states_sec} section for more discussion about the KModel
     * class.
     */
    class KModelContinuousStates : public Karana::Core::Base {
      public:
        /**
         * @brief Constructor
         * @param name the continuous model states
         */
        KModelContinuousStates(std::string_view name)
            : Base(name){};

        bool isReady() const override {
            kc::warn("Your continuous model states class does not override isReady. It should "
                     "do this to "
                     "ensure it is ready.");
            return true;
        }

        /**
         * @brief Get the continuous model states.
         *
         * @return The continuous model states.
         */
        virtual const Eigen::Ref<const km::Vec> getX() const = 0;

        /**
         * @brief Get the derivative of the continuous model states.
         *
         * @return The continuous model states' derivatives.
         */
        virtual const Eigen::Ref<const km::Vec> getdX() = 0;

        /**
         * @brief Set the continuous model states.
         *
         * @param x The new continuous model states.
         */
        virtual void setX(const Eigen::Ref<const km::Vec> x) = 0;
    };

    /**
     * @class KModelScratch
     * @brief A scratchpad to store model information. This is primarily used for debugging
     * purposes. See the \sref{kmodel_scratch_sec} section for more discussion about the KModel
     * class.
     */
    class KModelScratch : public Karana::Core::Base {
      public:
        /**
         * @brief Constructor
         * @param name the model scratch name
         */
        KModelScratch(std::string_view name)
            : Base(name){};
    };

#ifndef PYBIND11_MKDOC_SKIP
    /**
     * @brief Used to determine if a class has a preDeriv method defined.
     */
    template <typename T>
    concept HasPreDeriv = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.preDeriv(ti, x) } -> std::same_as<void>;
    };

    /**
     * @brief Used to determine if a class has a preDeriv method defined.
     */
    template <typename T>
    concept HasPostDeriv = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.postDeriv(ti, x) } -> std::same_as<void>;
    };

    /**
     * @brief Used to determine if a class has a preModelStep method defined.
     */
    template <typename T>
    concept HasPreModelStep = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.preModelStep(ti, x) } -> std::same_as<void>;
    };

    /**
     * @brief Used to determine if a class has a postModelStep method defined.
     */
    template <typename T>
    concept HasPostModelStep = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.postModelStep(ti, x) } -> std::same_as<void>;
    };

    /**
     * @brief Used to determine if a class has a nextModelStepTime method defined.
     */
    template <typename T>
    concept HasNextModelStepTime = requires(T t, const km::Ktime &ti) {
        { t.nextModelStepTime(ti) } -> std::same_as<std::optional<km::Ktime>>;
    };

    /**
     * @brief Used to determine if a class has a preHop method defined.
     */
    template <typename T>
    concept HasPreHop = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.preHop(ti, x) } -> std::same_as<void>;
    };

    /**
     * @brief Used to determine if a class has a postHop method defined.
     */
    template <typename T>
    concept HasPostHop = requires(T t, const km::Ktime &ti, const km::Vec &x) {
        { t.postHop(ti, x) } -> std::same_as<void>;
    };
#endif

    class NoParams : public KModelParams {};
    class NoScratch : public KModelScratch {};
    class NoDiscreteStates : public KModelDiscreteStates {};
    class NoContinuousStates : public KModelContinuousStates {};

    /** KModel<T,P,Sc,S,C> uses the curiously recurring template pattern (CRTP) to determine what
     methods the derived class has, and make the appropriate calls. All C++ models should derive
     from this. Python models will have a different class to derive from. See the \sref{kmodels_sec}
     section for more discussion about the KModel class.
     */
    template <class T,
              class P = NoParams,
              class Sc = NoScratch,
              class S = NoDiscreteStates,
              class C = NoContinuousStates>
    class KModel : public BaseKModel {

#ifndef PYBIND11_MKDOC_SKIP
        static_assert(
            std::is_base_of_v<KModelParams, P> and not std::is_same_v<KModelParams, P>,
            "The second template parameter (the param class), must be derived from KModelParams, "
            "but must not be KModelParams itself (use NoParams if the model has no params).");
        static_assert(std::is_base_of_v<KModelScratch, Sc> and
                          not std::is_same_v<KModelScratch, Sc>,
                      "The third template parameter (the model scratch class), must be derived "
                      "from KModelScratch, but must not be KModelScratch itself (use NoScratch if "
                      "the model has no scratch).");
        static_assert(
            std::is_base_of_v<KModelDiscreteStates, S> and
                not std::is_same_v<KModelDiscreteStates, S>,
            "The fourth template parameter (the discrete model states class), must be derived from "
            "KModelDiscreteStates, but must not be KModelDiscreteStates itself (use "
            "NoDiscreteStates "
            "if the model has no discrete states).");
        static_assert(std::is_base_of_v<KModelContinuousStates, C> and
                          not std::is_same_v<KModelContinuousStates, C>,
                      "The fifth template parameter (the continuous model states class), must be "
                      "derived from KModelContinuousStates, but must not be KModelContinuousStates "
                      "itself (use NoContinuousStates if the model has no continuous states).");
#endif
      public:
        using BaseKModel::BaseKModel;

        /// The parameters for the model.
        kc::ks_ptr<P> params = nullptr;

        /// The scratch for the model.
        kc::ks_ptr<Sc> scratch = nullptr;

        /// The discrete states for the model.
        kc::ks_ptr<S> discrete_states = nullptr;

        /// The continuous states for the model.
        kc::ks_ptr<C> continuous_states = nullptr;

        /**
         * @brief Checks whether the model is ready.
         * @return bool - Returns false if the params pointer is empty
         *                 or if the parameters are not finalize. Returns true otherwise.
         */
        bool isReady() const override {
            bool ready = true;

            // If P is not KModelParams, then call isReady on it. Otherwise, just return true.
            if constexpr (not std::is_same_v<NoParams, P>) {
                if (params) {
                    if (not params->isReady()) {
                        ready = false;
                    }
                } else {
                    kc::warn("The params class for model {} is {} (so params should be defined), "
                             "but it is currently a nullptr.",
                             name(),
                             typeid(P).name());
                    ready = false;
                }
            }

            // If Sc is not KModelScratch, then call isReady on it. Otherwise, just return true.
            if constexpr (not std::is_same_v<NoScratch, Sc>) {
                if (scratch) {
                    if (not scratch->isReady()) {
                        ready = false;
                    }
                } else {
                    kc::warn("The scratch class for model {} is {} (so scratch should be defined), "
                             "but it is currently a nullptr.",
                             name(),
                             typeid(Sc).name());
                    ready = false;
                }
            }

            // If S is not KModelDiscreteStates, then call isReady on it. Otherwise, just return
            // true.
            if constexpr (not std::is_same_v<NoDiscreteStates, S>) {
                if (discrete_states) {
                    if (not discrete_states->isReady()) {
                        ready = false;
                    }
                } else {
                    kc::warn("The discrete states class for model {} is {} (so discrete states "
                             "should be defined), "
                             "but it is currently a nullptr.",
                             name(),
                             typeid(S).name());
                    ready = false;
                }
            }

            // If C is not KModelContinuousStates, then call isReady on it. Otherwise, just
            // return true.
            if constexpr (not std::is_same_v<NoContinuousStates, C>) {
                if (continuous_states) {
                    if (not continuous_states->isReady()) {
                        ready = false;
                    }
                } else {
                    kc::warn("The continuous model states class for model {} is {} (so continuous "
                             "states should be defined), but it is currently a nullptr.",
                             name(),
                             typeid(C).name());
                    ready = false;
                }
            }

            // Check if we registered a post model step event if appropriate
            if constexpr (HasPostModelStep<T>) {
                if (not model_manager->hasRegisteredTimedEvent(
                        std::format("{}_post_model_step_{}", name(), id()), false)) {
                    kc::warn("A postModelStep method is defined, but the period is 0 nor does the "
                             "model have a nextModelStepTime method that returns a Ktime. "
                             "Therefore, this method will "
                             "never be run.");
                    ready = false;
                }
            }

            if constexpr (HasPreModelStep<T>) {
                if (not model_manager->hasRegisteredTimedEvent(
                        std::format("{}_pre_model_step_{}", name(), id()), true)) {
                    kc::warn("A preModelStep method is defined, but the period is 0 not does the "
                             "model have a nextModelStepTime method that returns a Ktime. "
                             "Therefore, this method will "
                             "never be run.");
                    ready = false;
                }
            }

            return ready;
        };

        /**
         * @brief Get the model's next time step after t.
         * @param t The t to use when calculating the next time step.
         * @return The model's next time step.
         */
        std::optional<km::Ktime> getNextModelStepTime(const km::Ktime &t) final {
#ifndef PYBIND11_MKDOC_SKIP
            if constexpr (HasNextModelStepTime<T>) {
                return static_cast<T *>(this)->nextModelStepTime(t);
            } else {
                return t + _period;
            }
#endif
        }

        /**
         * @brief Get the model's period.
         * @returns The model's period.
         */
        km::Ktime getPeriod() final override {
#ifndef PYBIND11_MKDOC_SKIP
            if constexpr (HasNextModelStepTime<T>) {
                kc::warn("A nextModelStepTime is defined for model {}. Returning -1.", name());
                return km::Ktime{-1};
            } else {
                return _period;
            }
#endif
        }

        /**
         * @brief Set the model's period.
         * @param t - The value to set the model's period to.
         */
        void setPeriod(const km::Ktime &t) override {
#ifndef PYBIND11_MKDOC_SKIP
            if constexpr (HasNextModelStepTime<T>) {
                throw std::invalid_argument("Cannot set the model period for model {}, as it has a "
                                            "nextModelStepTime method.");
            } else {
                if (t <= km::Ktime{0}) [[unlikely]] {
                    throw std::invalid_argument(
                        std::format("Cannot set the period to something <= 0. Got {}", _period));
                }
                if (_period <= km::Ktime{0}) {
                    // If the period is <= 0 currently, then we need to re-register the model,
                    // as this may change how it is registered.
                    _period = t;

                    // If the model is already registered, then unregister it and re-register it.
                    if (_registered) {
                        kc::ks_ptr<BaseKModel> this_mod = kc::static_pointer_cast<BaseKModel>(
                            kc::ks_ptr<Base>(shared_from_this()));
                        model_manager->unregisterModel(this_mod);
                        model_manager->registerModel(this_mod);
                    }
                } else {
                    // Otherwise, just modify the period. This will affect the already-registered
                    // timed events if this model is registered, so need to re-register.
                    _period = t;
                }
            }
#endif
        }

      protected:
        /**
         * @brief Register this model instance with the state propagator. See the
         * \sref{model_register_sec} for details.
         */
        void _registerModel() override {
#ifndef PYBIND11_MKDOC_SKIP
            if (_registered) {
                kc::warn("Model {} has already been registered. Doing nothing.", name());
                return;
            }

            // If we have continuous states, than mark this model as such.
            if constexpr (not std::is_same_v<NoContinuousStates, C>) {
                _has_continuous_states = true;
            }

            // any_methods_registered is used to decide if we should trigger an error if at least
            // one of the methods affecting the sim is defined.
            bool any_methods_registered = false;

            if constexpr (HasPreDeriv<T>) {
                kc::trace("Registering preDeriv for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                model_manager->fns.pre_deriv_fns[std::format("{}_pre_deriv_{}", name(), id())] =
                    [t](const km::Ktime &ti, const km::Vec &x) { return t->preDeriv(ti, x); };
            };
            if constexpr (HasPostDeriv<T>) {
                kc::trace("Registering postDeriv for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                model_manager->fns.post_deriv_fns[std::format("{}_post_deriv_{}", name(), id())] =
                    [t](const km::Ktime &ti, const km::Vec &x) { return t->postDeriv(ti, x); };
            };

            if constexpr (HasPreHop<T>) {
                kc::trace("Registering preHop for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                model_manager->fns.pre_hop_fns[std::format("{}_pre_hop_{}", name(), id())] =
                    [t](const km::Ktime &ti, const km::Vec &x) { return t->preHop(ti, x); };
            }

            if constexpr (HasPostHop<T>) {
                kc::trace("Registering postHop for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                model_manager->fns.post_hop_fns[std::format("{}_post_hop_{}", name(), id())] =
                    [t](const km::Ktime &ti, const km::Vec &x) { return t->postHop(ti, x); };
            }

            if constexpr (HasNextModelStepTime<T>) {
                kc::trace("nextHopEndTime exists for model {} and will be used over the period.",
                          name());
            }

            if constexpr (HasPreModelStep<T>) {
                kc::trace("Registering preModelStep for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                if constexpr (HasNextModelStepTime<T>) {
                    // Register a timed event that uses the nextModelStepTime as the reschedule
                    // method.
                    auto te = kd::TimedEvent::create(
                        std::format("{}_pre_model_step_{}", name(), id()),
                        model_manager->_time_keeper->getTime(),
                        [t](const km::Ktime &) {
                            return t->preModelStep(t->model_manager->_time_keeper->getTime(),
                                                   t->model_manager->_curr_X);
                        },
                        true);
                    te->reschedule_fn = [t](const km::Ktime &ti) {
                        return t->nextModelStepTime(ti);
                    };
                    model_manager->registerTimedEvent(te);
                } else if (_period > km::Ktime{0}) {
                    // Register a timed event that uses the period.
                    auto te = kd::TimedEvent::create(
                        std::format("{}_pre_model_step_{}", name(), id()),
                        model_manager->_time_keeper->getTime(),
                        [t](const km::Ktime &) {
                            return t->preModelStep(t->model_manager->_time_keeper->getTime(),
                                                   t->model_manager->_curr_X);
                        },
                        true);
                    te->reschedule_fn = [t](const km::Ktime &ti) { return ti + t->_period; };
                    model_manager->registerTimedEvent(te);
                }
            };

            if constexpr (HasPostModelStep<T>) {
                kc::trace("Registering postModelStep for model {}.", name());
                any_methods_registered = true;
                kc::ks_ptr<Base> dark = shared_from_this();
                kc::ks_ptr<T> t = kc::static_pointer_cast<T>(dark);
                if constexpr (HasNextModelStepTime<T>) {
                    if (auto next_time = t->nextModelStepTime(model_manager->getTime());
                        next_time) {
                        // Register a timed event that uses the nextModelStepTime as the reschedule
                        // method.
                        auto te = kd::TimedEvent::create(
                            std::format("{}_post_model_step_{}", name(), id()),
                            next_time.value(),
                            [t](const km::Ktime &) {
                                return t->postModelStep(t->model_manager->_time_keeper->getTime(),
                                                        t->model_manager->_curr_X);
                            },
                            false);
                        te->reschedule_fn = [t](const km::Ktime &ti) {
                            return t->nextModelStepTime(ti);
                        };
                        model_manager->registerTimedEvent(te);
                    }
                } else if (_period > km::Ktime{0}) {
                    // Register a timed event that uses the period.
                    auto te = kd::TimedEvent::create(
                        std::format("{}_post_model_step_{}", name(), id()),
                        model_manager->getTime() + _period,
                        [t](const km::Ktime &) {
                            return t->postModelStep(t->model_manager->_time_keeper->getTime(),
                                                    t->model_manager->_curr_X);
                        },
                        false);
                    te->reschedule_fn = [t](const km::Ktime &ti) { return ti + t->_period; };
                    model_manager->registerTimedEvent(te);
                }
            };

            if (not any_methods_registered) {
                throw std::invalid_argument(std::format(
                    "Model \"{}\" did not define any of: preDeriv, postDeriv, preHop, postHop,"
                    " preModelStep, or postModelStep. Must define one of those methods.",
                    name()));
            }

            // Mark this model as registered
            _registered = true;
#endif
        }

        /**
         * @brief Unregister this model instance from the state propagator. See the
         * \sref{model_register_sec} for details.
         */
        void _unregisterModel() override {
#ifndef PYBIND11_MKDOC_SKIP
            if (not _registered) {
                kc::warn("Model {} is not registered. Doing nothing.", name());
                return;
            }

            if constexpr (HasPreDeriv<T>) {
                kc::trace("Unregistering preDeriv for model {}.", name());
                model_manager->fns.pre_deriv_fns.erase(
                    std::format("{}_pre_deriv_{}", name(), id()));
            }
            if constexpr (HasPostDeriv<T>) {
                kc::trace("Unregistering postDeriv for model {}.", name());
                model_manager->fns.post_deriv_fns.erase(
                    std::format("{}_post_deriv_{}", name(), id()));
            }

            if constexpr (HasPreHop<T>) {
                kc::trace("Unregistering preHop for model {}.", name());
                model_manager->fns.pre_hop_fns.erase(std::format("{}_pre_hop_{}", name(), id()));
            }

            if constexpr (HasPostHop<T>) {
                kc::trace("Unregistering postHop for model {}.", name());
                model_manager->fns.post_hop_fns.erase(std::format("{}_post_hop_{}", name(), id()));
            }

            if constexpr (HasPreModelStep<T>) {
                kc::trace("Unregistering preModelStep for model {}.", name());
                if constexpr (HasNextModelStepTime<T>) {
                    // It's possible this will have already been removed if the nextModelStepTime
                    // ever returned 0.
                    model_manager->unregisterTimedEvent(
                        std::format("{}_pre_model_step_{}", name(), id()), true, true);
                } else if (_period > km::Ktime{0}) {
                    // It's possible this will have already been removed if the user changed the
                    // period at some point.
                    model_manager->unregisterTimedEvent(
                        std::format("{}_pre_model_step_{}", name(), id()), true, true);
                }
            }

            if constexpr (HasPostModelStep<T>) {
                kc::trace("Unregistering postModelStep for model {}.", name());
                if constexpr (HasNextModelStepTime<T>) {
                    model_manager->unregisterTimedEvent(
                        std::format("{}_post_model_step_{}", name(), id()), false, true);
                } else if (_period > km::Ktime{0}) {
                    // It's possible this will have already been removed if the user changed the
                    // period at some point.
                    model_manager->unregisterTimedEvent(
                        std::format("{}_post_model_step_{}", name(), id()), false, true);
                }
            }

            // Mark this model as not registered
            _registered = false;
#endif
        }

        const Eigen::Ref<const km::Vec> _getContinuousStates() const override {
            if constexpr (not std::is_same_v<KModelContinuousStates, C>) {
                return continuous_states->getX();
            } else {
                throw std::runtime_error("_getContinuousStates called on a non-continuous model.");
            }
        }

        const Eigen::Ref<const km::Vec> _getContinuousStatesDeriv() override {
            if constexpr (not std::is_same_v<KModelContinuousStates, C>) {
                return continuous_states->getdX();
            } else {
                throw std::runtime_error(
                    "_getContinuousStatesDeriv called on a non-continuous model.");
            }
        }

        void _setContinuousStates(const Eigen::Ref<const km::Vec> x) override {
            if constexpr (not std::is_same_v<KModelContinuousStates, C>) {
                return continuous_states->setX(x);
            } else {
                throw std::runtime_error("_setContinuousStates called on a non-continuous model.");
            }
        }

        std::string
        dumpString(std::string_view prefix = "",
                   const Karana::Core::Base::DumpOptions * /*options*/ = nullptr) const override {

            std::string result =
                std::format("{}Dumping model '{}' ({})\n", prefix, name(), typeString());

            // If P is not KModelParams, then get its dumpString. Otherwise, skip it.
            if constexpr (not std::is_same_v<NoParams, P>) {
                result.append(std::format("{}    Model Params:\n", prefix));
                result.append(params->dumpString(std::format("{}        ", prefix)));
            }

            // If Sc is not KModelScratch, then get its dumpString. Otherwise, skip it.
            if constexpr (not std::is_same_v<NoScratch, Sc>) {
                result.append(std::format("{}    Model Scratch:\n", prefix));
                result.append(scratch->dumpString(std::format("{}        ", prefix)));
            }

            // If S is not KModelDiscreteStates, then get its dumpString. Otherwise, skip it.
            if constexpr (not std::is_same_v<NoDiscreteStates, S>) {
                result.append(std::format("{}    Model Discrete States:\n", prefix));
                result.append(discrete_states->dumpString(std::format("{}        ", prefix)));
            }

            // If C is not KModelContinuousStates, then get its dumpString. Otherwise, skip it.
            if constexpr (not std::is_same_v<NoContinuousStates, C>) {
                result.append(std::format("{}    Model Continuous States:\n", prefix));
                result.append(continuous_states->dumpString(std::format("{}        ", prefix)));
            }

            return result;
        }
    };

} // namespace Karana::Models