6 #include "pinocchio/algorithm/aba.hpp" 24 using namespace Eigen;
27 &aba<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd,VectorXd>,
28 bp::args(
"Model",
"Data",
"q",
"v",
"tau"),
29 "Compute ABA, store the result in Data::ddq and return it.",
30 bp::return_value_policy<bp::return_by_value>());
33 &aba<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd,VectorXd,Force>,
34 bp::args(
"Model",
"Data",
"q",
"v",
"tau",
"f_ext"),
35 "Compute ABA with external forces, store the result in Data::ddq and return it.",
36 bp::return_value_policy<bp::return_by_value>());
38 bp::def(
"computeMinverse",
40 bp::args(
"Model",
"Data",
"q"),
41 "Computes the inverse of the joint space inertia matrix using a variant of the Articulated Body algorithm.\n" 42 "The result is stored in data.Minv.",
43 bp::return_value_policy<bp::return_by_value>());
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
const Data::RowMatrixXs & computeMinverse_proxy(const Model &model, Data &data, const Eigen::VectorXd &q)
void make_symmetric(Eigen::MatrixBase< Matrix > &mat)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Main pinocchio namespace.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
JointCollectionTpl & model