spatial-dyn
Classes | Functions
Forward Dynamics

Classes

struct  spatial_dyn::ForwardDynamicsOptions
 

Functions

Eigen::VectorXd spatial_dyn::ForwardDynamics (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > tau, const std::map< size_t, SpatialForced > &f_external, const ForwardDynamicsOptions &options)
 
Eigen::VectorXd spatial_dyn::ForwardDynamicsAba (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > tau, const std::map< size_t, SpatialForced > &f_external, const ForwardDynamicsOptions &options)
 
const Eigen::LDLT< Eigen::MatrixXd > & spatial_dyn::InertiaInverse (const ArticulatedBody &ab)
 
const Eigen::MatrixXd & spatial_dyn::InertiaInverseAba (const ArticulatedBody &ab)
 

Detailed Description

C++ implementation of spatial_dyn forward dynamics algorithms.

See also
Python: py_forward_dynamics

Function Documentation

◆ ForwardDynamics()

Eigen::VectorXd spatial_dyn::ForwardDynamics ( const ArticulatedBody ab,
Eigen::Ref< const Eigen::VectorXd >  tau,
const std::map< size_t, SpatialForced > &  f_external = {},
const ForwardDynamicsOptions options = {} 
)

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
abArticulatedBody.
tauApplied joint torques.
f_externalMap 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.
optionsForwardDynamicsOptions.
Returns
Joint accelerations.
See also
Python: spatialdyn.forward_dynamics()

◆ ForwardDynamicsAba()

Eigen::VectorXd spatial_dyn::ForwardDynamicsAba ( const ArticulatedBody ab,
Eigen::Ref< const Eigen::VectorXd >  tau,
const std::map< size_t, SpatialForced > &  f_external = {},
const ForwardDynamicsOptions options = {} 
)

Compute the forward dynamics with ABA.

Uses the Articulated Body Algorithm (ABA) to compute the forward dynamics in O(n) time.

Parameters
abArticulatedBody.
tauApplied joint torques.
f_externalMap 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.
optionsForwardDynamicsOptions.
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
abArticulatedBody.
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
abArticulatedBody.
Returns
Reference to the cached inverse inertia matrix.
See also
Python: spatialdyn.inertia_inverse_aba()