GCC Code Coverage Report


Directory: ./
File: bindings/python/algorithm/expose-rnea.cpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 17 23 73.9%
Branches: 14 28 50.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 //
4
5 #include "pinocchio/bindings/python/algorithm/algorithms.hpp"
6 #include "pinocchio/algorithm/rnea.hpp"
7
8 namespace pinocchio
9 {
10 namespace python
11 {
12
13 20 void exposeRNEA()
14 {
15 typedef context::Scalar Scalar;
16 typedef context::VectorXs VectorXs;
17 enum
18 {
19 Options = context::Options
20 };
21
22
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
23 "rnea", &rnea<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>,
24
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q", "v", "a"),
25 "Compute the RNEA, store the result in Data and return it.\n\n"
26 "Parameters:\n"
27 "\tmodel: model of the kinematic tree\n"
28 "\tdata: data related to the model\n"
29 "\tq: the joint configuration vector (size model.nq)\n"
30 "\tv: the joint velocity vector (size model.nv)\n"
31 "\ta: the joint acceleration vector (size model.nv)\n",
32 bp::return_value_policy<bp::return_by_value>());
33
34
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
35 "rnea",
36 &rnea<
37 Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs, context::Force>,
38
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q", "v", "a", "fext"),
39 "Compute the RNEA with external forces, store the result in Data and return it.\n\n"
40 "Parameters:\n"
41 "\tmodel: model of the kinematic tree\n"
42 "\tdata: data related to the model\n"
43 "\tq: the joint configuration vector (size model.nq)\n"
44 "\tv: the joint velocity vector (size model.nv)\n"
45 "\ta: the joint acceleration vector (size model.nv)\n"
46 "\tfext: list of external forces expressed in the local frame of the joints (size "
47 "model.njoints)\n",
48 bp::return_value_policy<bp::return_by_value>());
49
50
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
51 "nonLinearEffects",
52 &nonLinearEffects<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>,
53
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q", "v"),
54 "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), "
55 "store the result in Data and return it.\n\n"
56 "Parameters:\n"
57 "\tmodel: model of the kinematic tree\n"
58 "\tdata: data related to the model\n"
59 "\tq: the joint configuration vector (size model.nq)\n"
60 "\tv: the joint velocity vector (size model.nv)\n",
61 bp::return_value_policy<bp::return_by_value>());
62
63
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
64 "computeGeneralizedGravity",
65 &computeGeneralizedGravity<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
66
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q"),
67 "Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store "
68 "the result in data.g and return it.\n\n"
69 "Parameters:\n"
70 "\tmodel: model of the kinematic tree\n"
71 "\tdata: data related to the model\n"
72 "\tq: the joint configuration vector (size model.nq)\n",
73 bp::return_value_policy<bp::return_by_value>());
74
75
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
76 "computeStaticTorque",
77 &computeStaticTorque<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
78
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q", "fext"),
79 "Computes the generalized static torque contribution g(q) - J.T f_ext of the "
80 "Lagrangian dynamics, store the result in data.tau and return it.\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 "
86 "model.njoints)\n",
87 bp::return_value_policy<bp::return_by_value>());
88
89
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
90 "computeCoriolisMatrix",
91 &computeCoriolisMatrix<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>,
92
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data", "q", "v"),
93 "Compute the Coriolis Matrix C(q,v) of the Lagrangian dynamics, store the result in data.C "
94 "and return it.\n\n"
95 "Parameters:\n"
96 "\tmodel: model of the kinematic tree\n"
97 "\tdata: data related to the model\n"
98 "\tq: the joint configuration vector (size model.nq)\n"
99 "\tv: the joint velocity vector (size model.nv)\n",
100 bp::return_value_policy<bp::return_by_value>());
101
102
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 bp::def(
103 "getCoriolisMatrix", &getCoriolisMatrix<Scalar, Options, JointCollectionDefaultTpl>,
104
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 bp::args("model", "data"),
105 "Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of "
106 "the derivative algorithms, store the result in data.C and return it.\n\n"
107 "Parameters:\n"
108 "\tmodel: model of the kinematic tree\n"
109 "\tdata: data related to the model\n",
110 20 bp::return_value_policy<bp::return_by_value>());
111 20 }
112
113 } // namespace python
114 } // namespace pinocchio
115