BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem class

LinearTimeInvariantSystem describes a MIMO linear time invariant system of the form $\dot{x} = Ax + Bu$ where x is the state and u the control input.

The state, its derivative and the control input are described by vectors The LinearTimeInvariantSystem inherits from a generic DynamicalSystem where the State is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
xEigen::VectorXdA generic vector belonging to $\mathbb{R}^n$

The StateDerivative is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
dxEigen::VectorXdA state vector derivative belonging to $\mathbb{R}^n$

The Input is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
uEigen::VectorXdA control vector belonging to $\mathbb{R}^m$

Base classes

template<class _Derived>
class DynamicalSystem<LinearTimeInvariantSystem>
DynamicalSystem defines a continuous time dynamical system, i.e.

Public functions

auto setSystemMatrices(const Eigen::Ref<const Eigen::MatrixXd>& A, const Eigen::Ref<const Eigen::MatrixXd>& B) -> bool
Set the system matrices.
auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) -> bool
Initialize the Dynamical system.
auto setState(const State& state) -> bool
Set the state of the dynamical system.
auto getState() const -> const State&
Get the state to the dynamical system.
auto setControlInput(const Input& controlInput) -> bool
Set the control input to the dynamical system.
auto dynamics(const std::chrono::nanoseconds& time, StateDerivative& stateDerivative) -> bool
Computes the system dynamics.

Function documentation

bool BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::setSystemMatrices(const Eigen::Ref<const Eigen::MatrixXd>& A, const Eigen::Ref<const Eigen::MatrixXd>& B)

Set the system matrices.

Parameters
A the A matrix.
B the B matrix.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler)

Initialize the Dynamical system.

Parameters
handler pointer to the parameter handler.
Returns true in case of success/false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::setState(const State& state)

Set the state of the dynamical system.

Parameters
state tuple containing a const reference to the state elements.
Returns true in case of success, false otherwise.

const State& BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::getState() const

Get the state to the dynamical system.

Returns the current state of the dynamical system

bool BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::setControlInput(const Input& controlInput)

Set the control input to the dynamical system.

Parameters
controlInput the value of the control input used to compute the system dynamics.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::LinearTimeInvariantSystem::dynamics(const std::chrono::nanoseconds& time, StateDerivative& stateDerivative)

Computes the system dynamics.

Parameters
time the time at witch the dynamics is computed.
stateDerivative
Returns true in case of success, false otherwise.

It return $Ax + Bu$