Autoware.Auto
more_thuente_line_search.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 
18 // This file contains modified code from the following open source projects
19 // published under the licenses listed below:
20 //
21 // Software License Agreement (BSD License)
22 //
23 // Point Cloud Library (PCL) - www.pointclouds.org
24 // Copyright (c) 2010-2011, Willow Garage, Inc.
25 // Copyright (c) 2012-, Open Perception, Inc.
26 //
27 // All rights reserved.
28 //
29 // Redistribution and use in source and binary forms, with or without
30 // modification, are permitted provided that the following conditions
31 // are met:
32 //
33 // * Redistributions of source code must retain the above copyright
34 // notice, this list of conditions and the following disclaimer.
35 // * Redistributions in binary form must reproduce the above
36 // copyright notice, this list of conditions and the following
37 // disclaimer in the documentation and/or other materials provided
38 // with the distribution.
39 // * Neither the name of the copyright holder(s) nor the names of its
40 // contributors may be used to endorse or promote products derived
41 // from this software without specific prior written permission.
42 //
43 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
44 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
45 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
46 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
47 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
48 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
49 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
50 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
51 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
52 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
53 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
54 // POSSIBILITY OF SUCH DAMAGE.
55 
56 #ifndef OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_
57 #define OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_
58 
60 #include <optimization/utils.hpp>
62 
63 #include <limits>
64 #include <algorithm>
65 #include <utility>
66 
67 namespace autoware
68 {
69 namespace common
70 {
71 namespace comp = helper_functions::comparisons;
72 namespace optimization
73 {
74 
75 namespace detail
76 {
78 constexpr common::types::float32_t kDelta = 0.66F;
79 } // namespace detail
80 
94 class OPTIMIZATION_PUBLIC MoreThuenteLineSearch : public LineSearch<MoreThuenteLineSearch>
95 {
96 public:
101  {
102  kMinimization,
103  kMaximization
104  };
105 
119  const StepT max_step,
120  const StepT min_step,
121  const OptimizationDirection optimization_direction = OptimizationDirection::kMinimization,
122  const StepT mu = 1.e-4F,
123  const StepT eta = 0.1F, // Default value suggested in Section 5 of the paper.
124  const std::int32_t max_iterations = 10)
125  : LineSearch{max_step},
126  m_step_min{min_step},
127  m_optimization_direction{optimization_direction},
128  m_mu{mu},
129  m_eta{eta},
130  m_max_iterations{max_iterations}
131  {
132  if (min_step < 0.0F) {throw std::domain_error("Min step cannot be negative.");}
133  if (max_step < min_step) {throw std::domain_error("Max step cannot be smaller than min step.");}
134  if (mu < 0.0F || mu > 1.0F) {throw std::domain_error("mu must be in (0, 1).");}
135  if (eta < 0.0F || eta > 1.0F) {throw std::domain_error("eta must be in (0, 1).");}
136  if (max_iterations < 1) {throw std::domain_error("Less than 1 iteration is not allowed.");}
137  m_compute_mode.set_score().set_jacobian();
138  }
139 
157  template<typename DomainValueT, typename OptimizationProblemT>
158  DomainValueT compute_next_step_(
159  const DomainValueT & x0,
160  const DomainValueT & initial_step,
161  OptimizationProblemT & optimization_problem);
162 
163 private:
165  struct Interval
166  {
167  StepT a_l;
168  StepT a_u;
169  };
170 
174  template<typename OptimizationProblemT>
175  class ObjectiveFunction;
176 
181  template<typename ObjectiveFunctionT>
182  class AuxiliaryFunction;
183 
184  // Find the next step as described in section 4 of the paper.
185  template<typename FunctionValueT>
186  StepT find_next_step_length(
187  const FunctionValueT & f_t, const FunctionValueT & f_l, const FunctionValueT & f_u);
188 
189  // Find the next [a_l, a_u] interval as described in the "Updating Algorithm" with function psi
190  // and "Modifier Updating Algorithm" with function phi.
191  template<typename FunctionValueT>
192  Interval update_interval(
193  const FunctionValueT & f_t, const FunctionValueT & f_l, const FunctionValueT & f_u);
194 
195  StepT m_step_min{};
196  OptimizationDirection m_optimization_direction;
197  ComputeMode m_compute_mode{};
198  StepT m_mu{};
199  StepT m_eta{};
200  std::int32_t m_max_iterations{};
201 };
202 
203 template<typename DomainValueT, typename OptimizationProblemT>
205  const DomainValueT & x0, const DomainValueT & initial_step,
206  OptimizationProblemT & optimization_problem)
207 {
208  auto a_t = std::min(static_cast<StepT>(initial_step.norm()), get_step_max());
209  if (a_t < m_step_min) {
210  // We don't want to perform the line search as the initial step is out of allowed bounds. We
211  // assume that the optimizer knows what it is doing and return the initial_step unmodified.
212  return initial_step;
213  }
214  // Function phi as defined in eq. 1.3
215  using FunctionPhi = ObjectiveFunction<OptimizationProblemT>;
216  // Function phi as defined right before eq. 2.1
217  using FunctionPsi = AuxiliaryFunction<FunctionPhi>;
218  FunctionPhi phi{x0, initial_step, optimization_problem, m_optimization_direction};
219  FunctionPsi psi{phi, m_mu};
220 
221 
222  Interval interval{m_step_min, get_step_max()};
223  const auto phi_0 = phi(0.0F);
224  auto phi_t = phi(a_t);
225  auto psi_t = psi(a_t);
226  auto f_l = psi(interval.a_l);
227  auto f_u = psi(interval.a_u);
228 
229  bool use_auxiliary_function = true;
230  // Follows the "Search Algorithm" as presented in the paper.
231  for (auto step_iterations = 0; step_iterations < m_max_iterations; ++step_iterations) {
232  if ((psi_t.value <= 0.0F) &&
233  (std::abs(phi_t.derivative) <= m_eta * std::abs(phi_0.derivative)))
234  {
235  // We reached the termination condition as the step satisfies the strong Wolfe conditions (the
236  // ones in the if condition). This means we have converged and are ready to return the found
237  // step.
238  break;
239  }
240 
241  // Pick next step size by interpolating either phi or psi depending on which update algorithm is
242  // currently being used.
243  if (use_auxiliary_function) {
244  a_t = find_next_step_length(psi_t, f_l, f_u);
245  } else {
246  a_t = find_next_step_length(phi_t, f_l, f_u);
247  }
248  if (a_t < m_step_min || std::isnan(a_t)) {
249  // This can happen if we are closer than the minimum step to the optimum. We don't want to do
250  // anything in this case.
251  a_t = 0.0F;
252  break;
253  }
254  phi_t = phi(a_t);
255  psi_t = psi(a_t);
256 
257  // Decide if we want to switch to using a "Modified Updating Algorithm" (shown after theorem 3.2
258  // in the paper) by switching from using function psi to using function phi. The decision
259  // follows the logic in the paragraph right before theorem 3.3 in the paper.
260  if (use_auxiliary_function && (psi_t.value <= 0.0 && psi_t.derivative > 0.0)) {
261  use_auxiliary_function = false;
262  // We now want to switch to using phi so compute the required values.
263  f_l = phi(interval.a_l);
264  f_u = phi(interval.a_u);
265  }
266 
267  if (use_auxiliary_function) {
268  // Update the interval that will be used to generate the next step using the
269  // "Updating Algorithm" (right after theorem 2.1 in the paper).
270  interval = update_interval(psi_t, f_l, f_u);
271  f_l = psi(interval.a_l);
272  f_u = psi(interval.a_u);
273  } else {
274  // Update the interval that will be used to generate the next step using the
275  // "Modified Updating Algorithm" (right after theorem 3.2 in the paper).
276  interval = update_interval(phi_t, f_l, f_u);
277  f_l = phi(interval.a_l);
278  f_u = phi(interval.a_u);
279  }
280  constexpr auto EPS = std::numeric_limits<StepT>::epsilon();
281  if (comp::approx_eq(interval.a_u, interval.a_l, m_step_min, EPS)) {
282  // The interval has converged to a point so we can stop here.
283  a_t = interval.a_u;
284  break;
285  }
286  }
287  return a_t * phi.get_step_direction();
288 }
289 
290 template<typename OptimizationProblemT>
291 class MoreThuenteLineSearch::ObjectiveFunction
292 {
293  using ValueT = typename OptimizationProblemT::Value;
294  using JacobianT = typename OptimizationProblemT::Jacobian;
295  using DomainValueT = typename OptimizationProblemT::DomainValue;
296 
297 public:
300  {
302  ValueT value;
303  ValueT derivative;
304  };
305 
306  ObjectiveFunction(
307  const DomainValueT & starting_state,
308  const DomainValueT & initial_step,
309  OptimizationProblemT & underlying_function,
310  const OptimizationDirection direction)
311  : m_starting_state{starting_state},
312  m_step_direction{initial_step.normalized()},
313  m_underlying_function{underlying_function}
314  {
315  m_compute_mode.set_score().set_jacobian();
316  m_underlying_function.evaluate(m_starting_state, m_compute_mode);
317  m_underlying_function.jacobian(m_starting_state, m_underlying_function_jacobian);
318  const auto derivative = m_underlying_function_jacobian.dot(m_step_direction);
319  switch (direction) {
321  if (derivative > ValueT{0.0}) {
322  m_step_direction *= -1.0;
323  }
324  break;
326  if (derivative < ValueT{0.0}) {
327  m_step_direction *= -1.0;
328  }
329  // The function phi must have a derivative < 0 following the introduction of the
330  // More-Thuente paper. In case we want to solve a maximization problem, the derivative will
331  // be positive and we need to make a dual problem from it by flipping the values of phi.
332  m_multiplier = ValueT{-1.0};
333  break;
334  }
335  }
336 
338  FunctionValue operator()(const StepT & step_size)
339  {
340  if (step_size < StepT{0.0}) {throw std::runtime_error("Step cannot be negative");}
341  const auto current_state = m_starting_state + step_size * m_step_direction;
342  m_underlying_function.evaluate(current_state, m_compute_mode);
343  m_underlying_function.jacobian(current_state, m_underlying_function_jacobian);
344  return {
345  step_size,
346  m_multiplier * m_underlying_function(current_state),
347  m_multiplier * m_underlying_function_jacobian.dot(m_step_direction)};
348  }
349 
351  const DomainValueT & get_step_direction() const noexcept {return m_step_direction;}
352 
353 private:
354  DomainValueT m_starting_state;
355  DomainValueT m_step_direction;
356  OptimizationProblemT & m_underlying_function;
357  ComputeMode m_compute_mode{};
358  JacobianT m_underlying_function_jacobian;
359  ValueT m_multiplier{1.0};
360 };
361 
362 
363 template<typename ObjectiveFunctionT>
364 class MoreThuenteLineSearch::AuxiliaryFunction
365 {
366  using FunctionValue = typename ObjectiveFunctionT::FunctionValue;
367 
368 public:
370  AuxiliaryFunction(ObjectiveFunctionT & objective_function, const StepT & mu)
371  : m_objective_function{objective_function},
372  m_mu{mu},
373  m_initial_objective_function_value{objective_function(0.0F)} {}
374 
376  FunctionValue operator()(const StepT & step_size)
377  {
378  const auto & objective_function_value = m_objective_function(step_size);
379  const auto value =
380  objective_function_value.value -
381  m_initial_objective_function_value.value -
382  m_mu * step_size * objective_function_value.derivative;
383  const auto derivative =
384  objective_function_value.derivative - m_mu * m_initial_objective_function_value.derivative;
385  return {step_size, value, derivative};
386  }
387 
388 private:
389  ObjectiveFunctionT & m_objective_function;
390  StepT m_mu{};
391  FunctionValue m_initial_objective_function_value{};
392  FunctionValue m_value{};
393 };
394 
395 template<typename FunctionValueT>
396 MoreThuenteLineSearch::StepT MoreThuenteLineSearch::find_next_step_length(
397  const FunctionValueT & f_t, const FunctionValueT & f_l, const FunctionValueT & f_u)
398 {
399  if (std::isnan(f_t.argument) || std::isnan(f_l.argument) || std::isnan(f_u.argument)) {
400  throw std::runtime_error("Got nan values in the step computation function.");
401  }
402  constexpr auto kValueEps = 0.00001;
403  constexpr auto kStepEps = 0.00001F;
404  // A lambda to calculate the minimizer of the cubic that interpolates f_a, f_a_derivative, f_b and
405  // f_b_derivative on [a, b]. Equation 2.4.52 [Sun, Yuan 2006]
406  const auto find_cubic_minimizer = [kStepEps](const auto & f_a, const auto & f_b) -> StepT {
407  if (comp::approx_eq(f_a.argument, f_b.argument, kStepEps, kStepEps)) {
408  return f_a.argument;
409  }
410  const auto z = 3.0F * (f_a.value - f_b.value) /
411  (f_b.argument - f_a.argument) + f_a.derivative + f_b.derivative;
412  const auto w = std::sqrt(z * z - f_a.derivative * f_b.derivative);
413  // Equation 2.4.56 [Sun, Yuan 2006]
414  return f_b.argument - (f_b.argument - f_a.argument) * (f_b.derivative + w - z) /
415  (f_b.derivative - f_a.derivative + 2.0F * w);
416  };
417 
418  // A lambda to calculate the minimizer of the quadratic that interpolates f_a, f_b and f'_a
419  const auto find_a_q = [kStepEps](
420  const FunctionValueT & f_a, const FunctionValueT & f_b) -> StepT {
421  if (comp::approx_eq(f_a.argument, f_b.argument, kStepEps, kStepEps)) {
422  return f_a.argument;
423  }
424  return f_a.argument + 0.5F *
425  (f_b.argument - f_a.argument) * (f_b.argument - f_a.argument) * f_a.derivative /
426  (f_a.value - f_b.value + (f_b.argument - f_a.argument) * f_a.derivative);
427  };
428 
429  // A lambda to calculate the minimizer of the quadratic that interpolates f'_a, and f'_b
430  const auto find_a_s = [kStepEps](
431  const FunctionValueT & f_a, const FunctionValueT & f_b) -> StepT {
432  if (comp::approx_eq(f_a.argument, f_b.argument, kStepEps, kStepEps)) {
433  return f_a.argument;
434  }
435  return f_a.argument +
436  (f_b.argument - f_a.argument) * f_a.derivative / (f_a.derivative - f_b.derivative);
437  };
438 
439  // We cover here all the cases presented in the More-Thuente paper in section 4.
440  if (f_t.value > f_l.value) { // Case 1 from section 4.
441  const auto a_c = find_cubic_minimizer(f_l, f_t);
442  const auto a_q = find_a_q(f_l, f_t);
443  if (std::fabs(a_c - f_l.argument) < std::fabs(a_q - f_l.argument)) {
444  return a_c;
445  } else {
446  return 0.5F * (a_q + a_c);
447  }
448  } else if (f_t.derivative * f_l.derivative < 0) { // Case 2 from section 4.
449  const auto a_c = find_cubic_minimizer(f_l, f_t);
450  const auto a_s = find_a_s(f_l, f_t);
451  if (std::fabs(a_c - f_t.argument) >= std::fabs(a_s - f_t.argument)) {
452  return a_c;
453  } else {
454  return a_s;
455  }
456  } else if (comp::abs_lte(std::abs(f_t.derivative), std::abs(f_l.derivative), kValueEps)) {
457  // Case 3 from section 4.
458  const auto a_c = find_cubic_minimizer(f_l, f_t);
459  const auto a_s = find_a_s(f_l, f_t);
460  if (std::fabs(a_c - f_t.argument) < std::fabs(a_s - f_t.argument)) {
461  return std::min(
462  f_t.argument + detail::kDelta * (f_u.argument - f_t.argument),
463  static_cast<StepT>(a_c));
464  } else {
465  return std::max(
466  f_t.argument + detail::kDelta * (f_u.argument - f_t.argument),
467  static_cast<StepT>(a_s));
468  }
469  } else { // Case 4 from section 4.
470  return find_cubic_minimizer(f_t, f_u);
471  }
472 }
473 
474 template<typename FunctionValueT>
475 MoreThuenteLineSearch::Interval MoreThuenteLineSearch::update_interval(
476  const FunctionValueT & f_t, const FunctionValueT & f_l, const FunctionValueT & f_u)
477 {
478  // Following either "Updating Algorithm" or "Modifier Updating Algorithm" depending on the
479  // provided function f (can be psi or phi).
480  if (f_t.value > f_l.value) {
481  return {f_l.argument, f_t.argument}; // case a
482  } else if (f_t.derivative * (f_t.argument - f_l.argument) < 0) {
483  return {f_t.argument, f_u.argument}; // case b
484  } else if (f_t.derivative * (f_t.argument - f_l.argument) > 0) {
485  return {f_t.argument, f_l.argument}; // case c
486  }
487  // Converged to a point.
488  return {f_t.argument, f_t.argument};
489 }
490 
491 } // namespace optimization
492 } // namespace common
493 } // namespace autoware
494 
495 
496 #endif // OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_
utils.hpp
autoware::common::helper_functions::comparisons::approx_eq
bool approx_eq(const T &a, const T &b, const T &abs_eps, const T &rel_eps)
Check for approximate equality in absolute and relative terms.
Definition: float_comparisons.hpp:139
autoware::common::helper_functions::comparisons::abs_lte
bool abs_lte(const T &a, const T &b, const T &eps)
Check for approximate less than or equal in absolute terms.
Definition: float_comparisons.hpp:69
autoware::common::optimization::MoreThuenteLineSearch::MoreThuenteLineSearch
MoreThuenteLineSearch(const StepT max_step, const StepT min_step, const OptimizationDirection optimization_direction=OptimizationDirection::kMinimization, const StepT mu=1.e-4F, const StepT eta=0.1F, const std::int32_t max_iterations=10)
Constructs a new instance.
Definition: more_thuente_line_search.hpp:118
autoware::common::optimization::detail::kDelta
constexpr common::types::float32_t kDelta
This value is used in More-Thuente paper without explanation (in the paper: Section 4,...
Definition: more_thuente_line_search.hpp:78
autoware::common::optimization::MoreThuenteLineSearch
This class describes a More-Thuente line search as presented in the paper "Line Search Algorithms wit...
Definition: more_thuente_line_search.hpp:94
autoware::common::optimization::LineSearch
Base class (CRTP) to mange the step length during optimization.
Definition: line_search.hpp:34
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
float_comparisons.hpp
autoware::common::optimization::LineSearch< MoreThuenteLineSearch >::get_step_max
StepT get_step_max() const noexcept
Definition: line_search.hpp:65
catr_diff.w
w
Definition: catr_diff.py:22
line_search.hpp
autoware::common::optimization::MoreThuenteLineSearch::ObjectiveFunction::FunctionValue::argument
StepT argument
Definition: more_thuente_line_search.hpp:301
autoware::common::helper_functions::comparisons
Definition: bool_comparisons.hpp:32
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
autoware::common::optimization::MoreThuenteLineSearch::ObjectiveFunction::FunctionValue
A utility struct that holds the argument, value and derivative of a function.
Definition: more_thuente_line_search.hpp:299
autoware::common::optimization::MoreThuenteLineSearch::ObjectiveFunction::FunctionValue::value
ValueT value
Definition: more_thuente_line_search.hpp:302
autoware::common::optimization::LineSearch< MoreThuenteLineSearch >::StepT
float_t StepT
Definition: line_search.hpp:38
autoware::common::optimization::MoreThuenteLineSearch::compute_next_step_
DomainValueT compute_next_step_(const DomainValueT &x0, const DomainValueT &initial_step, OptimizationProblemT &optimization_problem)
Calculates the next step.
Definition: more_thuente_line_search.hpp:204
autoware::common::optimization::MoreThuenteLineSearch::OptimizationDirection
OptimizationDirection
An enum that defines the direction of optimization.
Definition: more_thuente_line_search.hpp:100
autoware::common::optimization::MoreThuenteLineSearch::OptimizationDirection::kMaximization
@ kMaximization
autoware::common::optimization::MoreThuenteLineSearch::OptimizationDirection::kMinimization
@ kMinimization
autoware::common::optimization::MoreThuenteLineSearch::ObjectiveFunction::FunctionValue::derivative
ValueT derivative
Definition: more_thuente_line_search.hpp:303