class
FloatingBaseSystemAccelerationKinematicsFloatingBaseSystemAccelerationKinematics describes the kinematics of a floating base system at the acceleration level.
It inherits from a generic DynamicalSystem where:
- The State is represented as a named tuple with the following parameters:
Name | Type | Description |
---|---|---|
p | Eigen::Vector3d | Base position expressed in the inertial frame. |
R | manif::SO3d | Base orientation. The rotation matrix ( {}^I R_b ) transforms vectors expressed in the base frame to the inertial frame. |
s | Eigen::VectorXd | Joint positions (in radians). |
dp | Eigen::Vector3d | Base linear velocity (i.e., time derivative of p ), expressed in the inertial frame. (mixed representation) |
omega | manif::SO3d::Tangent | Base angular velocity, expressed in the inertial frame (using left trivialization). |
ds | Eigen::VectorXd | Joint velocities (in rad/s). |
- The StateDerivative is represented as a named tuple with the following parameters:
Name | Type | Description |
---|---|---|
dp | Eigen::Vector3d | Time derivative of the base position (i.e., base linear velocity). |
omega | manif::SO3d::Tangent | Time derivative of the base orientation (related to angular velocity). |
ds | Eigen::VectorXd | Time derivative of the joint positions (i.e., joint velocities). |
ddp | Eigen::Vector3d | Base linear acceleration (second time derivative of p ). |
domega | manif::SO3d::Tangent | Base angular acceleration (time derivative of omega ). |
dds | Eigen::VectorXd | Joint accelerations (in rad/s²). |
- The Input to the system is represented as a named tuple with the following parameters:
Name | Type | Description |
---|---|---|
dtwist | Twist (e.g., Eigen::Matrix<double, 6, 1> ) | Base twist in mixed representation (typically combining both linear and angular components). |
dds | Eigen::VectorXd | Joint accelerations (in rad/s²). |
This formulation encapsulates both the instantaneous state (including positions and velocities) and their time derivatives (accelerations), while employing Lie group representations (i.e., ( SO(3) )) for handling rotations.
Base classes
-
template<class _Derived>class DynamicalSystem<FloatingBaseSystemAccelerationKinematics>
- DynamicalSystem defines a continuous time dynamical system, i.e.
Public functions
-
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 floating based system dynamics.
Function documentation
bool BipedalLocomotion:: ContinuousDynamicalSystem:: FloatingBaseSystemAccelerationKinematics:: 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:: FloatingBaseSystemAccelerationKinematics:: 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:: FloatingBaseSystemAccelerationKinematics:: dynamics(const std::chrono::nanoseconds& time,
StateDerivative& stateDerivative)
Computes the floating based system dynamics.
Parameters | |
---|---|
time | the time at witch the dynamics is computed. |
stateDerivative | |
Returns | true in case of success, false otherwise. |
It return .