56 #ifndef OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_
57 #define OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_
71 namespace comp = helper_functions::comparisons;
72 namespace optimization
119 const StepT max_step,
120 const StepT min_step,
122 const StepT mu = 1.e-4F,
123 const StepT eta = 0.1F,
124 const std::int32_t max_iterations = 10)
126 m_step_min{min_step},
127 m_optimization_direction{optimization_direction},
130 m_max_iterations{max_iterations}
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();
157 template<
typename DomainValueT,
typename OptimizationProblemT>
158 DomainValueT compute_next_step_(
159 const DomainValueT & x0,
160 const DomainValueT & initial_step,
161 OptimizationProblemT & optimization_problem);
174 template<
typename OptimizationProblemT>
175 class ObjectiveFunction;
181 template<
typename ObjectiveFunctionT>
182 class AuxiliaryFunction;
185 template<
typename FunctionValueT>
186 StepT find_next_step_length(
187 const FunctionValueT & f_t,
const FunctionValueT & f_l,
const FunctionValueT & f_u);
191 template<
typename FunctionValueT>
192 Interval update_interval(
193 const FunctionValueT & f_t,
const FunctionValueT & f_l,
const FunctionValueT & f_u);
196 OptimizationDirection m_optimization_direction;
197 ComputeMode m_compute_mode{};
200 std::int32_t m_max_iterations{};
203 template<
typename DomainValueT,
typename OptimizationProblemT>
205 const DomainValueT & x0,
const DomainValueT & initial_step,
206 OptimizationProblemT & optimization_problem)
209 if (a_t < m_step_min) {
215 using FunctionPhi = ObjectiveFunction<OptimizationProblemT>;
217 using FunctionPsi = AuxiliaryFunction<FunctionPhi>;
218 FunctionPhi phi{x0, initial_step, optimization_problem, m_optimization_direction};
219 FunctionPsi psi{phi, m_mu};
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);
229 bool use_auxiliary_function =
true;
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)))
243 if (use_auxiliary_function) {
244 a_t = find_next_step_length(psi_t, f_l, f_u);
246 a_t = find_next_step_length(phi_t, f_l, f_u);
248 if (a_t < m_step_min || std::isnan(a_t)) {
260 if (use_auxiliary_function && (psi_t.value <= 0.0 && psi_t.derivative > 0.0)) {
261 use_auxiliary_function =
false;
263 f_l = phi(interval.a_l);
264 f_u = phi(interval.a_u);
267 if (use_auxiliary_function) {
270 interval = update_interval(psi_t, f_l, f_u);
271 f_l = psi(interval.a_l);
272 f_u = psi(interval.a_u);
276 interval = update_interval(phi_t, f_l, f_u);
277 f_l = phi(interval.a_l);
278 f_u = phi(interval.a_u);
280 constexpr
auto EPS = std::numeric_limits<StepT>::epsilon();
287 return a_t * phi.get_step_direction();
290 template<
typename OptimizationProblemT>
291 class MoreThuenteLineSearch::ObjectiveFunction
293 using ValueT =
typename OptimizationProblemT::Value;
294 using JacobianT =
typename OptimizationProblemT::Jacobian;
295 using DomainValueT =
typename OptimizationProblemT::DomainValue;
307 const DomainValueT & starting_state,
308 const DomainValueT & initial_step,
309 OptimizationProblemT & underlying_function,
311 : m_starting_state{starting_state},
312 m_step_direction{initial_step.normalized()},
313 m_underlying_function{underlying_function}
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);
321 if (derivative > ValueT{0.0}) {
322 m_step_direction *= -1.0;
326 if (derivative < ValueT{0.0}) {
327 m_step_direction *= -1.0;
332 m_multiplier = ValueT{-1.0};
338 FunctionValue operator()(
const StepT & step_size)
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);
346 m_multiplier * m_underlying_function(current_state),
347 m_multiplier * m_underlying_function_jacobian.dot(m_step_direction)};
351 const DomainValueT & get_step_direction() const noexcept {
return m_step_direction;}
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};
363 template<
typename ObjectiveFunctionT>
364 class MoreThuenteLineSearch::AuxiliaryFunction
366 using FunctionValue =
typename ObjectiveFunctionT::FunctionValue;
370 AuxiliaryFunction(ObjectiveFunctionT & objective_function,
const StepT & mu)
371 : m_objective_function{objective_function},
373 m_initial_objective_function_value{objective_function(0.0F)} {}
376 FunctionValue operator()(
const StepT & step_size)
378 const auto & objective_function_value = m_objective_function(step_size);
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};
389 ObjectiveFunctionT & m_objective_function;
391 FunctionValue m_initial_objective_function_value{};
392 FunctionValue m_value{};
395 template<
typename FunctionValueT>
397 const FunctionValueT & f_t,
const FunctionValueT & f_l,
const FunctionValueT & f_u)
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.");
402 constexpr
auto kValueEps = 0.00001;
403 constexpr
auto kStepEps = 0.00001F;
406 const auto find_cubic_minimizer = [kStepEps](
const auto & f_a,
const auto & f_b) ->
StepT {
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);
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);
419 const auto find_a_q = [kStepEps](
420 const FunctionValueT & f_a,
const FunctionValueT & f_b) ->
StepT {
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);
430 const auto find_a_s = [kStepEps](
431 const FunctionValueT & f_a,
const FunctionValueT & f_b) ->
StepT {
435 return f_a.argument +
436 (f_b.argument - f_a.argument) * f_a.derivative / (f_a.derivative - f_b.derivative);
440 if (f_t.value > f_l.value) {
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)) {
446 return 0.5F * (a_q + a_c);
448 }
else if (f_t.derivative * f_l.derivative < 0) {
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)) {
456 }
else if (
comp::abs_lte(std::abs(f_t.derivative), std::abs(f_l.derivative), kValueEps)) {
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)) {
463 static_cast<StepT>(a_c));
467 static_cast<StepT>(a_s));
470 return find_cubic_minimizer(f_t, f_u);
474 template<
typename FunctionValueT>
475 MoreThuenteLineSearch::Interval MoreThuenteLineSearch::update_interval(
476 const FunctionValueT & f_t,
const FunctionValueT & f_l,
const FunctionValueT & f_u)
480 if (f_t.value > f_l.value) {
481 return {f_l.argument, f_t.argument};
482 }
else if (f_t.derivative * (f_t.argument - f_l.argument) < 0) {
483 return {f_t.argument, f_u.argument};
484 }
else if (f_t.derivative * (f_t.argument - f_l.argument) > 0) {
485 return {f_t.argument, f_l.argument};
488 return {f_t.argument, f_t.argument};
496 #endif // OPTIMIZATION__LINE_SEARCH__MORE_THUENTE_LINE_SEARCH_HPP_