10 #ifndef SPATIAL_DYN_ALGORITHMS_INVERSE_DYNAMICS_H_
11 #define SPATIAL_DYN_ALGORITHMS_INVERSE_DYNAMICS_H_
15 #include "spatial_dyn/eigen/spatial_math.h"
16 #include "spatial_dyn/structs/articulated_body.h"
17 #include "spatial_dyn/structs/options.h"
46 Eigen::VectorXd
InverseDynamics(
const ArticulatedBody& ab,
const Eigen::VectorXd& ddq,
47 const std::map<size_t, SpatialForced>& f_external = {},
48 const InverseDynamicsOptions& options = {});
74 const Eigen::VectorXd&
Gravity(
const ArticulatedBody& ab);
91 const std::map<size_t, SpatialForced>& f_external = {});
106 Eigen::VectorXd
Friction(
const ArticulatedBody& ab, Eigen::Ref<const Eigen::VectorXd> tau,
107 bool compensate =
true,
double stiction_epsilon = 0.01);
121 const Eigen::MatrixXd&
Inertia(
const ArticulatedBody& ab);
134 const SpatialInertiad&
CompositeInertia(
const ArticulatedBody& ab,
int link = 0);
const Eigen::VectorXd & Gravity(const ArticulatedBody &ab)
Definition: inverse_dynamics.cc:144
const Eigen::VectorXd & CentrifugalCoriolis(const ArticulatedBody &ab)
Definition: inverse_dynamics.cc:99
Eigen::VectorXd Friction(const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > tau, bool compensate, double stiction_epsilon)
Definition: inverse_dynamics.cc:199
Eigen::VectorXd InverseDynamics(const ArticulatedBody &ab, const Eigen::VectorXd &ddq, const std::map< size_t, SpatialForced > &f_external, const InverseDynamicsOptions &options)
Definition: inverse_dynamics.cc:21
const Eigen::MatrixXd & Inertia(const ArticulatedBody &ab)
Definition: inverse_dynamics.cc:223
const SpatialInertiad & CompositeInertia(const ArticulatedBody &ab, int link)
Definition: inverse_dynamics.cc:259
Eigen::VectorXd ExternalTorques(const ArticulatedBody &ab, const std::map< size_t, SpatialForced > &f_external)
Definition: inverse_dynamics.cc:171
Definition: discrete_dynamics.cc:21