Go to the documentation of this file.
28 const ForceAlignedVector & fext)
52 const ForceAlignedVector & fext)
63 using namespace Eigen;
65 bp::def(
"computeGeneralizedGravityDerivatives",
67 bp::args(
"model",
"data",
"q"),
68 "Computes the partial derivative of the generalized gravity contribution\n"
69 "with respect to the joint configuration.\n\n"
71 "\tmodel: model of the kinematic tree\n"
72 "\tdata: data related to the model\n"
73 "\tq: the joint configuration vector (size model.nq)\n"
74 "Returns: dtau_statique_dq\n");
76 bp::def(
"computeStaticTorqueDerivatives",
78 bp::args(
"model",
"data",
"q",
"fext"),
79 "Computes the partial derivative of the generalized gravity and external forces contributions (a.k.a static torque vector)\n"
80 "with respect to the joint configuration.\n\n"
82 "\tmodel: model of the kinematic tree\n"
83 "\tdata: data related to the model\n"
84 "\tq: the joint configuration vector (size model.nq)\n"
85 "\tfext: list of external forces expressed in the local frame of the joints (size model.njoints)\n"
86 "Returns: dtau_statique_dq\n");
88 bp::def(
"computeRNEADerivatives",
90 bp::args(
"model",
"data",
"q",
"v",
"a"),
91 "Computes the RNEA partial derivatives, store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da)\n"
92 "which correspond to the partial derivatives of the torque output with respect to the joint configuration,\n"
93 "velocity and acceleration vectors.\n\n"
95 "\tmodel: model of the kinematic tree\n"
96 "\tdata: data related to the model\n"
97 "\tq: the joint configuration vector (size model.nq)\n"
98 "\tv: the joint velocity vector (size model.nv)\n"
99 "\ta: the joint acceleration vector (size model.nv)\n\n"
100 "Returns: (dtau_dq, dtau_dv, dtau_da)\n");
102 bp::def(
"computeRNEADerivatives",
104 bp::args(
"model",
"data",
"q",
"v",
"a",
"fext"),
105 "Computes the RNEA partial derivatives with external contact foces,\n"
106 "store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da)\n"
107 "which correspond to the partial derivatives of the torque output with respect to the joint configuration,\n"
108 "velocity and acceleration vectors.\n\n"
110 "\tmodel: model of the kinematic tree\n"
111 "\tdata: data related to the model\n"
112 "\tq: the joint configuration vector (size model.nq)\n"
113 "\tv: the joint velocity vector (size model.nv)\n"
114 "\ta: the joint acceleration vector (size model.nv)\n"
115 "\tfext: list of external forces expressed in the local frame of the joints (size model.njoints)\n\n"
116 "Returns: (dtau_dq, dtau_dv, dtau_da)\n");
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
void computeRNEADerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
void make_symmetric(Eigen::MatrixBase< Matrix > &mat)
Data::MatrixXs computeStaticTorqueDerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const ForceAlignedVector &fext)
void exposeRNEADerivatives()
void computeStaticTorqueDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext, const Eigen::MatrixBase< ReturnMatrixType > &static_torque_partial_dq)
Computes the partial derivative of the generalized gravity and external forces contributions (a....
Data::MatrixXs computeGeneralizedGravityDerivatives(const Model &model, Data &data, const Eigen::VectorXd &q)
void computeGeneralizedGravityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< ReturnMatrixType > &gravity_partial_dq)
Computes the partial derivative of the generalized gravity contribution with respect to the joint con...
ForceTpl< double, 0 > Force
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
bp::tuple computeRNEADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a)
bp::tuple computeRNEADerivatives_fext(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const ForceAlignedVector &fext)
typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceAlignedVector
Eigen::Ref< Matrix > make_ref(Eigen::PlainObjectBase< Matrix > &mat)
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:58