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(Force) ForceAlignedVector;
16 
18  const Eigen::VectorXd & q)
19  {
21  res.setZero();
23  return res;
24  }
25 
27  const Eigen::VectorXd & q,
28  const ForceAlignedVector & fext)
29  {
31  res.setZero();
33  return res;
34  }
35 
36  bp::tuple computeRNEADerivatives(const Model & model, Data & data,
37  const Eigen::VectorXd & q,
38  const Eigen::VectorXd & v,
39  const Eigen::VectorXd & a)
40  {
43  return bp::make_tuple(make_ref(data.dtau_dq),
44  make_ref(data.dtau_dv),
45  make_ref(data.M));
46  }
47 
49  const Eigen::VectorXd & q,
50  const Eigen::VectorXd & v,
51  const Eigen::VectorXd & a,
52  const ForceAlignedVector & fext)
53  {
56  return bp::make_tuple(make_ref(data.dtau_dq),
57  make_ref(data.dtau_dv),
58  make_ref(data.M));
59  }
60 
62  {
63  using namespace Eigen;
64 
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"
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("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"
81  "Parameters:\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");
87 
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"
94  "Parameters:\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");
101 
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"
109  "Parameters:\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");
117  }
118 
119 
120 
121  } // namespace python
122 } // namespace pinocchio
pinocchio::python::VectorXd
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:16
boost::python
Eigen
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: multibody/data.hpp:29
pinocchio::DataTpl::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: multibody/data.hpp:59
pinocchio::python::make_symmetric
void make_symmetric(Eigen::MatrixBase< Matrix > &mat)
Definition: bindings/python/utils/eigen.hpp:24
pinocchio::python::computeStaticTorqueDerivatives
Data::MatrixXs computeStaticTorqueDerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const ForceAlignedVector &fext)
Definition: expose-rnea-derivatives.cpp:26
pinocchio::python::exposeRNEADerivatives
void exposeRNEADerivatives()
Definition: expose-rnea-derivatives.cpp:61
rnea-derivatives.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
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::computeGeneralizedGravityDerivatives
Data::MatrixXs computeGeneralizedGravityDerivatives(const Model &model, Data &data, const Eigen::VectorXd &q)
Definition: expose-rnea-derivatives.cpp:17
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:44
pinocchio::Force
ForceTpl< double, 0 > Force
Definition: spatial/fwd.hpp:58
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:747
pinocchio::python::computeRNEADerivatives
bp::tuple computeRNEADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a)
Definition: expose-rnea-derivatives.cpp:36
a
Vec3f a
pinocchio::python::computeRNEADerivatives_fext
bp::tuple computeRNEADerivatives_fext(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const ForceAlignedVector &fext)
Definition: expose-rnea-derivatives.cpp:48
pinocchio::python::PINOCCHIO_ALIGNED_STD_VECTOR
typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceAlignedVector
pinocchio::python::make_ref
Eigen::Ref< Matrix > make_ref(Eigen::PlainObjectBase< Matrix > &mat)
Definition: bindings/python/utils/eigen.hpp:17
pinocchio::ModelTpl
Definition: multibody/fwd.hpp:23
pinocchio::python::res
ReturnType res
Definition: bindings/python/spatial/explog.hpp:46
eigen.hpp
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:746
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:58