diff --git a/docs/source/Support/bskReleaseNotes.rst b/docs/source/Support/bskReleaseNotes.rst
index 1545321ebc..8848334a03 100644
--- a/docs/source/Support/bskReleaseNotes.rst
+++ b/docs/source/Support/bskReleaseNotes.rst
@@ -108,6 +108,15 @@ Version |release|
``pyStatefulSysModel.i`` to use this mixin.
- Added support for setting the position and velocity of :ref:`MJBody` with pure translational motion.
- Added ``getAxis`` and ``isHinge`` to :ref:`MJJoint`.
+- Added :ref:`linearTimeInvariantSystem`. This module implements a linear time-invariant
+ system using state-space representation. It can be used to model linear systems in the dynamics task of
+ ``MJScene``. This model is abstract: subclasses must specify how the input vector is
+ read from input messages, and the output vector is written to output messages. Subclasses
+ can be implemented in Python.
+- Added :ref:`singleActuatorLTI`: a single-input single-output subclass of :ref:`linearTimeInvariantSystem`
+ whose input and output is a :ref:`SingleActuatorMsgPayload`.
+- Added :ref:`forceAtSiteLTI`: a subclass of :ref:`linearTimeInvariantSystem` whose input vector
+ is read from a :ref:`ForceAtSiteMsgPayload` and output vector is written to a :ref:`ForceAtSiteMsgPayload`.
Version 2.8.0 (August 30, 2025)
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/_UnitTest/test_linearTimeInvariantSystem.py b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/_UnitTest/test_linearTimeInvariantSystem.py
new file mode 100644
index 0000000000..5001d9ad2c
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/_UnitTest/test_linearTimeInvariantSystem.py
@@ -0,0 +1,263 @@
+#
+# ISC License
+#
+# Copyright (c) 2025, Autonomous Vehicle Systems Lab, University of Colorado at Boulder
+#
+# Permission to use, copy, modify, and/or distribute this software for any
+# purpose with or without fee is hereby granted, provided that the above
+# copyright notice and this permission notice appear in all copies.
+#
+# THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+# WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+# MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+# ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+# WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+# ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+# OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+import pytest
+import numpy as np
+import numpy.testing as npt
+import matplotlib.pyplot as plt
+
+from Basilisk.utilities import SimulationBaseClass
+from Basilisk.architecture import messaging
+from Basilisk.utilities import macros
+
+try:
+ from Basilisk.simulation import mujoco
+ from Basilisk.simulation import MJLinearTimeInvariantSystem
+ couldImportMujoco = True
+except Exception:
+ couldImportMujoco = False
+
+
+@pytest.mark.skipif(not couldImportMujoco, reason="Compiled Basilisk without --mujoco")
+@pytest.mark.parametrize("usePythonSubclass", [False, True])
+def test_linearTimeInvariantSystemFirstOrder(usePythonSubclass: bool,
+ showPlots: bool = False):
+ """
+ Unit test for LinearTimeInvariantSystem:
+
+ - When usePythonSubclass == False:
+ Uses the C++ SingleActuatorLTI subclass.
+
+ - When usePythonSubclass == True:
+ Uses a Python subclass of LinearTimeInvariantSystem that overrides
+ readInput and writeOutput via directors.
+
+ Both implement the same first order system:
+
+ x_dot = -a x + a u, y = x, u = 1 (constant step)
+
+ so that in continuous time:
+
+ x(t) = 1 - exp(-a t)
+ """
+ # Simulation setup
+ dt = 0.01 # s
+ tf = 2.0 # s
+
+ # First order dynamics parameter
+ a = 1.0 # 1/s; time constant tau = 1/a = 1 s
+
+ scSim = SimulationBaseClass.SimBaseClass()
+ dynProcess = scSim.CreateNewProcess("test")
+ dynProcess.addTask(scSim.CreateNewTask("test", macros.sec2nano(dt)))
+
+ # Empty MuJoCo scene: just a container for system models
+ scene = mujoco.MJScene("")
+ scSim.AddModelToTask("test", scene)
+
+ # Constant input message u = 1.0
+ cmdMsg = messaging.SingleActuatorMsg()
+ cmdPayload = messaging.SingleActuatorMsgPayload()
+ cmdPayload.input = 1.0
+ cmdMsg.write(cmdPayload)
+
+ if usePythonSubclass:
+ # Python subclass of LinearTimeInvariantSystem
+ class PyFirstOrderLTI(MJLinearTimeInvariantSystem.LinearTimeInvariantSystem):
+ def __init__(self):
+ super().__init__()
+ # Input/output messaging
+ self.inMsg = messaging.SingleActuatorMsgReader()
+ self.outMsg = messaging.SingleActuatorMsg()
+
+ def getInputSize(self) -> int:
+ return 1
+
+ def getOutputSize(self) -> int:
+ return 1
+
+ def readInput(self, CurrentSimNanos):
+ # Return 1x1 vector from SingleActuatorMsg
+ payload = self.inMsg()
+ return np.array([[payload.input]])
+
+ def writeOutput(self, CurrentSimNanos, y):
+ # Write y[0] to SingleActuatorMsg
+ payload = messaging.SingleActuatorMsgPayload()
+ payload.input = y[0][0]
+ self.outMsg.write(payload, self.moduleID, CurrentSimNanos)
+
+ system = PyFirstOrderLTI()
+
+ else:
+ # C++ subclass: SingleActuatorLTI
+ system = MJLinearTimeInvariantSystem.SingleActuatorLTI()
+
+ # First order system: x_dot = -a x + a u, y = x
+ A = np.array([[-a]])
+ B = np.array([[a]])
+ C = np.array([[1.0]])
+ D = np.array([[0.0]])
+ system.setA(A)
+ system.setB(B)
+ system.setC(C)
+ system.setD(D)
+ system.inMsg.subscribeTo(cmdMsg)
+
+ # Add system to the scene dynamics
+ scene.AddModelToDynamicsTask(system)
+
+ # Recorder for the system output
+ outRecorder = system.outMsg.recorder()
+ scSim.AddModelToTask("test", outRecorder)
+
+ # Initialize and run
+ scSim.InitializeSimulation()
+
+ # Basic size checks use the LinearTimeInvariantSystem API
+ assert system.getInputSize() == 1
+ assert system.getOutputSize() == 1
+ assert system.getStateSize() == 1
+
+ scSim.ConfigureStopTime(macros.sec2nano(tf))
+ scSim.ExecuteSimulation()
+
+ # Extract data
+ tNanos = outRecorder.times()
+ yVals = np.asarray(outRecorder.input) # SingleActuatorMsgPayload.input
+
+ # Convert times to seconds for plotting / diagnostics
+ t = tNanos * 1.0e-9
+
+ if showPlots:
+ fig, ax = plt.subplots()
+ ax.plot(t, yVals, label="y(t)")
+ ax.set_xlabel("Time [s]")
+ ax.set_ylabel("Output y")
+ ax.grid(True)
+ ax.legend()
+ plt.show()
+
+ # Continuous time target: x(t) = 1 - exp(-a t); y = x
+ yTargetFinal = 1.0 - np.exp(-a * tf)
+
+ # Use the last sample
+ yFinal = float(yVals[-1])
+
+ # Assert that final value is reasonably close to the continuous solution
+ # Tolerance is relaxed a bit to allow for integration and discretization error
+ npt.assert_allclose(yFinal, yTargetFinal, rtol=0.02, atol=1e-2)
+
+@pytest.mark.skipif(not couldImportMujoco, reason="Compiled Basilisk without --mujoco")
+def test_linearTimeInvariantSystemSecondOrder(showPlots: bool = False):
+ """
+ Unit test for an LTI model configured as a second-order system.
+
+ This test sets up a critically damped second-order linear time-invariant (LTI) system
+ with natural frequency wn = 10 rad/s and damping ratio zeta = 1.0. The system is driven
+ by a constant unit step input (u = 1.0). The test verifies:
+
+ 1. The final output value approaches 1.0 (steady-state response).
+ 2. The output does not overshoot beyond a small numerical margin (no overshoot for critical damping).
+ 3. The output time history closely matches the analytic step response for a critically damped system:
+ y(t) = 1 - exp(-wn * t) * (1 + wn * t)
+ """
+ # Simulation setup
+ dt = 0.01 # s
+ tf = 2.0 # s
+
+ scSim = SimulationBaseClass.SimBaseClass()
+ dynProcess = scSim.CreateNewProcess("test")
+ dynProcess.addTask(scSim.CreateNewTask("test", macros.sec2nano(dt)))
+
+ # Empty MuJoCo scene: just a container for system models
+ scene = mujoco.MJScene("")
+ scSim.AddModelToTask("test", scene)
+
+ # Constant input message u = 1.0
+ cmdMsg = messaging.SingleActuatorMsg()
+ cmdPayload = messaging.SingleActuatorMsgPayload()
+ cmdPayload.input = 1.0
+ cmdMsg.write(cmdPayload)
+
+ # Second order critically damped LTI: wn = 10 rad/s, zeta = 1, k = 1
+ wn = 10.0
+ zeta = 1.0
+
+ system = MJLinearTimeInvariantSystem.SingleActuatorLTI()
+ system.configureSecondOrder(wn, zeta) # default k = 1
+ system.inMsg.subscribeTo(cmdMsg)
+
+ # Add system to the scene dynamics
+ scene.AddModelToDynamicsTask(system)
+
+ # Recorder for the system output
+ outRecorder = system.outMsg.recorder()
+ scSim.AddModelToTask("test", outRecorder)
+
+ # Initialize and run
+ scSim.InitializeSimulation()
+
+ # Basic size checks use the LinearTimeInvariantSystem API
+ assert system.getInputSize() == 1
+ assert system.getOutputSize() == 1
+ assert system.getStateSize() == 2
+
+ scSim.ConfigureStopTime(macros.sec2nano(tf))
+ scSim.ExecuteSimulation()
+
+ # Extract data
+ tNanos = outRecorder.times()
+ yVals = np.asarray(outRecorder.input) # SingleActuatorMsgPayload.input
+
+ # Convert times to seconds for plotting / diagnostics
+ t = tNanos * 1.0e-9
+
+ if showPlots:
+ fig, ax = plt.subplots()
+ ax.plot(t, cmdPayload.input * np.ones_like(t), "--", label="Input")
+ ax.plot(t, yVals, label="Output")
+ ax.set_xlabel("Time [s]")
+ ax.set_ylabel("y(t) [-]")
+ ax.grid(True)
+ ax.legend()
+ plt.show()
+
+ # Analytic critically damped step response for:
+ # G(s) = wn^2 / (s^2 + 2*wn*s + wn^2), unit step input
+ # y(t) = 1 - exp(-wn t) * (1 + wn t)
+ yAnalytic = 1.0 - np.exp(-wn * t) * (1.0 + wn * t)
+
+ # 1) Final value near 1.0
+ npt.assert_allclose(yVals[-1], 1.0, atol=0.005)
+
+ # 2) No overshoot beyond a small numerical margin
+ assert np.max(yVals) <= 1.01
+
+ # 3) Shape close to analytic critically damped response
+ npt.assert_allclose(
+ yVals,
+ yAnalytic,
+ rtol=0.1,
+ atol=0.05
+ )
+
+
+if __name__ == "__main__":
+ assert couldImportMujoco
+ test_linearTimeInvariantSystemFirstOrder(usePythonSubclass=False, showPlots=True)
+ test_linearTimeInvariantSystemFirstOrder(usePythonSubclass=True, showPlots=True)
+ test_linearTimeInvariantSystemSecondOrder(showPlots=True)
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.cpp b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.cpp
new file mode 100644
index 0000000000..90ab5a5afa
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.cpp
@@ -0,0 +1,44 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab, University of Colorado at Boulder
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+
+ */
+#include "forceAtSiteLTI.h"
+
+Eigen::VectorXd ForceAtSiteLTI::readInput(uint64_t /*CurrentSimNanos*/)
+{
+ // Read the current payload from the input message
+ const ForceAtSiteMsgPayload payload = this->inMsg();
+
+ // Construct a 3 by 1 input vector from the force components
+ Eigen::VectorXd u(3);
+ u(0) = payload.force_S[0];
+ u(1) = payload.force_S[1];
+ u(2) = payload.force_S[2];
+
+ return u;
+}
+
+void ForceAtSiteLTI::writeOutput(uint64_t CurrentSimNanos,
+ const Eigen::VectorXd &y)
+{
+ ForceAtSiteMsgPayload payload{};
+ payload.force_S[0] = y(0);
+ payload.force_S[1] = y(1);
+ payload.force_S[2] = y(2);
+
+ this->outMsg.write(&payload, this->moduleID, CurrentSimNanos);
+}
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.h b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.h
new file mode 100644
index 0000000000..6a37f75490
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/forceAtSiteLTI.h
@@ -0,0 +1,114 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef FORCE_AT_SITE_LTI_H
+#define FORCE_AT_SITE_LTI_H
+
+#include "linearTimeInvariantSystem.h"
+
+#include "architecture/messaging/messaging.h"
+#include "architecture/msgPayloadDefC/ForceAtSiteMsgPayload.h"
+
+/**
+ * @brief Linear 3D force model based on LinearTimeInvariantSystem.
+ *
+ * This class implements a three input, three output LTI system where the
+ * input and output are carried through ForceAtSiteMsgPayload messages.
+ *
+ * Input:
+ * u = [Fx, Fy, Fz]^T in the site S frame, read from inMsg().force_S.
+ *
+ * Output:
+ * y = [Fx, Fy, Fz]^T in the site S frame, written to outMsg.force_S.
+ *
+ * The internal dynamics are defined by the A, B, C, D matrices stored in the
+ * base class LinearTimeInvariantSystem.
+ */
+class ForceAtSiteLTI : public LinearTimeInvariantSystem
+{
+public:
+ /**
+ * @brief Default constructor.
+ *
+ * The system matrices must be configured by the user before running
+ * the simulation, either by direct calls to setA, setB, setC, setD
+ * or through convenience configuration helpers.
+ */
+ ForceAtSiteLTI() = default;
+
+ /**
+ * @brief Get the dimension of the input vector.
+ *
+ * This model is strictly 3D, so the input dimension is always 3.
+ *
+ * @return Number of inputs (always 3).
+ */
+ size_t getInputSize() const override { return 3; }
+
+ /**
+ * @brief Get the dimension of the output vector.
+ *
+ * This model is strictly 3D, so the output dimension is always 3.
+ *
+ * @return Number of outputs (always 3).
+ */
+ size_t getOutputSize() const override { return 3; }
+
+ /**
+ * @brief Read the current input vector from the subscribed input message.
+ *
+ * This method constructs a 3 by 1 Eigen::VectorXd whose elements are
+ * taken from the force_S array of the ForceAtSiteMsgPayload read via
+ * inMsg().
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ * (Unused in this implementation.)
+ * @return Input vector u of size 3.
+ */
+ Eigen::VectorXd readInput(uint64_t CurrentSimNanos) override;
+
+ /**
+ * @brief Write the current output vector to the output message.
+ *
+ * The first three elements of the output vector y are written to the
+ * force_S array of the ForceAtSiteMsgPayload and sent on outMsg.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ * @param y Output vector of size at least 3.
+ */
+ void writeOutput(uint64_t CurrentSimNanos,
+ const Eigen::VectorXd &y) override;
+
+public:
+ /**
+ * @brief Output message carrying the 3D force command at the site.
+ *
+ * The force_S array is populated from the first three elements of
+ * the output vector y computed by LinearTimeInvariantSystem.
+ */
+ Message outMsg;
+
+ /**
+ * @brief Input message read functor providing the 3D force at the site.
+ *
+ * The force_S array of the payload is mapped to the input vector u.
+ */
+ ReadFunctor inMsg;
+};
+
+#endif /* FORCE_AT_SITE_LTI_H */
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.cpp b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.cpp
new file mode 100644
index 0000000000..6ac81ca0da
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.cpp
@@ -0,0 +1,410 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab, University of Colorado at Boulder
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+
+ */
+
+#include "linearTimeInvariantSystem.h"
+#include
+
+void LinearTimeInvariantSystem::registerStates(DynParamRegisterer registerer)
+{
+ const size_t stateSize = this->getStateSize();
+ if (stateSize > 0) {
+ xState = registerer.registerState(stateSize, 1, "x");
+ xState->setState(Eigen::VectorXd::Constant(stateSize, 0.0)); // default to x0 = 0
+ }
+}
+
+void LinearTimeInvariantSystem::UpdateState(uint64_t CurrentSimNanos)
+{
+ const size_t stateSize = this->getStateSize();
+ const size_t inputSize = this->getInputSize();
+ const size_t outputSize = this->getOutputSize();
+
+ Eigen::VectorXd u;
+ if (inputSize > 0) {
+ u = readInput(CurrentSimNanos);
+
+ if (static_cast(u.size()) != inputSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::UpdateState: readInput returned vector with incorrect size.");
+ }
+ }
+
+ Eigen::VectorXd y = Eigen::VectorXd::Zero(static_cast(outputSize));
+
+ if (xState && stateSize > 0) {
+ Eigen::VectorXd x = xState->getState();
+
+ if (static_cast(x.size()) != stateSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::UpdateState: stored state has incorrect size.");
+ }
+
+ Eigen::VectorXd dx = Eigen::VectorXd::Zero(static_cast(stateSize));
+ if (A.cols() > 0) {
+ dx += A * x;
+ }
+ if (B.cols() > 0 && inputSize > 0) {
+ dx += B * u;
+ }
+ xState->setDerivative(dx);
+
+ if (C.cols() > 0) {
+ y += C * x;
+ }
+ }
+
+ if (D.size() > 0 && inputSize > 0) {
+ y += D * u;
+ }
+
+ writeOutput(CurrentSimNanos, y);
+}
+
+void LinearTimeInvariantSystem::Reset(uint64_t /*CurrentSimNanos*/)
+{
+ const size_t stateSize = this->getStateSize();
+ const size_t inputSize = this->getInputSize();
+ const size_t outputSize = this->getOutputSize();
+
+ // =======================
+ // Matrix A (state x state)
+ // =======================
+ if (A.size() > 0) {
+ const size_t A_rows = static_cast(A.rows());
+ const size_t A_cols = static_cast(A.cols());
+
+ if (A_rows != stateSize || A_cols != stateSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::Reset: matrix A has inconsistent dimensions. ") +
+ "Expected size [" +
+ std::to_string(stateSize) + " x " + std::to_string(stateSize) +
+ "] based on getStateSize(), but received [" +
+ std::to_string(A_rows) + " x " + std::to_string(A_cols) +
+ "]."
+ ).c_str()
+ );
+ }
+ }
+
+ // =======================
+ // Matrix B (state x input)
+ // =======================
+ if (B.size() > 0) {
+ const size_t B_rows = static_cast(B.rows());
+ const size_t B_cols = static_cast(B.cols());
+
+ if (B_rows != stateSize || B_cols != inputSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::Reset: matrix B has inconsistent dimensions. ") +
+ "Expected size [" +
+ std::to_string(stateSize) + " x " + std::to_string(inputSize) +
+ "] based on getStateSize() and getInputSize(), but received [" +
+ std::to_string(B_rows) + " x " + std::to_string(B_cols) +
+ "]."
+ ).c_str()
+ );
+ }
+ }
+
+ // ==========================
+ // Matrix C (output x state)
+ // ==========================
+ if (C.size() > 0) {
+ const size_t C_rows = static_cast(C.rows());
+ const size_t C_cols = static_cast(C.cols());
+
+ if (C_rows != outputSize || C_cols != stateSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::Reset: matrix C has inconsistent dimensions. ") +
+ "Expected size [" +
+ std::to_string(outputSize) + " x " + std::to_string(stateSize) +
+ "] based on getOutputSize() and getStateSize(), but received [" +
+ std::to_string(C_rows) + " x " + std::to_string(C_cols) +
+ "]."
+ ).c_str()
+ );
+ }
+ }
+
+ // =========================
+ // Matrix D (output x input)
+ // =========================
+ if (D.size() > 0) {
+ const size_t D_rows = static_cast(D.rows());
+ const size_t D_cols = static_cast(D.cols());
+
+ if (D_rows != outputSize || D_cols != inputSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::Reset: matrix D has inconsistent dimensions. ") +
+ "Expected size [" +
+ std::to_string(outputSize) + " x " + std::to_string(inputSize) +
+ "] based on getOutputSize() and getInputSize(), but received [" +
+ std::to_string(D_rows) + " x " + std::to_string(D_cols) +
+ "]."
+ ).c_str()
+ );
+ }
+ }
+}
+
+const Eigen::MatrixXd &LinearTimeInvariantSystem::getA() const
+{
+ return A;
+}
+
+void LinearTimeInvariantSystem::setA(const Eigen::MatrixXd &Ain)
+{
+ A = Ain;
+}
+
+const Eigen::MatrixXd &LinearTimeInvariantSystem::getB() const
+{
+ return B;
+}
+
+void LinearTimeInvariantSystem::setB(const Eigen::MatrixXd &Bin)
+{
+ B = Bin;
+}
+
+const Eigen::MatrixXd &LinearTimeInvariantSystem::getC() const
+{
+ return C;
+}
+
+void LinearTimeInvariantSystem::setC(const Eigen::MatrixXd &Cin)
+{
+ C = Cin;
+}
+
+const Eigen::MatrixXd &LinearTimeInvariantSystem::getD() const
+{
+ return D;
+}
+
+void LinearTimeInvariantSystem::setD(const Eigen::MatrixXd &Din)
+{
+ D = Din;
+}
+
+void LinearTimeInvariantSystem::configureSecondOrder(double wn, double zeta, double k)
+{
+ if (wn <= 0.0) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "configureSecondOrder: natural frequency wn must be positive.");
+ return;
+ }
+ if (zeta < 0.0) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "configureSecondOrder: damping ratio zeta must be non negative.");
+ return;
+ }
+
+ A.resize(2, 2);
+ B.resize(2, 1);
+ C.resize(1, 2);
+ D.resize(1, 1);
+
+ const double wn2 = wn * wn;
+
+ A << 0.0 , 1.0,
+ -wn2, -2.0 * zeta * wn;
+
+ B << 0.0,
+ k * wn2;
+
+ C << 1.0, 0.0;
+
+ D << 0.0;
+}
+
+void LinearTimeInvariantSystem::configureSecondOrder(const Eigen::VectorXd &wn,
+ const Eigen::VectorXd &zeta,
+ const Eigen::VectorXd &k)
+{
+ const Eigen::Index n = wn.size();
+
+ if (n <= 0) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::configureSecondOrder(MIMO): input vectors must be non empty."
+ );
+ return;
+ }
+
+ if (zeta.size() != n || k.size() != n) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::configureSecondOrder(MIMO): size mismatch. ") +
+ "Expected wn, zeta, k to all have length " + std::to_string(static_cast(n)) + ". "
+ "Received lengths wn=" + std::to_string(static_cast(wn.size())) +
+ ", zeta=" + std::to_string(static_cast(zeta.size())) +
+ ", k=" + std::to_string(static_cast(k.size())) + "."
+ ).c_str()
+ );
+ return;
+ }
+
+ // Validate entries
+ for (Eigen::Index i = 0; i < n; ++i) {
+ const double wn_i = wn(i);
+ const double zeta_i = zeta(i);
+
+ if (wn_i <= 0.0) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::configureSecondOrder(MIMO): wn(") +
+ std::to_string(static_cast(i)) +
+ ") must be positive, but is " + std::to_string(wn_i) + "."
+ ).c_str()
+ );
+ return;
+ }
+
+ if (zeta_i < 0.0) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ (
+ std::string("LinearTimeInvariantSystem::configureSecondOrder(MIMO): zeta(") +
+ std::to_string(static_cast(i)) +
+ ") must be non negative, but is " + std::to_string(zeta_i) + "."
+ ).c_str()
+ );
+ return;
+ }
+ }
+
+ // Allocate matrices for MIMO second-order system: n channels, each 2 states
+ const Eigen::Index stateSize = 2 * n;
+ const Eigen::Index inputSize = n;
+ const Eigen::Index outputSize = n;
+
+ A.setZero(stateSize, stateSize);
+ B.setZero(stateSize, inputSize);
+ C.setZero(outputSize, stateSize);
+ D.setZero(outputSize, inputSize);
+
+ for (Eigen::Index i = 0; i < n; ++i) {
+ const double wn_i = wn(i);
+ const double zeta_i = zeta(i);
+ const double k_i = k(i);
+
+ const double wn2 = wn_i * wn_i;
+
+ const Eigen::Index rowPos = 2 * i; // position state index
+ const Eigen::Index rowVel = 2 * i + 1; // velocity state index
+
+ // A block for channel i:
+ // [ 0 1 ]
+ // [ -wn_i^2 -2*zeta_i*wn_i ]
+ A(rowPos, rowVel) = 1.0;
+ A(rowVel, rowPos) = -wn2;
+ A(rowVel, rowVel) = -2.0 * zeta_i * wn_i;
+
+ // B column i: [0, k_i * wn_i^2]^T in rows (rowPos, rowVel)
+ B(rowVel, i) = k_i * wn2;
+
+ // C row i: [1 0] on the position state of channel i
+ C(i, rowPos) = 1.0;
+
+ // D(i, i) remains zero (direct feedthrough = 0)
+ }
+}
+
+Eigen::VectorXd
+LinearTimeInvariantSystem::getX()
+{
+ if (!xState) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::getX: state has not been registered.");
+ return Eigen::VectorXd();
+ }
+ return xState->getState();
+}
+
+void LinearTimeInvariantSystem::setX(const Eigen::VectorXd &xin)
+{
+ if (!xState) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::setX: state has not been registered.");
+ return;
+ }
+
+ const size_t stateSize = this->getStateSize();
+ if (static_cast(xin.size()) != stateSize) {
+ bskLogger.bskLog(
+ BSK_ERROR,
+ "LinearTimeInvariantSystem::setX: input state vector has incorrect size.");
+ return;
+ }
+
+ xState->setState(xin);
+}
+
+size_t LinearTimeInvariantSystem::getInputSize() const
+{
+ if (B.cols() > 0) {
+ return static_cast(B.cols());
+ }
+ if (D.cols() > 0) {
+ return static_cast(D.cols());
+ }
+ return 0;
+}
+
+size_t LinearTimeInvariantSystem::getStateSize() const
+{
+ if (A.cols() > 0) {
+ return static_cast(A.cols());
+ }
+ if (B.rows() > 0) {
+ return static_cast(B.rows());
+ }
+ if (C.cols() > 0) {
+ return static_cast(C.cols());
+ }
+ return 0;
+}
+
+size_t LinearTimeInvariantSystem::getOutputSize() const
+{
+ if (C.rows() > 0) {
+ return static_cast(C.rows());
+ }
+ if (D.rows() > 0) {
+ return static_cast(D.rows());
+ }
+ return 0;
+}
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.h b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.h
new file mode 100644
index 0000000000..88d5923850
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.h
@@ -0,0 +1,335 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab, University of Colorado at Boulder
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+
+ */
+#ifndef LINEAR_TIME_INVARIANT_SYSTEM_H
+#define LINEAR_TIME_INVARIANT_SYSTEM_H
+
+#include
+#include
+
+#include
+
+#include "simulation/mujocoDynamics/_GeneralModuleFiles/StatefulSysModel.h"
+#include "architecture/utilities/bskLogging.h"
+
+/**
+ * @brief Linear time invariant system of the form
+ * x_dot = A x + B u, y = C x + D u.
+ *
+ * @verbatim
+ * x_dot = A x + B u
+ * y = C x + D u
+ * @endverbatim
+ *
+ * Subclasses must implement the input and output mapping methods.
+ */
+class LinearTimeInvariantSystem : public StatefulSysModel {
+public:
+ /** @brief Default constructor. */
+ LinearTimeInvariantSystem() = default;
+
+
+ /**
+ * @brief Register the state vector with the dynamics framework.
+ *
+ * If the state dimension is greater than zero, this function allocates
+ * a state block of size getStateSize() and initializes it to zero.
+ *
+ * @param registerer State registration helper provided by the framework.
+ */
+ void registerStates(DynParamRegisterer registerer) override;
+
+ /**
+ * @brief Compute the state derivative and system output at the current time.
+ *
+ * This method reads the current input vector using readInput, computes
+ * the state derivative
+ * x_dot = A x + B u and the output y = C x + D u, and writes the output
+ * using writeOutput. If no state is registered, only the direct feedthrough
+ * term y = D u is evaluated if applicable.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ */
+ void UpdateState(uint64_t CurrentSimNanos) override;
+
+ /**
+ * @brief Perform consistency checks and one time initialization.
+ *
+ * This method validates that the dimensions of the system matrices A, B,
+ * C, and D are consistent with getStateSize, getInputSize, and
+ * getOutputSize. Any inconsistency is reported through the logger.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ */
+ virtual void Reset(uint64_t CurrentSimNanos) override;
+
+
+ /** @name Parameter getters and setters
+ * Accessors for the system matrices A, B, C, and D.
+ * @{ */
+
+ /**
+ * @brief Get the state matrix A.
+ *
+ * @return Constant reference to the A matrix.
+ */
+ const Eigen::MatrixXd &getA() const;
+
+ /**
+ * @brief Set the state matrix A.
+ *
+ * This matrix defines the homogeneous term in the state equation
+ * @verbatim
+ * x_dot = A x + B u
+ * @endverbatim
+ *
+ * @param Ain New A matrix.
+ */
+ void setA(const Eigen::MatrixXd &Ain);
+
+ /**
+ * @brief Get the input matrix B.
+ *
+ * @return Constant reference to the B matrix.
+ */
+ const Eigen::MatrixXd &getB() const;
+
+ /**
+ * @brief Set the input matrix B.
+ *
+ * This matrix defines the contribution of the input vector u to the
+ * state equation
+ * @verbatim
+ * x_dot = A x + B u
+ * @endverbatim
+ *
+ * @param Bin New B matrix.
+ */
+ void setB(const Eigen::MatrixXd &Bin);
+
+ /**
+ * @brief Get the output matrix C.
+ *
+ * @return Constant reference to the C matrix.
+ */
+ const Eigen::MatrixXd &getC() const;
+
+ /**
+ * @brief Set the output matrix C.
+ *
+ * This matrix maps the state vector x to the output equation
+ * @verbatim
+ * y = C x + D u
+ * @endverbatim
+ *
+ * @param Cin New C matrix.
+ */
+ void setC(const Eigen::MatrixXd &Cin);
+
+ /**
+ * @brief Get the feedthrough matrix D.
+ *
+ * @return Constant reference to the D matrix.
+ */
+ const Eigen::MatrixXd &getD() const;
+
+ /**
+ * @brief Set the feedthrough matrix D.
+ *
+ * This matrix maps the input vector u directly to the output equation
+ * @verbatim
+ * y = C x + D u
+ * @endverbatim
+ *
+ * @param Din New D matrix.
+ */
+ void setD(const Eigen::MatrixXd &Din);
+
+ /**
+ * @brief Configure the A, B, C, D matrices as a standard SISO second order model.
+ *
+ * The resulting transfer function is:
+ * @verbatim
+ * G(s) = k * wn^2 / (s^2 + 2*zeta*wn*s + wn^2)
+ * @endverbatim
+ *
+ * State space realization:
+ * @verbatim
+ * x = [position, velocity]^T
+ * x_dot = [ 0 1 ] x + [0 ] u
+ * [ -wn^2 -2*zeta*wn ] [k * wn^2]
+ * y = [1 0] x
+ * @endverbatim
+ *
+ * @param wn Natural frequency in rad/s. Must be positive.
+ * @param zeta Damping ratio (dimensionless). Must be non negative.
+ * @param k Static gain. Default is unity.
+ */
+ void configureSecondOrder(double wn, double zeta, double k = 1.0);
+
+ /**
+ * @brief Configure A, B, C, D as a decoupled MIMO second order model.
+ *
+ * Each element of the input vectors defines one independent SISO channel:
+ * @verbatim
+ * G_i(s) = k_i * wn_i^2 / (s^2 + 2*zeta_i*wn_i*s + wn_i^2)
+ * @endverbatim
+ *
+ * The full state vector is
+ * @verbatim
+ * x = [pos_0, vel_0, pos_1, vel_1, ..., pos_{n-1}, vel_{n-1}]^T
+ * @endverbatim
+ *
+ * For n channels, the resulting dimensions are:
+ * @verbatim
+ * A: (2n x 2n), B: (2n x n), C: (n x 2n), D: (n x n).
+ * @endverbatim
+ *
+ * @param wn Vector of natural frequencies in rad/s. Each wn(i) must be positive.
+ * @param zeta Vector of damping ratios (dimensionless). Each zeta(i) must be non negative.
+ * @param k Vector of static gains. Must have the same length as wn and zeta.
+ */
+ void configureSecondOrder(const Eigen::VectorXd &wn,
+ const Eigen::VectorXd &zeta,
+ const Eigen::VectorXd &k);
+
+
+ /** @name State access
+ * Accessors for the internal state vector.
+ * @{ */
+
+ /**
+ * @brief Get the current state vector x.
+ *
+ * If the state has not been registered yet, an empty vector is returned
+ * and an error is logged.
+ *
+ * @return Copy of the current state vector.
+ */
+ Eigen::VectorXd getX();
+
+ /**
+ * @brief Set the current state vector x.
+ *
+ * If the state has been registered and the supplied vector has the same
+ * dimension as the stored state, the state is updated. Otherwise an
+ * error is logged and the call is ignored.
+ *
+ * @param xin New state vector.
+ */
+ void setX(const Eigen::VectorXd &xin);
+
+
+ /**
+ * @brief Get the dimension of the input vector u.
+ *
+ * The size is inferred from the B or D matrices when they are set.
+ *
+ * @return Size of the input vector.
+ */
+ virtual size_t getInputSize() const;
+
+ /**
+ * @brief Get the dimension of the state vector x.
+ *
+ * The size is inferred from the A, B, or C matrices when they are set.
+ *
+ * @return Size of the state vector.
+ */
+ virtual size_t getStateSize() const;
+
+ /**
+ * @brief Get the dimension of the output vector y.
+ *
+ * The size is inferred from the C or D matrices when they are set.
+ *
+ * @return Size of the output vector.
+ */
+ virtual size_t getOutputSize() const;
+
+ /**
+ * @brief Logger used to report errors and informational messages.
+ */
+ BSKLogger bskLogger;
+
+protected:
+ /**
+ * @brief Read the current input vector u from the simulation.
+ *
+ * Subclasses must implement this method to construct the input vector
+ * of size getInputSize() from the relevant input messages at the given
+ * simulation time.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ *
+ * @return Input vector u.
+ */
+ virtual Eigen::VectorXd readInput(uint64_t CurrentSimNanos) = 0;
+
+ /**
+ * @brief Write the current output vector y to the simulation.
+ *
+ * Subclasses must implement this method to map the output vector
+ * of size getOutputSize() to the appropriate output messages at the
+ * given simulation time.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ * @param y Output vector to write.
+ */
+ virtual void writeOutput(uint64_t CurrentSimNanos,
+ const Eigen::VectorXd &y) = 0;
+
+private:
+ /**
+ * @brief Pointer to the registered state data for the state vector x.
+ *
+ * This pointer is set during registerStates and is used to read and
+ * update the state and its derivative.
+ */
+ StateData *xState = nullptr;
+
+ /**
+ * @brief State matrix A.
+ *
+ * Defines the homogeneous dynamics x_dot = A x + B u.
+ */
+ Eigen::MatrixXd A;
+
+ /**
+ * @brief Input matrix B.
+ *
+ * Defines the input contribution to the dynamics x_dot = A x + B u.
+ */
+ Eigen::MatrixXd B;
+
+ /**
+ * @brief Output matrix C.
+ *
+ * Maps the state vector to the output y = C x + D u.
+ */
+ Eigen::MatrixXd C;
+
+ /**
+ * @brief Feedthrough matrix D.
+ *
+ * Maps the input vector directly to the output y = C x + D u.
+ */
+ Eigen::MatrixXd D;
+};
+
+#endif /* LINEAR_TIME_INVARIANT_SYSTEM_H */
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.i b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.i
new file mode 100644
index 0000000000..ef07d9cbb3
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/linearTimeInvariantSystem.i
@@ -0,0 +1,83 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+%module(directors="1",threads="1") MJLinearTimeInvariantSystem
+
+%include "architecture/utilities/bskException.swg"
+%default_bsk_exception();
+
+%{
+ // C++ includes visible to the generated wrapper
+ #include "linearTimeInvariantSystem.h"
+ #include "forceAtSiteLTI.h"
+ #include "singleActuatorLTI.h"
+%}
+
+/* Python helpers consistent with your other modules */
+%pythoncode %{
+from Basilisk.architecture.swig_common_model import *
+%}
+
+/* Common SWIG helpers */
+%include "swig_eigen.i"
+%include "std_string.i"
+%include "exception.i"
+
+/* Basilisk system-model base and helpers */
+%import "simulation/mujocoDynamics/_GeneralModuleFiles/pyStatefulSysModel.i"
+
+/* ============================
+ Base class: LinearTimeInvariantSystem
+ ============================ */
+
+/* Enable directors so Python subclasses can override virtual methods
+ (readInput, writeOutput, etc.). */
+%feature("director") LinearTimeInvariantSystem;
+
+%rename("_LinearTimeInvariantSystem") LinearTimeInvariantSystem;
+%include "linearTimeInvariantSystem.h"
+
+/* ============================
+ SingleActuatorLTI
+ ============================ */
+
+%ignore SingleActuatorLTI::readInput;
+%ignore SingleActuatorLTI::writeOutput;
+%include "singleActuatorLTI.h"
+
+%include "architecture/msgPayloadDefC/SingleActuatorMsgPayload.h"
+struct SingleActuatorMsgPayload_C;
+
+/* ============================
+ ForceAtSiteLTI
+ ============================ */
+
+%ignore ForceAtSiteLTI::readInput;
+%ignore ForceAtSiteLTI::writeOutput;
+%include "forceAtSiteLTI.h"
+
+%include "architecture/msgPayloadDefC/ForceAtSiteMsgPayload.h"
+struct ForceAtSiteMsgPayload_C;
+
+/* Final Python-side wrapper for the base LTI class */
+%pythoncode %{
+from Basilisk.architecture.sysModel import SysModelMixin
+
+class LinearTimeInvariantSystem(SysModelMixin, _LinearTimeInvariantSystem):
+ """Python wrapper for the C++ LinearTimeInvariantSystem."""
+%}
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.cpp b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.cpp
new file mode 100644
index 0000000000..963134bf0a
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.cpp
@@ -0,0 +1,12 @@
+#include "singleActuatorLTI.h"
+
+Eigen::VectorXd SingleActuatorLTI::readInput(uint64_t CurrentSimNanos)
+{
+ return Eigen::VectorXd::Constant(1, this->inMsg().input);
+}
+
+void SingleActuatorLTI::writeOutput(uint64_t CurrentSimNanos, const Eigen::VectorXd& y)
+{
+ auto payload = SingleActuatorMsgPayload{y(0)};
+ this->outMsg.write(&payload, moduleID, CurrentSimNanos);
+}
diff --git a/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.h b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.h
new file mode 100644
index 0000000000..89942b67ab
--- /dev/null
+++ b/src/simulation/mujocoDynamics/linearTimeInvariantSystem/singleActuatorLTI.h
@@ -0,0 +1,107 @@
+/*
+ ISC License
+
+ Copyright (c) 2025, Autonomous Vehicle Systems Lab, University of Colorado at Boulder
+
+ Permission to use, copy, modify, and/or distribute this software for any
+ purpose with or without fee is hereby granted, provided that the above
+ copyright notice and this permission notice appear in all copies.
+
+ THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+
+ */
+
+#ifndef SINGLE_ACTUATOR_LTI_H
+#define SINGLE_ACTUATOR_LTI_H
+
+#include "linearTimeInvariantSystem.h"
+
+#include "architecture/messaging/messaging.h"
+#include "architecture/msgPayloadDefC/SingleActuatorMsgPayload.h"
+
+/**
+ * @brief Linear SISO actuator model built on top of LinearTimeInvariantSystem.
+ *
+ * This class implements a single-input, single-output LTI system where
+ * both the input and output are carried through a SingleActuatorMsgPayload.
+ *
+ * The internal dynamics are defined by the A, B, C, D matrices stored in the
+ * base class LinearTimeInvariantSystem.
+ */
+class SingleActuatorLTI : public LinearTimeInvariantSystem
+{
+public:
+ /**
+ * @brief Default constructor.
+ *
+ * The underlying LinearTimeInvariantSystem matrices must be configured
+ * (for example, via configureSecondOrder or direct setA/setB/setC/setD
+ * calls) before the simulation is run.
+ */
+ SingleActuatorLTI() = default;
+
+ /**
+ * @brief Get the dimension of the input vector.
+ *
+ * This model is strictly SISO, so the input dimension is always 1.
+ *
+ * @return Number of inputs (always 1).
+ */
+ size_t getInputSize() const override { return 1; }
+
+ /**
+ * @brief Get the dimension of the output vector.
+ *
+ * This model is strictly SISO, so the output dimension is always 1.
+ *
+ * @return Number of outputs (always 1).
+ */
+ size_t getOutputSize() const override { return 1; }
+
+ /**
+ * @brief Read the current input vector from the subscribed input message.
+ *
+ * This method constructs a 1x1 Eigen::VectorXd whose single element is
+ * taken from inMsg().input.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ * @return Input vector u of size 1.
+ */
+ Eigen::VectorXd readInput(uint64_t CurrentSimNanos) override;
+
+ /**
+ * @brief Write the current output vector to the output message.
+ *
+ * The first element of the output vector y is written to outMsg as the
+ * 'input' field of SingleActuatorMsgPayload.
+ *
+ * @param CurrentSimNanos Current simulation time in nanoseconds.
+ * @param y Output vector of size 1.
+ */
+ void writeOutput(uint64_t CurrentSimNanos,
+ const Eigen::VectorXd &y) override;
+
+public:
+ /**
+ * @brief Output message carrying the actuator command.
+ *
+ * The 'input' field is populated from the first element of the output
+ * vector y computed by LinearTimeInvariantSystem.
+ */
+ Message outMsg;
+
+ /**
+ * @brief Input message read functor providing the actuator command.
+ *
+ * The 'input' field of the payload is mapped to the input vector u(0).
+ */
+ ReadFunctor inMsg;
+};
+
+#endif /* SINGLE_ACTUATOR_LTI_H */