5#ifndef __pinocchio_python_algorithm_proximal_hpp__ 6#define __pinocchio_python_algorithm_proximal_hpp__ 8#include "pinocchio/algorithm/proximal.hpp" 16 namespace bp = boost::python;
18 template<
typename ProximalSettings>
19 struct ProximalSettingsPythonVisitor
20 :
public boost::python::def_visitor<ProximalSettingsPythonVisitor<ProximalSettings>>
22 typedef typename ProximalSettings::Scalar Scalar;
25 template<
class PyClass>
26 void visit(PyClass & cl)
const 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."))
39 "Absolute proximal accuracy.")
42 "Relative proximal accuracy between two iterates.")
51 "Relatice residual between two iterates.")
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);
62 bp::class_<ProximalSettings>(
64 "Structure containing all the settings parameters for proximal algorithms.", bp::no_init)
65 .def(ProximalSettingsPythonVisitor<ProximalSettings>());
69 static std::string repr(
const ProximalSettings & self)
71 std::stringstream ss_repr;
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;
Main pinocchio namespace.