|
Eigen::MatrixXd | spatial_dyn::InverseDynamicsPositionDerivative (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > ddq, const std::map< size_t, SpatialForced > &f_external, const InverseDynamicsOptions &options) |
|
Eigen::MatrixXd | spatial_dyn::InverseDynamicsVelocityDerivative (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > ddq, const std::map< size_t, SpatialForced > &f_external, const InverseDynamicsOptions &options) |
|
Eigen::VectorXd | spatial_dyn::InverseDynamics (const ArticulatedBody &ab, const Eigen::VectorXd &ddq, const std::map< size_t, SpatialForced > &f_external, const InverseDynamicsOptions &options) |
|
const Eigen::VectorXd & | spatial_dyn::CentrifugalCoriolis (const ArticulatedBody &ab) |
|
const Eigen::VectorXd & | spatial_dyn::Gravity (const ArticulatedBody &ab) |
|
Eigen::VectorXd | spatial_dyn::ExternalTorques (const ArticulatedBody &ab, const std::map< size_t, SpatialForced > &f_external) |
|
Eigen::VectorXd | spatial_dyn::Friction (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > tau, bool compensate, double stiction_epsilon) |
|
const Eigen::MatrixXd & | spatial_dyn::Inertia (const ArticulatedBody &ab) |
|
const SpatialInertiad & | spatial_dyn::CompositeInertia (const ArticulatedBody &ab, int link) |
|
C++ implementation of spatial_dyn inverse dynamics algorithms.
- See also
- Python: py_inverse_dynamics
◆ CentrifugalCoriolis()
const Eigen::VectorXd & spatial_dyn::CentrifugalCoriolis |
( |
const ArticulatedBody & |
ab | ) |
|
Compute the centrifugal/Coriolis compensation torques.
Implements the Recursive Newton Euler Algorithm (RNEA) to compute the inverse dynamic torques in O(n) time. Results are cached such that subsequent calls with the same q
and dq
will return in O(1) time.
- Parameters
-
- Returns
- Reference to the cached centrifugal/Coriolis torques.
- See also
- Python: spatialdyn.centrifugal_coriolis()
◆ CompositeInertia()
Compute the composite rigid body inertia from the given link to the end-effector.
Calls the Inertia() to compute the inertia with the Composite Rigid Body Algorithm (CRBA) in O(n^2) time. Results are cached such that subsequent calls with the same q
will return in O(1) time.
- Parameters
-
- Returns
- Spatial Inertia
- See also
- Python: spatialdyn.composite_inertia()
◆ ExternalTorques()
Compute the torques to compensate external forces applied on the rigid bodies.
Implements the Recursive Newton Euler Algorithm (RNEA) to compute the inverse dynamic torques in O(n) time. Results are cached such that subsequent calls with the same q
and dq
will return in O(1) time.
- Parameters
-
ab | ArticulatedBody. |
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. |
- Returns
- External torques.
- See also
- Python: spatialdyn.external_torque()
◆ Friction()
Eigen::VectorXd spatial_dyn::Friction |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
tau, |
|
|
bool |
compensate = true , |
|
|
double |
stiction_epsilon = 0.01 |
|
) |
| |
Compute Coulomb and viscous joint friction torques.
Friction torques are computed in O(n) time.
- Parameters
-
ab | ArticulatedBody. |
tau | Applied torques (for stiction). |
compensate | Return friction compensation torques as opposed to resulting friction torques. |
stiction_epsilon | Velocity threshold for stiction activation. |
- Returns
- Friction torques.
- See also
- Python: spatialdyn.friction()
◆ Gravity()
Compute the gravity compensation torques.
Implements the Recursive Newton Euler Algorithm (RNEA) to compute the inverse dynamic torques in O(n) time. Results are cached such that subsequent calls with the same q
and dq
will return in O(1) time.
- Parameters
-
- Returns
- Reference to the cached gravity torques.
- See also
- Python: spatialdyn.gravity()
◆ Inertia()
Compute the joint space inertia matrix.
Implements the Composite Rigid Body Algorithm (CRBA) to compute the 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
- Inertia matrix.
- See also
- Forward dynamics: spatial_dyn::InertiaInverse()
-
Python: spatialdyn.inertia()
◆ InverseDynamics()
Compute the inverse dynamics torques given the desired acceleration ddq
.
Implements the Recursive Newton Euler Algorithm (RNEA) to compute the inverse dynamic torques in O(n) time.
- Parameters
-
ab | ArticulatedBody. |
ddq | Desired joint acceleration. |
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 | InverseDynamicsOptions. |
- Returns
- Inverse dynamics torques.
- See also
- Python: spatialdyn.inverse_dynamics()
◆ InverseDynamicsPositionDerivative()
Eigen::MatrixXd spatial_dyn::InverseDynamicsPositionDerivative |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
ddq, |
|
|
const std::map< size_t, SpatialForced > & |
f_external = {} , |
|
|
const InverseDynamicsOptions & |
options = { true, true } |
|
) |
| |
Compute the inverse dynamics torques given the desired acceleration ddq
.
Implements the Recursive Newton Euler Algorithm (RNEA) to compute the inverse dynamic torques in O(n) time.
- Parameters
-
ab | ArticulatedBody. |
ddq | Desired joint acceleration. |
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 | InverseDynamicsOptions. |
- Returns
- Inverse dynamics torques.
- See also
- Python: spatialdyn.inverse_dynamics()