Directory: | ./ |
---|---|
File: | include/pinocchio/bindings/python/algorithm/proximal.hpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 20 | 29 | 69.0% |
Branches: | 31 | 84 | 36.9% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2019-2022 INRIA | ||
3 | // | ||
4 | |||
5 | #ifndef __pinocchio_python_algorithm_proximal_hpp__ | ||
6 | #define __pinocchio_python_algorithm_proximal_hpp__ | ||
7 | |||
8 | #include "pinocchio/algorithm/proximal.hpp" | ||
9 | |||
10 | #include <sstream> | ||
11 | |||
12 | namespace pinocchio | ||
13 | { | ||
14 | namespace python | ||
15 | { | ||
16 | namespace bp = boost::python; | ||
17 | |||
18 | template<typename ProximalSettings> | ||
19 | struct ProximalSettingsPythonVisitor | ||
20 | : public boost::python::def_visitor<ProximalSettingsPythonVisitor<ProximalSettings>> | ||
21 | { | ||
22 | typedef typename ProximalSettings::Scalar Scalar; | ||
23 | |||
24 | public: | ||
25 | template<class PyClass> | ||
26 | 69 | void visit(PyClass & cl) const | |
27 | { | ||
28 |
2/4✓ Branch 2 taken 69 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 69 times.
✗ Branch 6 not taken.
|
69 | cl.def(bp::init<>("Default constructor.", bp::arg("self"))) |
29 |
5/10✓ 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.
|
207 | .def(bp::init<const Scalar, const Scalar, int>( |
30 |
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.
|
276 | (bp::arg("self"), bp::arg("accuracy"), bp::arg("mu"), bp::arg("max_iter")), |
31 | "Structure containing all the settings parameters for the proximal algorithms.")) | ||
32 |
6/12✓ 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.
|
345 | .def(bp::init<const Scalar, const Scalar, const Scalar, int>( |
33 |
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.
|
207 | (bp::arg("self"), bp::arg("absolute_accuracy"), bp::arg("relative_accuracy"), |
34 |
2/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
|
207 | bp::arg("mu"), bp::arg("max_iter")), |
35 | "Structure containing all the settings parameters for the proximal algorithms.")) | ||
36 | |||
37 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
38 | "absolute_accuracy", &ProximalSettings::absolute_accuracy, | ||
39 | "Absolute proximal accuracy.") | ||
40 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
41 | "relative_accuracy", &ProximalSettings::relative_accuracy, | ||
42 | "Relative proximal accuracy between two iterates.") | ||
43 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
44 | "mu", &ProximalSettings::mu, "Regularization parameter of the Proximal algorithms.") | ||
45 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property("max_iter", &ProximalSettings::max_iter, "Maximal number of iterations.") |
46 | |||
47 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
48 | "absolute_residual", &ProximalSettings::absolute_residual, "Absolute residual.") | ||
49 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
50 | "relative_residual", &ProximalSettings::relative_residual, | ||
51 | "Relatice residual between two iterates.") | ||
52 | |||
53 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .add_property( |
54 | "iter", &ProximalSettings::iter, | ||
55 | "Final number of iteration of the algorithm when it has converged or " | ||
56 | "reached the maximal number of allowed iterations.") | ||
57 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .def("__repr__", &repr); |
58 | 69 | } | |
59 | |||
60 | 69 | static void expose() | |
61 | { | ||
62 | 69 | bp::class_<ProximalSettings>( | |
63 | "ProximalSettings", | ||
64 | "Structure containing all the settings parameters for proximal algorithms.", bp::no_init) | ||
65 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
69 | .def(ProximalSettingsPythonVisitor<ProximalSettings>()); |
66 | 69 | } | |
67 | |||
68 | private: | ||
69 | ✗ | static std::string repr(const ProximalSettings & self) | |
70 | { | ||
71 | ✗ | std::stringstream ss_repr; | |
72 | |||
73 | ✗ | ss_repr << "ProximalSettings("; | |
74 | ✗ | ss_repr << self.absolute_accuracy << ", "; | |
75 | ✗ | ss_repr << self.relative_accuracy << ", "; | |
76 | ✗ | ss_repr << self.mu << ", "; | |
77 | ✗ | ss_repr << self.max_iter; | |
78 | ✗ | ss_repr << ")"; | |
79 | |||
80 | ✗ | return ss_repr.str(); | |
81 | } | ||
82 | }; | ||
83 | |||
84 | } // namespace python | ||
85 | } // namespace pinocchio | ||
86 | |||
87 | #endif // ifndef __pinocchio_python_algorithm_proximal_hpp__ | ||
88 |