Go to the documentation of this file.
30 const ForceAlignedVector & fext)
56 const ForceAlignedVector & fext)
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");
78 bp::args(
"model",
"data",
"q",
"fext"),
79 "Computes the partial derivative of the generalized gravity and external forces "
80 "contributions (a.k.a static torque vector)\n"
81 "with respect to the joint configuration.\n\n"
83 "\tmodel: model of the kinematic tree\n"
84 "\tdata: data related to the model\n"
85 "\tq: the joint configuration vector (size model.nq)\n"
86 "\tfext: list of external forces expressed in the local frame of the joints (size "
88 "Returns: dtau_statique_dq\n");
92 "Computes the RNEA partial derivatives, store the result in data.dtau_dq, "
93 "data.dtau_dv and data.M (aka dtau_da)\n"
94 "which correspond to the partial derivatives of the torque output with respect to "
95 "the joint configuration,\n"
96 "velocity and acceleration vectors.\n\n"
98 "\tmodel: model of the kinematic tree\n"
99 "\tdata: data related to the model\n"
100 "\tq: the joint configuration vector (size model.nq)\n"
101 "\tv: the joint velocity vector (size model.nv)\n"
102 "\ta: the joint acceleration vector (size model.nv)\n\n"
103 "Returns: (dtau_dq, dtau_dv, dtau_da)\n");
107 bp::args(
"model",
"data",
"q",
"v",
"a",
"fext"),
108 "Computes the RNEA partial derivatives with external contact foces,\n"
109 "store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da)\n"
110 "which correspond to the partial derivatives of the torque output with respect to "
111 "the joint configuration,\n"
112 "velocity and acceleration vectors.\n\n"
114 "\tmodel: model of the kinematic tree\n"
115 "\tdata: data related to the model\n"
116 "\tq: the joint configuration vector (size model.nq)\n"
117 "\tv: the joint velocity vector (size model.nv)\n"
118 "\ta: the joint acceleration vector (size model.nv)\n"
119 "\tfext: list of external forces expressed in the local frame of the joints (size "
121 "Returns: (dtau_dq, dtau_dv, dtau_da)\n");
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
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...
void exposeRNEADerivatives()
ForceTpl< Scalar, Options > Force
bp::tuple computeRNEADerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a)
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....
typedef PINOCCHIO_ALIGNED_STD_VECTOR(context::Force) ForceAlignedVector
bp::tuple computeRNEADerivatives_fext(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a, const ForceAlignedVector &fext)
void make_symmetric(const Eigen::MatrixBase< Matrix > &mat, const int mode=Eigen::Upper)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
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...
context::Data::MatrixXs computeGeneralizedGravityDerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
context::Data::MatrixXs computeStaticTorqueDerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q, const ForceAlignedVector &fext)
Eigen::Ref< Matrix > make_ref(const Eigen::PlainObjectBase< Matrix > &mat)
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29