admm-solver.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022-2024 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_admm_solver_hpp__
6 #define __pinocchio_algorithm_admm_solver_hpp__
7 
9 #include "pinocchio/math/fwd.hpp"
12 
15 
16 #include <boost/optional.hpp>
17 
18 namespace pinocchio
19 {
20  template<typename _Scalar>
21  struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
22  ADMMContactSolverTpl : ContactSolverBaseTpl<_Scalar>
23  {
24  typedef _Scalar Scalar;
25  typedef ContactSolverBaseTpl<_Scalar> Base;
26  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> VectorXs;
27  typedef const Eigen::Ref<const VectorXs> ConstRefVectorXs;
28  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixXs;
29  typedef PowerIterationAlgoTpl<VectorXs> PowerIterationAlgo;
30 
31  using Base::problem_size;
32 
33  // struct SolverParameters
34  // {
35  // explicit SolverParameters(const int problem_dim)
36  // : rho_power(Scalar(0.2))
37  // , ratio_primal_dual(Scalar(10))
38  // , mu_prox
39  // {
40  //
41  // }
42  //
43  // /// \brief Rho solver ADMM
44  // boost::optional<Scalar> rho;
45  // /// \brief Power value associated to rho. This quantity will be automatically updated.
46  // Scalar rho_power;
47  // /// \brief Ratio primal/dual
48  // Scalar ratio_primal_dual;
49  // /// \brief Proximal value
50  // Scalar mu_prox;
51  //
52  // /// \brief Largest eigenvalue
53  // boost::optional<Scalar> L_value;
54  // /// \brief Largest eigenvector
55  // boost::optional<VectorXs> L_vector;
56  // };
57  //
58  struct SolverStats
59  {
60  explicit SolverStats(const int max_it)
61  : it(0)
62  , cholesky_update_count(0)
63  {
64  primal_feasibility.reserve(size_t(max_it));
65  dual_feasibility.reserve(size_t(max_it));
66  dual_feasibility_ncp.reserve(size_t(max_it));
67  complementarity.reserve(size_t(max_it));
68  rho.reserve(size_t(max_it));
69  }
70 
71  void reset()
72  {
73  primal_feasibility.clear();
74  dual_feasibility.clear();
75  complementarity.clear();
76  dual_feasibility_ncp.clear();
77  rho.clear();
78  it = 0;
79  cholesky_update_count = 0;
80  }
81 
82  size_t size() const
83  {
84  return primal_feasibility.size();
85  }
86 
88  int it;
89 
91  int cholesky_update_count;
92 
94  std::vector<Scalar> primal_feasibility;
95 
97  std::vector<Scalar> dual_feasibility;
98  std::vector<Scalar> dual_feasibility_ncp;
99 
101  std::vector<Scalar> complementarity;
102 
104  std::vector<Scalar> rho;
105  };
106  //
107  // struct SolverResults
108  // {
109  // explicit SolverResults(const int problem_dim, const int max_it)
110  // : L_vector(problem_dim)
111  //
112  // /// \brief Largest eigenvalue
113  // Scalar L_value;
114  // /// \brief Largest eigenvector
115  // VectorXs L_vector;
116  //
117  // SolverStats stats;
118  // };
119 
120  explicit ADMMContactSolverTpl(
121  int problem_dim,
122  Scalar mu_prox = Scalar(1e-6),
123  Scalar tau = Scalar(0.5),
124  Scalar rho_power = Scalar(0.2),
125  Scalar rho_power_factor = Scalar(0.05),
126  Scalar ratio_primal_dual = Scalar(10),
127  int max_it_largest_eigen_value_solver = 20)
128  : Base(problem_dim)
129  , is_initialized(false)
130  , mu_prox(mu_prox)
131  , tau(tau)
132  , rho(Scalar(-1))
133  , rho_power(rho_power)
134  , rho_power_factor(rho_power_factor)
135  , ratio_primal_dual(ratio_primal_dual)
136  , max_it_largest_eigen_value_solver(max_it_largest_eigen_value_solver)
137  , power_iteration_algo(problem_dim)
138  , x_(VectorXs::Zero(problem_dim))
139  , y_(VectorXs::Zero(problem_dim))
140  , x_previous(VectorXs::Zero(problem_dim))
141  , y_previous(VectorXs::Zero(problem_dim))
142  , z_previous(VectorXs::Zero(problem_dim))
143  , z_(VectorXs::Zero(problem_dim))
144  , s_(VectorXs::Zero(problem_dim))
145  , rhs(problem_dim)
146  , primal_feasibility_vector(VectorXs::Zero(problem_dim))
147  , dual_feasibility_vector(VectorXs::Zero(problem_dim))
148  , stats(Base::max_it)
149  {
150  power_iteration_algo.max_it = max_it_largest_eigen_value_solver;
151  }
152 
154  void setRho(const Scalar rho)
155  {
156  this->rho = rho;
157  }
159  Scalar getRho() const
160  {
161  return rho;
162  }
163 
165  void setRhoPower(const Scalar rho_power)
166  {
167  this->rho_power = rho_power;
168  }
170  Scalar getRhoPower() const
171  {
172  return rho_power;
173  }
174 
176  void setRhoPowerFactor(const Scalar rho_power_factor)
177  {
178  this->rho_power_factor = rho_power_factor;
179  }
181  Scalar getRhoPowerFactor() const
182  {
183  return rho_power_factor;
184  }
185 
187  void setTau(const Scalar tau)
188  {
189  this->tau = tau;
190  }
192  Scalar getTau() const
193  {
194  return tau;
195  }
196 
198  void setProximalValue(const Scalar mu)
199  {
200  this->mu_prox = mu;
201  }
203  Scalar getProximalValue() const
204  {
205  return mu_prox;
206  }
207 
209  void setRatioPrimalDual(const Scalar ratio_primal_dual)
210  {
212  ratio_primal_dual > 0., "The ratio primal/dual should be positive strictly");
213  this->ratio_primal_dual = ratio_primal_dual;
214  }
216  Scalar getRatioPrimalDual() const
217  {
218  return ratio_primal_dual;
219  }
220 
222  int getCholeskyUpdateCount() const
223  {
224  return cholesky_update_count;
225  }
226 
240  template<
241  typename DelassusDerived,
242  typename VectorLike,
243  typename ConstraintAllocator,
244  typename VectorLikeR>
245  bool solve(
246  DelassusOperatorBase<DelassusDerived> & delassus,
247  const Eigen::MatrixBase<VectorLike> & g,
248  const std::vector<CoulombFrictionConeTpl<Scalar>, ConstraintAllocator> & cones,
249  const Eigen::MatrixBase<VectorLikeR> & R,
250  const boost::optional<ConstRefVectorXs> primal_guess = boost::none,
251  const boost::optional<ConstRefVectorXs> dual_guess = boost::none,
252  bool compute_largest_eigen_values = true,
253  bool stat_record = false);
254 
267  template<
268  typename DelassusDerived,
269  typename VectorLike,
270  typename ConstraintAllocator,
271  typename VectorLikeOut>
272  bool solve(
273  DelassusOperatorBase<DelassusDerived> & delassus,
274  const Eigen::MatrixBase<VectorLike> & g,
275  const std::vector<CoulombFrictionConeTpl<Scalar>, ConstraintAllocator> & cones,
276  const Eigen::DenseBase<VectorLikeOut> & x)
277  {
278  return solve(
279  delassus.derived(), g.derived(), cones, x.const_cast_derived(),
280  VectorXs::Zero(problem_size));
281  }
282 
284  const VectorXs & getPrimalSolution() const
285  {
286  return y_;
287  }
289  const VectorXs & getDualSolution() const
290  {
291  return z_;
292  }
294  const VectorXs & getComplementarityShift() const
295  {
296  return s_;
297  }
298 
301  static inline Scalar computeRho(const Scalar L, const Scalar m, const Scalar rho_power)
302  {
303  const Scalar cond = L / m;
304  const Scalar rho = math::sqrt(L * m) * math::pow(cond, rho_power);
305  return rho;
306  }
307 
310  static inline Scalar computeRhoPower(const Scalar L, const Scalar m, const Scalar rho)
311  {
312  const Scalar cond = L / m;
313  const Scalar sqtr_L_m = math::sqrt(L * m);
314  const Scalar rho_power = math::log(rho / sqtr_L_m) / math::log(cond);
315  return rho_power;
316  }
317 
318  PowerIterationAlgo & getPowerIterationAlgo()
319  {
320  return power_iteration_algo;
321  }
322 
323  SolverStats & getStats()
324  {
325  return stats;
326  }
327 
328  protected:
329  bool is_initialized;
330 
332  Scalar mu_prox;
333 
335  Scalar tau;
336 
338  Scalar rho;
340  Scalar rho_power;
342  Scalar rho_power_factor;
344  Scalar ratio_primal_dual;
345 
347  int max_it_largest_eigen_value_solver;
348 
350  PowerIterationAlgo power_iteration_algo;
351 
353  VectorXs x_, y_;
355  VectorXs x_previous, y_previous, z_previous;
357  VectorXs z_;
359  VectorXs s_;
360 
361  VectorXs rhs, primal_feasibility_vector, dual_feasibility_vector;
362 
363  int cholesky_update_count;
364 
366  SolverStats stats;
367 
368 #ifdef PINOCCHIO_WITH_HPP_FCL
369  using Base::timer;
370 #endif // PINOCCHIO_WITH_HPP_FCL
371  }; // struct ADMMContactSolverTpl
372 } // namespace pinocchio
373 
374 #include "pinocchio/algorithm/admm-solver.hxx"
375 
376 #endif // ifndef __pinocchio_algorithm_admm_solver_hpp__
test-cpp2pybind11.m
m
Definition: test-cpp2pybind11.py:22
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
Definition: include/pinocchio/macros.hpp:193
delassus-operator-base.hpp
L
L
pinocchio::python::PowerIterationAlgo
Solver::PowerIterationAlgo PowerIterationAlgo
Definition: admm-solver.cpp:27
Base
BVNodeBase Base
pinocchio::PINOCCHIO_UNSUPPORTED_MESSAGE
struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") ContactCholeskyDecompositionTpl
Contact Cholesky decomposition structure. This structure allows to compute in a efficient and parsimo...
Definition: algorithm/contact-cholesky.hpp:55
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::python::ConstRefVectorXs
const typedef Eigen::Ref< const VectorXs > ConstRefVectorXs
Definition: admm-solver.cpp:31
pinocchio::python::VectorXs
context::VectorXs VectorXs
Definition: admm-solver.cpp:30
contact-solver-base.hpp
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:23
pinocchio::cholesky::solve
Mat & solve(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y)
Return the solution of using the Cholesky decomposition stored in data given the entry ....
pinocchio::context::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: context/generic.hpp:49
fwd.hpp
size
FCL_REAL size() const
x
x
comparison-operators.hpp
mu
double mu
Definition: delassus.cpp:58
pinocchio::python::SolverStats
Solver::SolverStats SolverStats
Definition: admm-solver.cpp:28
fwd.hpp
pinocchio.explog.log
def log(x)
Definition: bindings/python/pinocchio/explog.py:29
Base
eigenvalues.hpp
simulation-closed-kinematic-chains.rho
int rho
Definition: simulation-closed-kinematic-chains.py:110
simulation-closed-kinematic-chains.rhs
rhs
Definition: simulation-closed-kinematic-chains.py:138
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:33