expose-rnea.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
7 #include "pinocchio/algorithm/rnea.hpp"
8 
9 namespace pinocchio
10 {
11  namespace python
12  {
13 
14  void exposeRNEA()
15  {
16  using namespace Eigen;
17 
18  bp::def("rnea",
19  &rnea<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd,VectorXd>,
20  bp::args("model","data","q","v","a"),
21  "Compute the RNEA, store the result in Data and return it.\n\n"
22  "Parameters:\n"
23  "\tmodel: model of the kinematic tree\n"
24  "\tdata: data related to the model\n"
25  "\tq: the joint configuration vector (size model.nq)\n"
26  "\tv: the joint velocity vector (size model.nv)\n"
27  "\ta: the joint acceleration vector (size model.nv)\n",
28  bp::return_value_policy<bp::return_by_value>());
29 
30  bp::def("rnea",
31  &rnea<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd,VectorXd,Force>,
32  bp::args("model","data","q","v","a","fext"),
33  "Compute the RNEA with external forces, store the result in Data and return it.\n\n"
34  "Parameters:\n"
35  "\tmodel: model of the kinematic tree\n"
36  "\tdata: data related to the model\n"
37  "\tq: the joint configuration vector (size model.nq)\n"
38  "\tv: the joint velocity vector (size model.nv)\n"
39  "\ta: the joint acceleration vector (size model.nv)\n"
40  "\tfext: list of external forces expressed in the local frame of the joints (size model.njoints)\n",
41  bp::return_value_policy<bp::return_by_value>());
42 
43  bp::def("nonLinearEffects",
44  &nonLinearEffects<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd>,
45  bp::args("model","data","q","v"),
46  "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), store the result in Data and return it.\n\n"
47  "Parameters:\n"
48  "\tmodel: model of the kinematic tree\n"
49  "\tdata: data related to the model\n"
50  "\tq: the joint configuration vector (size model.nq)\n"
51  "\tv: the joint velocity vector (size model.nv)\n",
52  bp::return_value_policy<bp::return_by_value>());
53 
54  bp::def("computeGeneralizedGravity",
55  &computeGeneralizedGravity<double,0,JointCollectionDefaultTpl,VectorXd>,
56  bp::args("model","data","q"),
57  "Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store the result in data.g and return it.\n\n"
58  "Parameters:\n"
59  "\tmodel: model of the kinematic tree\n"
60  "\tdata: data related to the model\n"
61  "\tq: the joint configuration vector (size model.nq)\n",
62  bp::return_value_policy<bp::return_by_value>());
63 
64  bp::def("computeStaticTorque",
65  &computeStaticTorque<double,0,JointCollectionDefaultTpl,VectorXd>,
66  bp::args("model","data","q","fext"),
67  "Computes the generalized static torque contribution g(q) - J.T f_ext of the Lagrangian dynamics, store the result in data.tau and return it.\n\n"
68  "Parameters:\n"
69  "\tmodel: model of the kinematic tree\n"
70  "\tdata: data related to the model\n"
71  "\tq: the joint configuration vector (size model.nq)\n"
72  "\tfext: list of external forces expressed in the local frame of the joints (size model.njoints)\n",
73  bp::return_value_policy<bp::return_by_value>());
74 
75  bp::def("computeCoriolisMatrix",
76  &computeCoriolisMatrix<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd>,
77  bp::args("model","data","q","v"),
78  "Compute the Coriolis Matrix C(q,v) of the Lagrangian dynamics, store the result in data.C and return it.\n\n"
79  "Parameters:\n"
80  "\tmodel: model of the kinematic tree\n"
81  "\tdata: data related to the model\n"
82  "\tq: the joint configuration vector (size model.nq)\n"
83  "\tv: the joint velocity vector (size model.nv)\n",
84  bp::return_value_policy<bp::return_by_value>());
85 
86  bp::def("getCoriolisMatrix",
87  &getCoriolisMatrix<double,0,JointCollectionDefaultTpl>,
88  bp::args("model","data"),
89  "Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of the derivative algorithms, store the result in data.C and return it.\n\n"
90  "Parameters:\n"
91  "\tmodel: model of the kinematic tree\n"
92  "\tdata: data related to the model\n",
93  bp::return_value_policy<bp::return_by_value>());
94 
95  }
96 
97  } // namespace python
98 } // namespace pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:30