Directory: | ./ |
---|---|
File: | include/pinocchio/algorithm/proximal.hpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 21 | 33 | 63.6% |
Branches: | 11 | 138 | 8.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2019-2022 INRIA | ||
3 | // | ||
4 | |||
5 | #ifndef __pinocchio_algorithm_proximal_hpp__ | ||
6 | #define __pinocchio_algorithm_proximal_hpp__ | ||
7 | |||
8 | #include <Eigen/Core> | ||
9 | #include "pinocchio/multibody/model.hpp" | ||
10 | #include "pinocchio/multibody/data.hpp" | ||
11 | |||
12 | namespace pinocchio | ||
13 | { | ||
14 | |||
15 | /// | ||
16 | /// \brief Structure containing all the settings parameters for the proximal algorithms. | ||
17 | /// | ||
18 | /// \tparam _Scalar Scalar type of the for the regularization and the accuracy parameter. | ||
19 | /// | ||
20 | /// It contains the accuracy, the maximal number of iterations and the regularization factor | ||
21 | /// common to all proximal algorithms. | ||
22 | /// | ||
23 | template<typename _Scalar> | ||
24 | struct ProximalSettingsTpl | ||
25 | { | ||
26 | typedef _Scalar Scalar; | ||
27 | |||
28 | /// \brief Default constructor. | ||
29 | 216 | ProximalSettingsTpl() | |
30 | 216 | : absolute_accuracy(Eigen::NumTraits<Scalar>::dummy_precision()) | |
31 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
216 | , relative_accuracy(Eigen::NumTraits<Scalar>::dummy_precision()) |
32 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
216 | , mu(0) |
33 | 216 | , max_iter(1) | |
34 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
216 | , absolute_residual(-1.) |
35 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
216 | , relative_residual(-1.) |
36 | 216 | , iter(0) | |
37 | { | ||
38 | 216 | } | |
39 | |||
40 | /// | ||
41 | /// \brief Constructor with all the setting parameters. | ||
42 | /// | ||
43 | 43 | ProximalSettingsTpl(const Scalar accuracy, const Scalar mu, const int max_iter) | |
44 | 43 | : absolute_accuracy(accuracy) | |
45 |
0/2✗ Branch 1 not taken.
✗ Branch 2 not taken.
|
43 | , relative_accuracy(accuracy) |
46 |
0/2✗ Branch 1 not taken.
✗ Branch 2 not taken.
|
43 | , mu(mu) |
47 | 43 | , max_iter(max_iter) | |
48 |
0/2✗ Branch 1 not taken.
✗ Branch 2 not taken.
|
43 | , absolute_residual(-1.) |
49 |
0/2✗ Branch 1 not taken.
✗ Branch 2 not taken.
|
43 | , relative_residual(-1.) |
50 | 43 | , iter(0) | |
51 | { | ||
52 |
3/22✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 43 times.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 14 not taken.
✗ Branch 15 not taken.
✗ Branch 17 not taken.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✗ Branch 22 not taken.
✗ Branch 24 not taken.
✗ Branch 25 not taken.
✗ Branch 27 not taken.
✗ Branch 28 not taken.
|
43 | PINOCCHIO_CHECK_INPUT_ARGUMENT( |
53 | check_expression_if_real<Scalar>(accuracy >= 0.) && "Accuracy must be positive."); | ||
54 |
3/22✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 43 times.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 14 not taken.
✗ Branch 15 not taken.
✗ Branch 17 not taken.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✗ Branch 22 not taken.
✗ Branch 24 not taken.
✗ Branch 25 not taken.
✗ Branch 27 not taken.
✗ Branch 28 not taken.
|
43 | PINOCCHIO_CHECK_INPUT_ARGUMENT( |
55 | check_expression_if_real<Scalar>(mu >= 0.) && "mu must be positive"); | ||
56 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 43 times.
|
43 | assert(max_iter >= 1 && "max_iter must be greater or equal to 1"); |
57 | 43 | } | |
58 | |||
59 | /// | ||
60 | /// \brief Constructor with all the setting parameters. | ||
61 | /// | ||
62 | ✗ | ProximalSettingsTpl( | |
63 | const Scalar absolute_accuracy, | ||
64 | const Scalar relative_accuracy, | ||
65 | const Scalar mu, | ||
66 | const int max_iter) | ||
67 | ✗ | : absolute_accuracy(absolute_accuracy) | |
68 | ✗ | , relative_accuracy(relative_accuracy) | |
69 | ✗ | , mu(mu) | |
70 | ✗ | , max_iter(max_iter) | |
71 | ✗ | , absolute_residual(-1.) | |
72 | ✗ | , relative_residual(-1.) | |
73 | ✗ | , iter(0) | |
74 | { | ||
75 | ✗ | PINOCCHIO_CHECK_INPUT_ARGUMENT( | |
76 | check_expression_if_real<Scalar>(absolute_accuracy >= 0.) | ||
77 | && "Absolute accuracy must be positive."); | ||
78 | ✗ | PINOCCHIO_CHECK_INPUT_ARGUMENT( | |
79 | check_expression_if_real<Scalar>(relative_accuracy >= 0.) | ||
80 | && "Relative accuracy must be positive."); | ||
81 | ✗ | PINOCCHIO_CHECK_INPUT_ARGUMENT( | |
82 | check_expression_if_real<Scalar>(mu >= 0.) && "mu must be positive"); | ||
83 | ✗ | assert(max_iter >= 1 && "max_iter must be greater or equal to 1"); | |
84 | } | ||
85 | |||
86 | // data | ||
87 | |||
88 | /// \brief Absolute proximal accuracy. | ||
89 | Scalar absolute_accuracy; | ||
90 | |||
91 | /// \brief Relative proximal accuracy between two iterates. | ||
92 | Scalar relative_accuracy; | ||
93 | |||
94 | /// \brief Regularization parameter of the proximal algorithm. | ||
95 | Scalar mu; | ||
96 | |||
97 | /// \brief Maximal number of iterations. | ||
98 | int max_iter; | ||
99 | |||
100 | // data that can be modified by the algorithm | ||
101 | |||
102 | /// \brief Absolute residual. | ||
103 | Scalar absolute_residual; | ||
104 | |||
105 | /// \brief Relatice residual between two iterates. | ||
106 | Scalar relative_residual; | ||
107 | |||
108 | /// \brief Total number of iterations of the algorithm when it has converged or reached the | ||
109 | /// maximal number of allowed iterations. | ||
110 | int iter; | ||
111 | }; | ||
112 | |||
113 | } // namespace pinocchio | ||
114 | |||
115 | #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION | ||
116 | #include "pinocchio/algorithm/proximal.txx" | ||
117 | #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION | ||
118 | |||
119 | #endif // ifndef __pinocchio_algorithm_proximal_hpp__ | ||
120 |