Directory: | ./ |
---|---|
File: | bindings/python/algorithm/expose-aba.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 17 | 24 | 70.8% |
Branches: | 32 | 64 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2015-2021 CNRS INRIA | ||
3 | // | ||
4 | |||
5 | #include "pinocchio/bindings/python/algorithm/algorithms.hpp" | ||
6 | #include "pinocchio/bindings/python/utils/namespace.hpp" | ||
7 | |||
8 | #include "pinocchio/algorithm/aba.hpp" | ||
9 | #include "pinocchio/bindings/python/utils/eigen.hpp" | ||
10 | |||
11 | namespace pinocchio | ||
12 | { | ||
13 | namespace python | ||
14 | { | ||
15 | |||
16 | 2 | const context::Data::RowMatrixXs & computeMinverse_proxy( | |
17 | const context::Model & model, context::Data & data, const context::VectorXs & q) | ||
18 | { | ||
19 | 2 | computeMinverse(model, data, q); | |
20 | 2 | make_symmetric(data.Minv); | |
21 | 2 | return data.Minv; | |
22 | } | ||
23 | |||
24 | const context::Data::RowMatrixXs & | ||
25 | ✗ | computeMinverse_min_proxy(const context::Model & model, context::Data & data) | |
26 | { | ||
27 | ✗ | pinocchio::computeMinverse(model, data); | |
28 | ✗ | make_symmetric(data.Minv); | |
29 | ✗ | return data.Minv; | |
30 | } | ||
31 | |||
32 | 69 | void exposeABA() | |
33 | { | ||
34 | typedef context::Scalar Scalar; | ||
35 | typedef context::VectorXs VectorXs; | ||
36 | enum | ||
37 | { | ||
38 | Options = context::Options | ||
39 | }; | ||
40 | |||
41 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | bp::def( |
42 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | "computeMinverse", &computeMinverse_proxy, bp::args("model", "data", "q"), |
43 | "Computes the inverse of the joint space inertia matrix using an extension of the " | ||
44 | "Articulated Body algorithm.\n" | ||
45 | "The result is stored in data.Minv.\n" | ||
46 | "Parameters:\n" | ||
47 | "\t model: Model of the kinematic tree\n" | ||
48 | "\t data: Data related to the kinematic tree\n" | ||
49 | "\t q: joint configuration (size model.nq)", | ||
50 | ✗ | bp::return_value_policy<bp::return_by_value>()); | |
51 | |||
52 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | bp::def( |
53 | "aba", &aba<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>, | ||
54 |
9/18✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 69 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 69 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 69 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 69 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 69 times.
✗ Branch 26 not taken.
|
207 | (bp::arg("model"), bp::arg("data"), bp::arg("q"), bp::arg("v"), bp::arg("tau"), |
55 |
3/6✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
|
138 | bp::arg("convention") = pinocchio::Convention::LOCAL), |
56 | "Compute ABA, store the result in data.ddq and return it.\n" | ||
57 | "Parameters:\n" | ||
58 | "\t model: Model of the kinematic tree\n" | ||
59 | "\t data: Data related to the kinematic tree\n" | ||
60 | "\t q: joint configuration (size model.nq)\n" | ||
61 | "\t tau: joint velocity (size model.nv)\n" | ||
62 | "\t v: joint torque (size model.nv)" | ||
63 | "\t convention: Convention to use", | ||
64 | ✗ | bp::return_value_policy<bp::return_by_value>()); | |
65 | |||
66 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | bp::def( |
67 | "aba", | ||
68 | &aba< | ||
69 | Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs, context::Force>, | ||
70 |
10/20✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 69 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 69 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 69 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 69 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 69 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 69 times.
✗ Branch 29 not taken.
|
207 | (bp::arg("model"), bp::arg("data"), bp::arg("q"), bp::arg("v"), bp::arg("tau"), |
71 |
4/8✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
|
207 | bp::arg("fext"), bp::arg("convention") = pinocchio::Convention::LOCAL), |
72 | "Compute ABA with external forces, store the result in data.ddq and return it.\n" | ||
73 | "Parameters:\n" | ||
74 | "\t model: Model of the kinematic tree\n" | ||
75 | "\t data: Data related to the kinematic tree\n" | ||
76 | "\t q: joint configuration (size model.nq)\n" | ||
77 | "\t v: joint velocity (size model.nv)\n" | ||
78 | "\t tau: joint torque (size model.nv)\n" | ||
79 | "\t fext: vector of external forces expressed in the local frame of the joint (size " | ||
80 | "model.njoints)" | ||
81 | "\t convention: Convention to use", | ||
82 | ✗ | bp::return_value_policy<bp::return_by_value>()); | |
83 | |||
84 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | bp::def( |
85 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | "computeMinverse", &computeMinverse_min_proxy, bp::args("model", "data"), |
86 | "Computes the inverse of the joint space inertia matrix using an extension of the " | ||
87 | "Articulated Body algorithm.\n" | ||
88 | "The result is stored in data.Minv.\n" | ||
89 | "Remarks: pinocchio.aba should have been called first.\n" | ||
90 | "Parameters:\n" | ||
91 | "\t model: Model of the kinematic tree\n" | ||
92 | "\t data: Data related to the kinematic tree", | ||
93 | 69 | bp::return_value_policy<bp::return_by_value>()); | |
94 | 69 | } | |
95 | |||
96 | } // namespace python | ||
97 | } // namespace pinocchio | ||
98 |