crocoddyl  1.3.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
kkt.cpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2018-2020, LAAS-CNRS, New York University, Max Planck Gesellschaft,
5 // University of Edinburgh
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
9 
10 #include "crocoddyl/core/solvers/kkt.hpp"
11 
12 namespace crocoddyl {
13 
14 SolverKKT::SolverKKT(boost::shared_ptr<ShootingProblem> problem)
15  : SolverAbstract(problem),
16  regfactor_(10.),
17  regmin_(1e-9),
18  regmax_(1e9),
19  cost_try_(0.),
20  th_grad_(1e-12),
21  was_feasible_(false) {
22  allocateData();
23  const unsigned int& n_alphas = 10;
24  xreg_ = 0.;
25  ureg_ = 0.;
26  alphas_.resize(n_alphas);
27  for (unsigned int n = 0; n < n_alphas; ++n) {
28  alphas_[n] = 1. / pow(2., (double)n);
29  }
30 }
31 
32 SolverKKT::~SolverKKT() {}
33 
34 bool SolverKKT::solve(const std::vector<Eigen::VectorXd>& init_xs, const std::vector<Eigen::VectorXd>& init_us,
35  const std::size_t& maxiter, const bool& is_feasible, const double&) {
36  setCandidate(init_xs, init_us, is_feasible);
37  bool recalc = true;
38  for (iter_ = 0; iter_ < maxiter; ++iter_) {
39  while (true) {
40  try {
41  computeDirection(recalc);
42  } catch (std::exception& e) {
43  recalc = false;
44  if (xreg_ == regmax_) {
45  return false;
46  } else {
47  continue;
48  }
49  }
50  break;
51  }
52 
53  expectedImprovement();
54  for (std::vector<double>::const_iterator it = alphas_.begin(); it != alphas_.end(); ++it) {
55  steplength_ = *it;
56  try {
57  dV_ = tryStep(steplength_);
58  } catch (std::exception& e) {
59  continue;
60  }
61  dVexp_ = steplength_ * d_[0] + 0.5 * steplength_ * steplength_ * d_[1];
62  if (d_[0] < th_grad_ || !is_feasible_ || dV_ > th_acceptstep_ * dVexp_) {
63  was_feasible_ = is_feasible_;
64  setCandidate(xs_try_, us_try_, true);
65  cost_ = cost_try_;
66  break;
67  }
68  }
69  stoppingCriteria();
70  const std::size_t& n_callbacks = callbacks_.size();
71  if (n_callbacks != 0) {
72  for (std::size_t c = 0; c < n_callbacks; ++c) {
73  CallbackAbstract& callback = *callbacks_[c];
74  callback(*this);
75  }
76  }
77  if (was_feasible_ && stop_ < th_stop_) {
78  return true;
79  }
80  }
81  return false;
82 }
83 
84 void SolverKKT::computeDirection(const bool& recalc) {
85  const std::size_t& T = problem_->get_T();
86  if (recalc) {
87  calc();
88  }
89  computePrimalDual();
90  const Eigen::VectorBlock<Eigen::VectorXd, Eigen::Dynamic> p_x = primal_.segment(0, ndx_);
91  const Eigen::VectorBlock<Eigen::VectorXd, Eigen::Dynamic> p_u = primal_.segment(ndx_, nu_);
92 
93  std::size_t ix = 0;
94  std::size_t iu = 0;
95  for (std::size_t t = 0; t < T; ++t) {
96  const std::size_t& ndxi = problem_->get_runningModels()[t]->get_state()->get_ndx();
97  const std::size_t& nui = problem_->get_runningModels()[t]->get_nu();
98  dxs_[t] = p_x.segment(ix, ndxi);
99  dus_[t] = p_u.segment(iu, nui);
100  lambdas_[t] = dual_.segment(ix, ndxi);
101  ix += ndxi;
102  iu += nui;
103  }
104  const std::size_t& ndxi = problem_->get_terminalModel()->get_state()->get_ndx();
105  dxs_.back() = p_x.segment(ix, ndxi);
106  lambdas_.back() = dual_.segment(ix, ndxi);
107 }
108 
109 double SolverKKT::tryStep(const double& steplength) {
110  const std::size_t& T = problem_->get_T();
111  for (std::size_t t = 0; t < T; ++t) {
112  const boost::shared_ptr<ActionModelAbstract>& m = problem_->get_runningModels()[t];
113 
114  m->get_state()->integrate(xs_[t], steplength * dxs_[t], xs_try_[t]);
115  us_try_[t] = us_[t];
116  us_try_[t] += steplength * dus_[t];
117  }
118  const boost::shared_ptr<ActionModelAbstract> m = problem_->get_terminalModel();
119  m->get_state()->integrate(xs_[T], steplength * dxs_[T], xs_try_[T]);
120  cost_try_ = problem_->calc(xs_try_, us_try_);
121  return cost_ - cost_try_;
122 }
123 
124 double SolverKKT::stoppingCriteria() {
125  const std::size_t& T = problem_->get_T();
126  std::size_t ix = 0;
127  std::size_t iu = 0;
128  for (std::size_t t = 0; t < T; ++t) {
129  const boost::shared_ptr<ActionDataAbstract>& d = problem_->get_runningDatas()[t];
130  const std::size_t& ndxi = problem_->get_runningModels()[t]->get_state()->get_ndx();
131  const std::size_t& nui = problem_->get_runningModels()[t]->get_nu();
132 
133  dF.segment(ix, ndxi) = lambdas_[t];
134  dF.segment(ix, ndxi).noalias() -= d->Fx.transpose() * lambdas_[t + 1];
135  dF.segment(ndx_ + iu, nui).noalias() = -lambdas_[t + 1].transpose() * d->Fu;
136  ix += ndxi;
137  iu += nui;
138  }
139  const std::size_t& ndxi = problem_->get_terminalModel()->get_state()->get_ndx();
140  dF.segment(ix, ndxi) = lambdas_.back();
141  stop_ = (kktref_.segment(0, ndx_ + nu_) + dF).squaredNorm() + kktref_.segment(ndx_ + nu_, ndx_).squaredNorm();
142  return stop_;
143 }
144 
145 const Eigen::Vector2d& SolverKKT::expectedImprovement() {
146  d_ = Eigen::Vector2d::Zero();
147  // -grad^T.primal
148  d_(0) = -kktref_.segment(0, ndx_ + nu_).dot(primal_);
149  // -(hessian.primal)^T.primal
150  kkt_primal_.noalias() = kkt_.block(0, 0, ndx_ + nu_, ndx_ + nu_) * primal_;
151  d_(1) = -kkt_primal_.dot(primal_);
152  return d_;
153 }
154 
155 const Eigen::MatrixXd& SolverKKT::get_kkt() const { return kkt_; }
156 
157 const Eigen::VectorXd& SolverKKT::get_kktref() const { return kktref_; }
158 
159 const Eigen::VectorXd& SolverKKT::get_primaldual() const { return primaldual_; }
160 
161 const std::vector<Eigen::VectorXd>& SolverKKT::get_dxs() const { return dxs_; }
162 
163 const std::vector<Eigen::VectorXd>& SolverKKT::get_dus() const { return dus_; }
164 
165 const std::size_t& SolverKKT::get_nx() const { return nx_; }
166 
167 const std::size_t& SolverKKT::get_ndx() const { return ndx_; }
168 
169 const std::size_t& SolverKKT::get_nu() const { return nu_; }
170 
171 double SolverKKT::calc() {
172  cost_ = problem_->calc(xs_, us_);
173  cost_ = problem_->calcDiff(xs_, us_);
174 
175  // offset on constraint xnext = f(x,u) due to x0 = ref.
176  const std::size_t& cx0 = problem_->get_runningModels()[0]->get_state()->get_ndx();
177 
178  std::size_t ix = 0;
179  std::size_t iu = 0;
180  const std::size_t& T = problem_->get_T();
181  kkt_.block(ndx_ + nu_, 0, ndx_, ndx_) = Eigen::MatrixXd::Identity(ndx_, ndx_);
182  for (std::size_t t = 0; t < T; ++t) {
183  const boost::shared_ptr<ActionModelAbstract>& m = problem_->get_runningModels()[t];
184  const boost::shared_ptr<ActionDataAbstract>& d = problem_->get_runningDatas()[t];
185  const std::size_t& ndxi = m->get_state()->get_ndx();
186  const std::size_t& nui = m->get_nu();
187 
188  // Computing the gap at the initial state
189  if (t == 0) {
190  m->get_state()->diff(problem_->get_x0(), xs_[0], kktref_.segment(ndx_ + nu_, ndxi));
191  }
192 
193  // Filling KKT matrix
194  kkt_.block(ix, ix, ndxi, ndxi) = d->Lxx;
195  kkt_.block(ix, ndx_ + iu, ndxi, nui) = d->Lxu;
196  kkt_.block(ndx_ + iu, ix, nui, ndxi) = d->Lxu.transpose();
197  kkt_.block(ndx_ + iu, ndx_ + iu, nui, nui) = d->Luu;
198  kkt_.block(ndx_ + nu_ + cx0 + ix, ix, ndxi, ndxi) = -d->Fx;
199  kkt_.block(ndx_ + nu_ + cx0 + ix, ndx_ + iu, ndxi, nui) = -d->Fu;
200 
201  // Filling KKT vector
202  kktref_.segment(ix, ndxi) = d->Lx;
203  kktref_.segment(ndx_ + iu, nui) = d->Lu;
204  m->get_state()->diff(d->xnext, xs_[t + 1], kktref_.segment(ndx_ + nu_ + cx0 + ix, ndxi));
205 
206  ix += ndxi;
207  iu += nui;
208  }
209  const boost::shared_ptr<ActionDataAbstract>& df = problem_->get_terminalData();
210  const std::size_t& ndxf = problem_->get_terminalModel()->get_state()->get_ndx();
211  kkt_.block(ix, ix, ndxf, ndxf) = df->Lxx;
212  kktref_.segment(ix, ndxf) = df->Lx;
213  kkt_.block(0, ndx_ + nu_, ndx_ + nu_, ndx_) = kkt_.block(ndx_ + nu_, 0, ndx_, ndx_ + nu_).transpose();
214  return cost_;
215 }
216 
217 void SolverKKT::computePrimalDual() {
218  primaldual_ = kkt_.lu().solve(-kktref_);
219  primal_ = primaldual_.segment(0, ndx_ + nu_);
220  dual_ = primaldual_.segment(ndx_ + nu_, ndx_);
221 }
222 
223 void SolverKKT::increaseRegularization() {
224  xreg_ *= regfactor_;
225  if (xreg_ > regmax_) {
226  xreg_ = regmax_;
227  }
228  ureg_ = xreg_;
229 }
230 
231 void SolverKKT::decreaseRegularization() {
232  xreg_ /= regfactor_;
233  if (xreg_ < regmin_) {
234  xreg_ = regmin_;
235  }
236  ureg_ = xreg_;
237 }
238 
239 void SolverKKT::allocateData() {
240  const std::size_t& T = problem_->get_T();
241  dxs_.resize(T + 1);
242  dus_.resize(T);
243  lambdas_.resize(T + 1);
244  xs_try_.resize(T + 1);
245  us_try_.resize(T);
246 
247  nx_ = 0;
248  ndx_ = 0;
249  nu_ = 0;
250  for (std::size_t t = 0; t < T; ++t) {
251  const boost::shared_ptr<ActionModelAbstract>& model = problem_->get_runningModels()[t];
252  const std::size_t& nx = model->get_state()->get_nx();
253  const std::size_t& ndx = model->get_state()->get_ndx();
254  const std::size_t& nu = model->get_nu();
255  if (t == 0) {
256  xs_try_[t] = problem_->get_x0();
257  } else {
258  xs_try_[t] = Eigen::VectorXd::Constant(nx, NAN);
259  }
260  us_try_[t] = Eigen::VectorXd::Constant(nu, NAN);
261  dxs_[t] = Eigen::VectorXd::Zero(ndx);
262  dus_[t] = Eigen::VectorXd::Zero(nu);
263  lambdas_[t] = Eigen::VectorXd::Zero(ndx);
264  nx_ += nx;
265  ndx_ += ndx;
266  nu_ += nu;
267  }
268  const boost::shared_ptr<ActionModelAbstract>& model = problem_->get_terminalModel();
269  nx_ += model->get_state()->get_nx();
270  ndx_ += model->get_state()->get_ndx();
271  xs_try_.back() = problem_->get_terminalModel()->get_state()->zero();
272  dxs_.back() = Eigen::VectorXd::Zero(model->get_state()->get_ndx());
273  lambdas_.back() = Eigen::VectorXd::Zero(model->get_state()->get_ndx());
274 
275  // Set dimensions for kkt matrix and kkt_ref vector
276  kkt_.resize(2 * ndx_ + nu_, 2 * ndx_ + nu_);
277  kkt_.setZero();
278  kktref_.resize(2 * ndx_ + nu_);
279  kktref_.setZero();
280  primaldual_.resize(2 * ndx_ + nu_);
281  primaldual_.setZero();
282  primal_.resize(ndx_ + nu_);
283  primal_.setZero();
284  kkt_primal_.resize(ndx_ + nu_);
285  kkt_primal_.setZero();
286  dual_.resize(ndx_);
287  dual_.setZero();
288  dF.resize(ndx_ + nu_);
289  dF.setZero();
290 }
291 
292 } // namespace crocoddyl