pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
proximal.hpp
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
12namespace 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 void visit(PyClass & cl) const
27 {
28 cl.def(bp::init<>("Default constructor.", bp::arg("self")))
29 .def(bp::init<const Scalar, const Scalar, int>(
30 (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 .def(bp::init<const Scalar, const Scalar, const Scalar, int>(
33 (bp::arg("self"), bp::arg("absolute_accuracy"), bp::arg("relative_accuracy"),
34 bp::arg("mu"), bp::arg("max_iter")),
35 "Structure containing all the settings parameters for the proximal algorithms."))
36
37 .add_property(
38 "absolute_accuracy", &ProximalSettings::absolute_accuracy,
39 "Absolute proximal accuracy.")
40 .add_property(
41 "relative_accuracy", &ProximalSettings::relative_accuracy,
42 "Relative proximal accuracy between two iterates.")
43 .add_property(
44 "mu", &ProximalSettings::mu, "Regularization parameter of the Proximal algorithms.")
45 .add_property("max_iter", &ProximalSettings::max_iter, "Maximal number of iterations.")
46
47 .add_property(
48 "absolute_residual", &ProximalSettings::absolute_residual, "Absolute residual.")
49 .add_property(
50 "relative_residual", &ProximalSettings::relative_residual,
51 "Relatice residual between two iterates.")
52
53 .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 .def("__repr__", &repr);
58 }
59
60 static void expose()
61 {
62 bp::class_<ProximalSettings>(
63 "ProximalSettings",
64 "Structure containing all the settings parameters for proximal algorithms.", bp::no_init)
65 .def(ProximalSettingsPythonVisitor<ProximalSettings>());
66 }
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__
Main pinocchio namespace.
Definition treeview.dox:11
Scalar relative_residual
Relative convergence residual value.
Scalar absolute_residual
Absolule convergence residual value.