expose-rnea-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2021 CNRS INRIA
3 //
4 
8 
9 namespace pinocchio
10 {
11  namespace python
12  {
13 
14  namespace bp = boost::python;
15  typedef PINOCCHIO_ALIGNED_STD_VECTOR(context::Force) ForceAlignedVector;
16 
19  {
21  res.setZero();
23  return res;
24  }
25 
27  const context::Model & model,
29  const context::VectorXs & q,
30  const ForceAlignedVector & fext)
31  {
33  res.setZero();
35  return res;
36  }
37 
39  const context::Model & model,
41  const context::VectorXs & q,
42  const context::VectorXs & v,
43  const context::VectorXs & a)
44  {
47  return bp::make_tuple(make_ref(data.dtau_dq), make_ref(data.dtau_dv), make_ref(data.M));
48  }
49 
51  const context::Model & model,
53  const context::VectorXs & q,
54  const context::VectorXs & v,
55  const context::VectorXs & a,
56  const ForceAlignedVector & fext)
57  {
60  return bp::make_tuple(make_ref(data.dtau_dq), make_ref(data.dtau_dv), make_ref(data.M));
61  }
62 
64  {
65  bp::def(
66  "computeGeneralizedGravityDerivatives", 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"
70  "Parameters:\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");
75 
76  bp::def(
77  "computeStaticTorqueDerivatives", computeStaticTorqueDerivatives,
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"
82  "Parameters:\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 "
87  "model.njoints)\n"
88  "Returns: dtau_statique_dq\n");
89 
90  bp::def(
91  "computeRNEADerivatives", computeRNEADerivatives, bp::args("model", "data", "q", "v", "a"),
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"
97  "Parameters:\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");
104 
105  bp::def(
106  "computeRNEADerivatives", computeRNEADerivatives_fext,
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"
113  "Parameters:\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 "
120  "model.njoints)\n\n"
121  "Returns: (dtau_dq, dtau_dv, dtau_da)\n");
122  }
123 
124  } // namespace python
125 } // namespace pinocchio
pinocchio::DataTpl::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: multibody/data.hpp:74
boost::python
pinocchio::computeRNEADerivatives
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...
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::python::exposeRNEADerivatives
void exposeRNEADerivatives()
Definition: expose-rnea-derivatives.cpp:63
rnea-derivatives.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::context::Force
ForceTpl< Scalar, Options > Force
Definition: bindings/python/context/generic.hpp:55
pinocchio::python::computeRNEADerivatives
bp::tuple computeRNEADerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a)
Definition: expose-rnea-derivatives.cpp:38
pinocchio::computeStaticTorqueDerivatives
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....
pinocchio::python::PINOCCHIO_ALIGNED_STD_VECTOR
typedef PINOCCHIO_ALIGNED_STD_VECTOR(context::Force) ForceAlignedVector
pinocchio::python::computeRNEADerivatives_fext
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)
Definition: expose-rnea-derivatives.cpp:50
pinocchio::python::make_symmetric
void make_symmetric(const Eigen::MatrixBase< Matrix > &mat, const int mode=Eigen::Upper)
Definition: bindings/python/utils/eigen.hpp:24
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::computeGeneralizedGravityDerivatives
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...
algorithms.hpp
python
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::python::computeGeneralizedGravityDerivatives
context::Data::MatrixXs computeGeneralizedGravityDerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q)
Definition: expose-rnea-derivatives.cpp:17
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
a
Vec3f a
pinocchio::python::computeStaticTorqueDerivatives
context::Data::MatrixXs computeStaticTorqueDerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q, const ForceAlignedVector &fext)
Definition: expose-rnea-derivatives.cpp:26
pinocchio::python::make_ref
Eigen::Ref< Matrix > make_ref(const Eigen::PlainObjectBase< Matrix > &mat)
Definition: bindings/python/utils/eigen.hpp:17
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::res
ReturnType res
Definition: bindings/python/spatial/explog.hpp:68
eigen.hpp
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:35