C++ implementation of spatial_dyn forward dynamics algorithms.
- See also
- Python: py_forward_dynamics
◆ ForwardDynamics()
Compute the forward dynamics by inverting the inverse dynamics.
Uses RNEA to compute the bias torques and inverts the inertia matrix computed via CRBA to output the joint accelerations in O(n^2) time.
- Parameters
-
ab | ArticulatedBody. |
tau | Applied joint torques. |
f_external | Map of (index, force) pairs where the force is the sum of all external spatial forces (represented in the world frame) applied to the associated rigid body index. |
options | ForwardDynamicsOptions. |
- Returns
- Joint accelerations.
- See also
- Python: spatialdyn.forward_dynamics()
◆ ForwardDynamicsAba()
Compute the forward dynamics with ABA.
Uses the Articulated Body Algorithm (ABA) to compute the forward dynamics in O(n) time.
- Parameters
-
ab | ArticulatedBody. |
tau | Applied joint torques. |
f_external | Map of (index, force) pairs where the force is the sum of all external spatial forces (represented in the world frame) applied to the associated rigid body index. |
options | ForwardDynamicsOptions. |
- Returns
- Joint accelerations.
- See also
- Python: spatialdyn.forward_dynamics_aba()
◆ InertiaInverse()
const Eigen::LDLT< Eigen::MatrixXd > & spatial_dyn::InertiaInverse |
( |
const ArticulatedBody & |
ab | ) |
|
Compute the Cholesky decomposition of the joint space inertia matrix.
Uses CRBA to compute the inertia matrix in O(n^2) time, and finds the Cholesky decomposition in O(n^2) time. Results are cached such that subsequent calls with same q
will return in O(1) time.
- Parameters
-
- Returns
- Reference to the cached Cholesky decomposition of the inertia matrix.
- See also
- Python: spatialdyn.inertia_inverse()
◆ InertiaInverseAba()
const Eigen::MatrixXd & spatial_dyn::InertiaInverseAba |
( |
const ArticulatedBody & |
ab | ) |
|
Compute the inverse of the joint space inertia matrix with ABA.
Uses ABA to compute the inverse inertia matrix in O(n^2) time. Results are cached such that subsequent calls with the same q
will return in O(1) time.
- Parameters
-
- Returns
- Reference to the cached inverse inertia matrix.
- See also
- Python: spatialdyn.inertia_inverse_aba()