1#ifndef DUNE_FEM_NEWTONINVERSEOPERATOR_HH
2#define DUNE_FEM_NEWTONINVERSEOPERATOR_HH
17#include <dune/fem/common/staticlistofint.hh>
18#include <dune/fem/solver/parameter.hh>
19#include <dune/fem/io/parameter.hh>
20#include <dune/fem/operator/common/operator.hh>
21#include <dune/fem/operator/common/differentiableoperator.hh>
22#include <dune/fem/solver/inverseoperatorinterface.hh>
40 const double etaMax_ = 0.99;
41 const double gamma_ = 0.1;
42 mutable double previousEta_ = -1.0;
43 mutable double previousResidual_ = -1.0;
44 mutable double newtonTolerance_;
51 double nextLinearTolerance(
const double currentResidual)
const
55 if (previousEta_ >= 0.0)
57 const double etaA = gamma_ * currentResidual * currentResidual / (previousResidual_ * previousResidual_);
58 const double indicator = gamma_ * previousEta_ * previousEta_;
59 const double etaC = indicator < 0.1 ? std::min(etaA, etaMax_) :
std::
min(etaMax_,
std::
max(etaA, indicator));
60 eta = std::min(etaMax_, std::max(etaC, 0.5 * newtonTolerance_ / currentResidual));
62 previousResidual_ = currentResidual;
66 void setTolerance(
const double newtonTolerance) { newtonTolerance_ = newtonTolerance; }
72 template <
class SolverParam = SolverParameter>
73 struct NewtonParameter
74 :
public Dune::Fem::LocalParameter< NewtonParameter<SolverParam>, NewtonParameter<SolverParam> >
78 std::shared_ptr<SolverParam> baseParam_;
80 const std::string keyPrefix_;
82 ParameterReader parameter_;
84 void checkDeprecatedParameters()
const
86 const std::string newton(
"newton.");
87 const std::size_t pos = keyPrefix_.find( newton );
88 if( pos != std::string::npos )
90 DUNE_THROW(InvalidStateException,
"Keyprefix 'newton' is deprecated, replace with 'nonlinear'!");
93 const std::string params[]
94 = {
"tolerance",
"lineSearch",
"maxterations",
"linear",
"maxlinesearchiterations" };
95 for(
const auto& p : params )
97 std::string key(
"fem.solver.newton." );
99 if( parameter_.exists( key ) )
100 DUNE_THROW(InvalidStateException,
"Keyprefix 'newton' is deprecated, replace with 'nonlinear'!");
104 std::string replaceNonLinearWithLinear(
const std::string& keyPrefix )
const
106 if( keyPrefix.find(
"nonlinear" ) != std::string::npos )
108 return std::regex_replace(keyPrefix, std::regex(
"nonlinear"),
"linear" );
114 NewtonParameter(
const SolverParam& baseParameter,
const std::string keyPrefix =
"fem.solver.nonlinear." )
115 : baseParam_( static_cast< SolverParam* > (baseParameter.clone()) ),
116 keyPrefix_( keyPrefix ),
117 parameter_( baseParameter.parameter() )
119 checkDeprecatedParameters();
120 checkForcingErrorMeasure();
123 template <class Parameter, std::enable_if_t<!std::is_base_of<SolverParam,Parameter>::value && !std::is_same<Parameter,ParameterReader>::value,
int> i=0>
124 NewtonParameter(
const Parameter& solverParameter,
const std::string keyPrefix =
"fem.solver.nonlinear." )
125 : baseParam_( new SolverParam(solverParameter) ),
126 keyPrefix_( keyPrefix ),
127 parameter_( solverParameter.parameter() )
129 checkDeprecatedParameters();
130 checkForcingErrorMeasure();
133 template <class ParamReader, std::enable_if_t<!std::is_same<ParamReader,SolverParam>::value && std::is_same<ParamReader,ParameterReader>::value,
int> i=0>
134 NewtonParameter(
const ParamReader ¶meter,
const std::string keyPrefix =
"fem.solver.nonlinear." )
136 : baseParam_(
std::make_shared<SolverParam>( replaceNonLinearWithLinear(keyPrefix), parameter) ),
137 keyPrefix_( keyPrefix ),
138 parameter_( parameter )
140 checkDeprecatedParameters();
141 checkForcingErrorMeasure();
144 void checkForcingErrorMeasure()
146 if (forcing() == Forcing::eisenstatwalker)
148 baseParam_->setDefaultErrorMeasure(2);
149 if (baseParam_->errorMeasure() != LinearSolver::ToleranceCriteria::residualReduction)
150 DUNE_THROW( InvalidStateException,
"Parameter `linear.errormeasure` selecting the tolerance criteria in the linear solver must be `residualreduction` when using Eisenstat-Walker." );
154 const ParameterReader ¶meter ()
const {
return parameter_; }
155 const SolverParam& solverParameter ()
const {
return *baseParam_; }
156 const SolverParam& linear ()
const {
return *baseParam_; }
158 virtual void reset ()
164 maxLinearIterations_ = -1;
165 maxLineSearchIterations_ = -1;
169 virtual double tolerance ()
const
172 tolerance_ = parameter_.getValue<
double >( keyPrefix_ +
"tolerance", 1e-6 );
176 virtual void setTolerance (
const double tol )
182 virtual bool verbose ()
const
190 const bool v =
false;
191 verbose_ = parameter_.getValue<
bool >(keyPrefix_ +
"verbose", v ) ? 1 : 0 ;
196 virtual void setVerbose(
bool verb)
198 verbose_ = verb ? 1 : 0;
201 virtual int maxIterations ()
const
203 if(maxIterations_ < 0)
205 return maxIterations_;
208 virtual void setMaxIterations (
const int maxIter )
210 assert(maxIter >= 0);
211 maxIterations_ = maxIter;
216 virtual int maxLinearIterations ()
const
218 if(maxLinearIterations_ < 0)
219 maxLinearIterations_ = linear().maxIterations();
220 return maxLinearIterations_;
223 virtual void setMaxLinearIterations (
const int maxLinearIter )
225 assert(maxLinearIter >=0);
226 maxLinearIterations_ = maxLinearIter;
229 virtual int maxLineSearchIterations ()
const
231 if(maxLineSearchIterations_ < 0)
233 return maxLineSearchIterations_;
236 virtual void setMaxLineSearchIterations (
const int maxLineSearchIter )
238 assert( maxLineSearchIter >= 0);
239 maxLineSearchIterations_ = maxLineSearchIter;
243 LIST_OF_INT(LineSearchMethod,
247 virtual int lineSearch ()
const
249 if( parameter_.exists( keyPrefix_ +
"lineSearch" ) )
251 std::cout <<
"WARNING: using old parameter name '" << keyPrefix_ +
"lineSearch" <<
"',\n"
252 <<
"please switch to '" << keyPrefix_ +
"linesearch" <<
"' (all lower caps)!" <<std::endl;
253 return Forcing::to_id( parameter_.getEnum( keyPrefix_ +
"lineSearch", LineSearchMethod::names(),
LineSearchMethod::none ) );
255 return Forcing::to_id( parameter_.getEnum( keyPrefix_ +
"linesearch", LineSearchMethod::names(),
LineSearchMethod::none ) );
258 virtual void setLineSearch (
const int method )
260 Parameter::append( keyPrefix_ +
"linesearch", LineSearchMethod::to_string(method),
true );
268 virtual int forcing ()
const
270 if( parameter_.exists( keyPrefix_ +
"linear.tolerance.strategy" ) )
272 std::string keypref( keyPrefix_ );
273 std::string femsolver(
"fem.solver.");
274 size_t pos = keypref.find( femsolver );
275 if (pos != std::string::npos)
278 keypref.erase(pos, femsolver.length());
280 std::cout <<
"WARNING: using old parameter name '" << keypref +
"linear.tolerance.strategy" <<
"',\n"
281 <<
"please switch to '" << keypref +
"forcing" <<
"'!" <<std::endl;
282 return Forcing::to_id( parameter_.getEnum( keyPrefix_ +
"linear.tolerance.strategy", Forcing::names(),
Forcing::none ) );
284 return Forcing::to_id( parameter_.getEnum( keyPrefix_ +
"forcing", Forcing::names(),
Forcing::none ) );
287 virtual void setForcing (
const int strategy )
289 Parameter::append( keyPrefix_ +
"forcing", Forcing::to_string( strategy ),
true );
293 virtual bool simplified ()
const
295 return parameter_.getValue<
bool >( keyPrefix_ +
"simplified", 0 );
300 virtual bool forceNonLinear ()
const
303 v = parameter_.getValue<
bool >(keyPrefix_ +
"forcenonlinear", v );
308 mutable double tolerance_ = -1;
309 mutable int verbose_ = -1;
310 mutable int maxIterations_ = -1;
311 mutable int maxLinearIterations_ = -1;
312 mutable int maxLineSearchIterations_ = -1;
320 enum class NewtonFailure
325 IterationsExceeded = 2,
326 LinearIterationsExceeded = 3,
327 LineSearchFailed = 4,
328 TooManyIterations = 5,
329 TooManyLinearIterations = 6,
330 LinearSolverFailed = 7
354 template<
class JacobianOperator,
class LInvOp >
356 :
public Operator< typename JacobianOperator::RangeFunctionType, typename JacobianOperator::DomainFunctionType >
362 template <
class Obj,
bool defaultValue = false >
363 struct SelectPreconditioning
366 template <
typename T,
typename =
bool>
367 struct CheckMember :
public std::false_type { };
369 template <
typename T>
372 template <
class T,
bool>
375 static const bool value = defaultValue;
380 struct SelectValue< T, true >
382 static const bool value = T::preconditioningAvailable;
383 typedef typename T::PreconditionerType type;
386 static constexpr bool value = SelectValue< Obj, CheckMember< Obj >::value >::value;
387 typedef typename SelectValue< Obj, CheckMember< Obj >::value >::type type;
402 typedef typename SelectPreconditioning< LinearInverseOperatorType > :: type
PreconditionerType;
409 typedef NewtonParameter<typename LinearInverseOperatorType::SolverParameterType> ParameterType;
411 typedef std::function< bool (
const RangeFunctionType &w,
const RangeFunctionType &dw,
double residualNorm ) > ErrorMeasureType;
435 : verbose_( parameter.verbose() ),
436 maxLineSearchIterations_( parameter.maxLineSearchIterations() ),
437 jInv_(
std::move( jInv ) ),
438 parameter_(parameter),
439 lsMethod_( parameter.lineSearch() ),
440 finished_( [ epsilon ] ( const RangeFunctionType &w, const RangeFunctionType &dw, double res ) {
return res < epsilon; } ),
441 forcing_ ( parameter.forcing() ),
442 eisenstatWalker_ ( epsilon ),
476 const ParameterReader ¶meter = Parameter::container() )
488 void setErrorMeasure ( ErrorMeasureType finished ) { finished_ = std::move( finished ); }
494 void bind (
const OperatorType &op,
const PreconditionerType& preconditioner )
498 preconditioner_ = &preconditioner;
500 std::cerr <<
"WARNING: linear inverse operator does not support external preconditioning!" << std::endl;
503 void unbind () { op_ =
nullptr; preconditioner_ =
nullptr; }
505 virtual void operator() (
const DomainFunctionType &u, RangeFunctionType &w )
const;
507 int iterations ()
const {
return iterations_; }
508 void setMaxIterations (
int maxIterations ) { parameter_.setMaxIterations( maxIterations ); }
509 int linearIterations ()
const {
return linearIterations_; }
510 void setMaxLinearIterations (
int maxLinearIterations ) { parameter_.setMaxLinearIterations( maxLinearIterations ); }
511 void updateLinearTolerance ()
const {
512 if (forcing_ == ParameterType::Forcing::eisenstatwalker) {
513 double newTol = eisenstatWalker_.nextLinearTolerance( delta_ );
514 jInv_.parameter().setTolerance( newTol );
517 bool verbose()
const {
return verbose_ &&
Parameter::verbose( Parameter::solverStatistics ); }
518 double residual ()
const {
return delta_; }
520 NewtonFailure failed ()
const
525 return NewtonFailure::InvalidResidual;
526 else if( iterations_ >= parameter_.maxIterations() )
527 return NewtonFailure::TooManyIterations;
528 else if( linearIterations_ >= parameter_.maxLinearIterations() )
529 return NewtonFailure::TooManyLinearIterations;
530 else if( linearIterations_ < 0)
531 return NewtonFailure::LinearSolverFailed;
532 else if( !stepCompleted_ )
533 return NewtonFailure::LineSearchFailed;
535 return NewtonFailure::Success;
538 bool converged ()
const {
return failed() == NewtonFailure::Success; }
540 virtual int lineSearch(RangeFunctionType &w, RangeFunctionType &dw,
541 const DomainFunctionType &u, DomainFunctionType &residual)
const
543 double deltaOld = delta_;
544 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
547 if (failed() == NewtonFailure::InvalidResidual)
549 double test = dw.scalarProductDofs( dw );
552 delta_ = 2.*deltaOld;
555 int noLineSearch = (delta_ < deltaOld)?1:0;
556 int lineSearchIteration = 0;
557 const bool lsVerbose = verbose() &&
Parameter::verbose( Parameter::extendedStatistics );
558 while (delta_ >= deltaOld)
560 double deltaPrev = delta_;
563 std::cout <<
" line search:" << delta_ <<
">" << deltaOld << std::endl;
564 if (std::abs(delta_-deltaOld) < 1e-5*delta_)
567 (*op_)( w, residual );
569 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
570 if (std::abs(delta_-deltaPrev) < 1e-15)
572 if (failed() == NewtonFailure::InvalidResidual)
573 delta_ = 2.*deltaOld;
575 ++lineSearchIteration;
576 if( lineSearchIteration >= maxLineSearchIterations_ )
583 const std::vector<double>&
timing()
const {
return timing_; }
594 if( preconditioner_ )
596 jInv_.bind( jOp, *preconditioner_ );
606 template<
class ... Args>
616 const PreconditionerType* preconditioner_ =
nullptr;
619 const int maxLineSearchIterations_;
621 mutable DomainFieldType delta_;
622 mutable int iterations_;
623 mutable int linearIterations_;
625 mutable std::unique_ptr< JacobianOperatorType > jOp_;
626 ParameterType parameter_;
627 mutable int stepCompleted_;
629 ErrorMeasureType finished_;
631 EisenstatWalkerStrategy eisenstatWalker_;
633 mutable std::vector<double> timing_;
640 template<
class JacobianOperator,
class LInvOp >
641 inline void NewtonInverseOperator< JacobianOperator, LInvOp >
642 ::operator() (
const DomainFunctionType &u, RangeFunctionType &w )
const
645 std::fill(timing_.begin(), timing_.end(), 0.0 );
648 const bool nonlinear = op_->nonlinear() || parameter_.forceNonLinear();
651 DomainFunctionType residual( u );
652 RangeFunctionType dw( w );
655 double jacTime = 0.0;
656 JacobianOperatorType& jOp = jacobian(
"jacobianOperator", dw.space(), u.space(), parameter_.solverParameter() );
659 stepCompleted_ =
true;
661 linearIterations_ = 0;
663 (*op_)( w, residual );
665 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
666 updateLinearTolerance();
669 bool computeJacobian =
true;
670 const bool simplifiedNewton = parameter_.simplified();
672 const bool newtonVerbose = verbose() && nonlinear;
675 std::cout <<
"Start Newton: tol = " << parameter_.tolerance() <<
" (forcing = " << ParameterType::Forcing::to_string(forcing_) <<
" | linear tol = " << parameter_.linear().tolerance() <<
")"<<std::endl;
676 std::cout <<
"Newton iteration " << iterations_ <<
": |residual| = " << delta_;
681 std::cout << std::endl;
683 if( computeJacobian )
687 (*op_).jacobian( w, jOp );
690 computeJacobian = ! simplifiedNewton;
694 bindOperatorAndPreconditioner( jOp );
697 if ( parameter_.maxLinearIterations() - linearIterations_ <= 0 )
699 jInv_.setMaxIterations( parameter_.maxLinearIterations() - linearIterations_ );
702 jInv_( residual, dw );
704 if (jInv_.iterations() < 0)
706 linearIterations_ = jInv_.iterations();
709 linearIterations_ += jInv_.iterations();
717 (*op_)( w, residual );
723 int ls = lineSearch(w,dw,u,residual);
724 stepCompleted_ = ls >= 0;
725 updateLinearTolerance();
729 std::cout <<
"Newton iteration " << iterations_ <<
": |residual| = " << delta_ << std::flush;
731 if ( (finished_(w, dw, delta_)) || !converged())
735 std::cout << std::endl;
736 std::cout <<
"Linear iterations: " << linearIterations_ << std::endl;
746 std::cout << std::endl;
751 timing_[0] = allTimer.
elapsed();
752 timing_[1] = jacTime;
753 timing_[2] = timing_[0] - jacTime;
abstract differentiable operator
Definition: differentiableoperator.hh:29
Adaptive tolerance selection for linear solver.
Definition: newtoninverseoperator.hh:38
EisenstatWalkerStrategy(const double newtonTolerance)
Definition: newtoninverseoperator.hh:50
inverse operator based on a newton scheme
Definition: newtoninverseoperator.hh:357
NewtonInverseOperator(LinearInverseOperatorType jInv, const DomainFieldType &epsilon, const ParameterType ¶meter)
Definition: newtoninverseoperator.hh:434
Impl::SolverInfo SolverInfoType
performance info about last solver call
Definition: newtoninverseoperator.hh:414
static constexpr bool preconditioningAvailable
type of preconditioner for linear solver
Definition: newtoninverseoperator.hh:401
JacobianOperator JacobianOperatorType
type of operator's Jacobian
Definition: newtoninverseoperator.hh:392
NewtonInverseOperator(const ParameterType ¶meter=ParameterType(Parameter::container()))
Definition: newtoninverseoperator.hh:453
const std::vector< double > & timing() const
returns [overall, jacobian, solve] timings in seconds for last operator () call.
Definition: newtoninverseoperator.hh:583
SolverInfoType info() const
return performance information about last solver run */
Definition: newtoninverseoperator.hh:586
NewtonInverseOperator(const DomainFieldType &epsilon, const ParameterReader ¶meter=Parameter::container())
Definition: newtoninverseoperator.hh:475
void setErrorMeasure(ErrorMeasureType finished)
Definition: newtoninverseoperator.hh:488
DifferentiableOperator< JacobianOperatorType > OperatorType
type of operator to invert
Definition: newtoninverseoperator.hh:395
LInvOp LinearInverseOperatorType
type of linear inverse operator
Definition: newtoninverseoperator.hh:398
NewtonInverseOperator(const DomainFieldType &epsilon, const ParameterType ¶meter)
Definition: newtoninverseoperator.hh:464
static bool verbose()
obtain the cached value for fem.verbose with default verbosity level 2
Definition: parameter.hh:466
static void append(int &argc, char **argv)
add parameters from the command line RangeType gRight;
Definition: parameter.hh:219
A simple stop watch.
Definition: timer.hh:43
void reset() noexcept
Reset timer while keeping the running/stopped state.
Definition: timer.hh:57
double elapsed() const noexcept
Get elapsed user-time from last reset until now/last stop in seconds.
Definition: timer.hh:77
A few common exception classes.
#define DUNE_THROW(E, m)
Definition: exceptions.hh:218
constexpr GeometryType none(unsigned int dim)
Returns a GeometryType representing a singular of dimension dim.
Definition: type.hh:471
constexpr auto max
Function object that returns the greater of the given values.
Definition: hybridutilities.hh:484
constexpr auto min
Function object that returns the smaller of the given values.
Definition: hybridutilities.hh:506
Dune namespace.
Definition: alignedallocator.hh:13
abstract operator
Definition: operator.hh:34
DomainFunction DomainFunctionType
type of discrete function in the operator's domain
Definition: operator.hh:36
DomainFunction::RangeFieldType DomainFieldType
field type of the operator's domain
Definition: operator.hh:41
RangeFunction RangeFunctionType
type of discrete function in the operator's range
Definition: operator.hh:38