DUNE-FEM (unstable)

newtoninverseoperator.hh
1#ifndef DUNE_FEM_NEWTONINVERSEOPERATOR_HH
2#define DUNE_FEM_NEWTONINVERSEOPERATOR_HH
3
4#include <cassert>
5#include <cmath>
6
7#include <iostream>
8#include <limits>
9#include <memory>
10#include <string>
11#include <regex>
12#include <utility>
13
14#include <dune/common/timer.hh>
16
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>
23
24namespace Dune
25{
26
27 namespace Fem
28 {
29
38 {
39 protected:
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_;
45
46 public:
50 EisenstatWalkerStrategy(const double newtonTolerance) : newtonTolerance_(newtonTolerance) {}
51 double nextLinearTolerance(const double currentResidual) const
52 {
53 double eta = etaMax_;
54 // First call previousEta_ is negative
55 if (previousEta_ >= 0.0)
56 {
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));
61 }
62 previousResidual_ = currentResidual;
63 previousEta_ = eta;
64 return eta;
65 }
66 void setTolerance(const double newtonTolerance) { newtonTolerance_ = newtonTolerance; }
67 };
68
69 // NewtonParameter
70 // ---------------
71
72 template <class SolverParam = SolverParameter>
73 struct NewtonParameter
74 : public Dune::Fem::LocalParameter< NewtonParameter<SolverParam>, NewtonParameter<SolverParam> >
75 {
76 protected:
77
78 std::shared_ptr<SolverParam> baseParam_;
79 // key prefix, default is fem.solver.nonlinear. (can be overloaded by user)
80 const std::string keyPrefix_;
81
82 ParameterReader parameter_;
83
84 void checkDeprecatedParameters() const
85 {
86 const std::string newton("newton.");
87 const std::size_t pos = keyPrefix_.find( newton );
88 if( pos != std::string::npos )
89 {
90 DUNE_THROW(InvalidStateException,"Keyprefix 'newton' is deprecated, replace with 'nonlinear'!");
91 }
92
93 const std::string params[]
94 = { "tolerance", "lineSearch", "maxterations", "linear", "maxlinesearchiterations" };
95 for( const auto& p : params )
96 {
97 std::string key( "fem.solver.newton." );
98 key += p;
99 if( parameter_.exists( key ) )
100 DUNE_THROW(InvalidStateException,"Keyprefix 'newton' is deprecated, replace with 'nonlinear'!");
101 }
102 }
103
104 std::string replaceNonLinearWithLinear( const std::string& keyPrefix ) const
105 {
106 if( keyPrefix.find( "nonlinear" ) != std::string::npos )
107 {
108 return std::regex_replace(keyPrefix, std::regex("nonlinear"), "linear" );
109 }
110 else
111 return keyPrefix;
112 }
113 public:
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() )
118 {
119 checkDeprecatedParameters();
120 }
121
122 template <class Parameter, std::enable_if_t<!std::is_base_of<SolverParam,Parameter>::value && !std::is_same<Parameter,ParameterReader>::value,int> i=0>
123 NewtonParameter( const Parameter& solverParameter, const std::string keyPrefix = "fem.solver.nonlinear." )
124 : baseParam_( new SolverParam(solverParameter) ),
125 keyPrefix_( keyPrefix ),
126 parameter_( solverParameter.parameter() )
127 {
128 checkDeprecatedParameters();
129 }
130
131 template <class ParamReader, std::enable_if_t<!std::is_same<ParamReader,SolverParam>::value && std::is_same<ParamReader,ParameterReader>::value,int> i=0>
132 NewtonParameter( const ParamReader &parameter, const std::string keyPrefix = "fem.solver.nonlinear." )
133 // pass keyprefix for linear solvers, which is the same as keyprefix with nonlinear replaced by linear
134 : baseParam_( std::make_shared<SolverParam>( replaceNonLinearWithLinear(keyPrefix), parameter) ),
135 keyPrefix_( keyPrefix),
136 parameter_( parameter )
137 {
138 checkDeprecatedParameters();
139 }
140
141 const ParameterReader &parameter () const { return parameter_; }
142 const SolverParam& solverParameter () const { return *baseParam_; }
143 const SolverParam& linear () const { return *baseParam_; }
144
145 virtual void reset ()
146 {
147 baseParam_->reset();
148 tolerance_ = -1;
149 verbose_ = -1;
150 maxIterations_ = -1;
151 maxLinearIterations_ = -1;
152 maxLineSearchIterations_ = -1;
153 }
154
155 //These methods affect the nonlinear solver
156 virtual double tolerance () const
157 {
158 if(tolerance_ < 0)
159 tolerance_ = parameter_.getValue< double >( keyPrefix_ + "tolerance", 1e-6 );
160 return tolerance_;
161 }
162
163 virtual void setTolerance ( const double tol )
164 {
165 assert( tol > 0 );
166 tolerance_ = tol;
167 }
168
169 virtual bool verbose () const
170 {
171 if(verbose_ < 0)
172 {
173 // the following causes problems with different default values
174 // used if baseParam_->keyPrefix is not default but the default is
175 // also used in the program
176 // const bool v = baseParam_? baseParam_->verbose() : false;
177 const bool v = false;
178 verbose_ = parameter_.getValue< bool >(keyPrefix_ + "verbose", v ) ? 1 : 0 ;
179 }
180 return verbose_;
181 }
182
183 virtual void setVerbose( bool verb)
184 {
185 verbose_ = verb ? 1 : 0;
186 }
187
188 virtual int maxIterations () const
189 {
190 if(maxIterations_ < 0)
191 maxIterations_ = parameter_.getValue< int >( keyPrefix_ + "maxiterations", std::numeric_limits< int >::max() );
192 return maxIterations_;
193 }
194
195 virtual void setMaxIterations ( const int maxIter )
196 {
197 assert(maxIter >= 0);
198 maxIterations_ = maxIter;
199 }
200
201 //Maximum Linear Iterations in total
203 virtual int maxLinearIterations () const
204 {
205 if(maxLinearIterations_ < 0)
206 maxLinearIterations_ = linear().maxIterations();
207 return maxLinearIterations_;
208 }
209
210 virtual void setMaxLinearIterations ( const int maxLinearIter )
211 {
212 assert(maxLinearIter >=0);
213 maxLinearIterations_ = maxLinearIter;
214 }
215
216 virtual int maxLineSearchIterations () const
217 {
218 if(maxLineSearchIterations_ < 0)
219 maxLineSearchIterations_ = parameter_.getValue< int >( keyPrefix_ + "maxlinesearchiterations", std::numeric_limits< int >::max() );
220 return maxLineSearchIterations_;
221 }
222
223 virtual void setMaxLineSearchIterations ( const int maxLineSearchIter )
224 {
225 assert( maxLineSearchIter >= 0);
226 maxLineSearchIterations_ = maxLineSearchIter;
227 }
228
229 // LineSearchMethod: none, simple
230 LIST_OF_INT(LineSearchMethod,
231 none=0,
232 simple=1);
233
234 virtual int lineSearch () const
235 {
236 if( parameter_.exists( keyPrefix_ + "lineSearch" ) )
237 {
238 std::cout << "WARNING: using old parameter name '" << keyPrefix_ + "lineSearch" << "',\n"
239 << "please switch to '" << keyPrefix_ + "linesearch" << "' (all lower caps)!" <<std::endl;
240 return Forcing::to_id( parameter_.getEnum( keyPrefix_ + "lineSearch", LineSearchMethod::names(), LineSearchMethod::none ) );
241 }
242 return Forcing::to_id( parameter_.getEnum( keyPrefix_ + "linesearch", LineSearchMethod::names(), LineSearchMethod::none ) );
243 }
244
245 virtual void setLineSearch ( const int method )
246 {
247 Parameter::append( keyPrefix_ + "linesearch", LineSearchMethod::to_string(method), true );
248 }
249
250 // Forcing: none, eisenstatwalker
251 LIST_OF_INT(Forcing,
252 none = 0, // the provided linear solver tol is used in every iteration
253 eisenstatwalker=1); // Eistenstat-Walker criterion
254
255 virtual int forcing () const
256 {
257 if( parameter_.exists( keyPrefix_ + "linear.tolerance.strategy" ) )
258 {
259 std::string keypref( keyPrefix_ );
260 std::string femsolver("fem.solver.");
261 size_t pos = keypref.find( femsolver );
262 if (pos != std::string::npos)
263 {
264 // If found then erase it from string
265 keypref.erase(pos, femsolver.length());
266 }
267 std::cout << "WARNING: using old parameter name '" << keypref + "linear.tolerance.strategy" << "',\n"
268 << "please switch to '" << keypref + "forcing" << "'!" <<std::endl;
269 return Forcing::to_id( parameter_.getEnum( keyPrefix_ + "linear.tolerance.strategy", Forcing::names(), Forcing::none ) );
270 }
271 return Forcing::to_id( parameter_.getEnum( keyPrefix_ + "forcing", Forcing::names(), Forcing::none ) );
272 }
273
274 virtual void setForcing ( const int strategy )
275 {
276 Parameter::append( keyPrefix_ + "forcing", Forcing::to_string( strategy ), true );
277 }
278
280 virtual bool simplified () const
281 {
282 return parameter_.getValue< bool >( keyPrefix_ + "simplified", 0 );
283 }
284
285 // allow to override the automatic choice of nonlinear or linear solver to
286 // force nonlinear all the time
287 virtual bool forceNonLinear () const
288 {
289 bool v = false;
290 v = parameter_.getValue< bool >(keyPrefix_ + "forcenonlinear", v );
291 return v;
292 }
293
294 private:
295 mutable double tolerance_ = -1;
296 mutable int verbose_ = -1;
297 mutable int maxIterations_ = -1;
298 mutable int maxLinearIterations_ = -1;
299 mutable int maxLineSearchIterations_ = -1;
300 };
301
302
303
304 // NewtonFailure
305 // -------------
306
307 enum class NewtonFailure
308 // : public int
309 {
310 Success = 0,
311 InvalidResidual = 1,
312 IterationsExceeded = 2,
313 LinearIterationsExceeded = 3,
314 LineSearchFailed = 4,
315 TooManyIterations = 5,
316 TooManyLinearIterations = 6,
317 LinearSolverFailed = 7
318 };
319
320
321
322 // NewtonInverseOperator
323 // ---------------------
324
341 template< class JacobianOperator, class LInvOp >
343 : public Operator< typename JacobianOperator::RangeFunctionType, typename JacobianOperator::DomainFunctionType >
344 {
347
349 template <class Obj, bool defaultValue = false >
350 struct SelectPreconditioning
351 {
352 private:
353 template <typename T, typename = bool>
354 struct CheckMember : public std::false_type { };
355
356 template <typename T>
357 struct CheckMember<T, decltype((void) T::preconditioningAvailable, true)> : public std::true_type { };
358
359 template <class T, bool>
360 struct SelectValue
361 {
362 static const bool value = defaultValue;
363 typedef BaseType type;
364 };
365
366 template <class T>
367 struct SelectValue< T, true >
368 {
369 static const bool value = T::preconditioningAvailable;
370 typedef typename T::PreconditionerType type;
371 };
372 public:
373 static constexpr bool value = SelectValue< Obj, CheckMember< Obj >::value >::value;
374 typedef typename SelectValue< Obj, CheckMember< Obj >::value >::type type;
375 };
376
377 public:
379 typedef JacobianOperator JacobianOperatorType;
380
383
386
388 static constexpr bool preconditioningAvailable = SelectPreconditioning< LinearInverseOperatorType > :: value;
389 typedef typename SelectPreconditioning< LinearInverseOperatorType > :: type PreconditionerType;
390
391 typedef typename BaseType::DomainFunctionType DomainFunctionType;
392 typedef typename BaseType::RangeFunctionType RangeFunctionType;
393
394 typedef typename BaseType::DomainFieldType DomainFieldType;
395
396 typedef NewtonParameter<typename LinearInverseOperatorType::SolverParameterType> ParameterType;
397
398 typedef std::function< bool ( const RangeFunctionType &w, const RangeFunctionType &dw, double residualNorm ) > ErrorMeasureType;
399
401 typedef Impl::SolverInfo SolverInfoType;
402
420 // main constructor
421 NewtonInverseOperator ( LinearInverseOperatorType jInv, const DomainFieldType &epsilon, const ParameterType &parameter )
422 : verbose_( parameter.verbose() ),
423 maxLineSearchIterations_( parameter.maxLineSearchIterations() ),
424 jInv_( std::move( jInv ) ),
425 parameter_(parameter),
426 lsMethod_( parameter.lineSearch() ),
427 finished_( [ epsilon ] ( const RangeFunctionType &w, const RangeFunctionType &dw, double res ) { return res < epsilon; } ),
428 forcing_ ( parameter.forcing() ),
429 eisenstatWalker_ ( epsilon ),
430 timing_(3, 0.0)
431 {
432 if (forcing_ == ParameterType::Forcing::eisenstatwalker) {
433 if (parameter_.linear().errorMeasure() != LinearSolver::ToleranceCriteria::residualReduction) {
434 DUNE_THROW( InvalidStateException, "Parameter `nonlinear.linear.errormeasure` selecting the tolerance criteria in the linear solver must be `residualreduction` when using Eisenstat-Walker." );
435 }
436 }
437 }
438
439
445 explicit NewtonInverseOperator ( const ParameterType &parameter = ParameterType( Parameter::container() ) )
446 : NewtonInverseOperator( parameter.tolerance(), parameter )
447 {
448 // std::cout << "in Newton inv op should use:" << parameter.linear().solverMethod({SolverParameter::gmres,SolverParameter::bicgstab,SolverParameter::minres}) << std::endl;
449 }
450
456 NewtonInverseOperator ( const DomainFieldType &epsilon, const ParameterType &parameter )
458 LinearInverseOperatorType( parameter.linear() ),
459 epsilon, parameter )
460 {}
461
467 NewtonInverseOperator ( const DomainFieldType &epsilon,
468 const ParameterReader &parameter = Parameter::container() )
469 : NewtonInverseOperator( epsilon, ParameterType( parameter ) )
470 {}
471
472
480 void setErrorMeasure ( ErrorMeasureType finished ) { finished_ = std::move( finished ); }
481
482 EisenstatWalkerStrategy& eisenstatWalker () { return eisenstatWalker_; }
483
484 void bind ( const OperatorType &op ) { op_ = &op; }
485
486 void bind ( const OperatorType &op, const PreconditionerType& preconditioner )
487 {
488 bind( op );
490 preconditioner_ = &preconditioner;
491 else
492 std::cerr << "WARNING: linear inverse operator does not support external preconditioning!" << std::endl;
493 }
494
495 void unbind () { op_ = nullptr; preconditioner_ = nullptr; }
496
497 virtual void operator() ( const DomainFunctionType &u, RangeFunctionType &w ) const;
498
499 int iterations () const { return iterations_; }
500 void setMaxIterations ( int maxIterations ) { parameter_.setMaxIterations( maxIterations ); }
501 int linearIterations () const { return linearIterations_; }
502 void setMaxLinearIterations ( int maxLinearIterations ) { parameter_.setMaxLinearIterations( maxLinearIterations ); }
503 void updateLinearTolerance () const {
504 if (forcing_ == ParameterType::Forcing::eisenstatwalker) {
505 double newTol = eisenstatWalker_.nextLinearTolerance( delta_ );
506 jInv_.parameter().setTolerance( newTol );
507 }
508 }
509 bool verbose() const { return verbose_ && Parameter::verbose( Parameter::solverStatistics ); }
510 double residual () const { return delta_; }
511
512 NewtonFailure failed () const
513 {
514 // check for finite |residual| - this also works for -ffinite-math-only (gcc)
515 // nan test not working with optimization flags...
516 if( !(delta_ < std::numeric_limits< DomainFieldType >::max()) || std::isnan( delta_ ) )
517 return NewtonFailure::InvalidResidual;
518 else if( iterations_ >= parameter_.maxIterations() )
519 return NewtonFailure::TooManyIterations;
520 else if( linearIterations_ >= parameter_.maxLinearIterations() )
521 return NewtonFailure::TooManyLinearIterations;
522 else if( linearIterations_ < 0)
523 return NewtonFailure::LinearSolverFailed;
524 else if( !stepCompleted_ )
525 return NewtonFailure::LineSearchFailed;
526 else
527 return NewtonFailure::Success;
528 }
529
530 bool converged () const { return failed() == NewtonFailure::Success; }
531
532 virtual int lineSearch(RangeFunctionType &w, RangeFunctionType &dw,
533 const DomainFunctionType &u, DomainFunctionType &residual) const
534 {
535 double deltaOld = delta_;
536 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
538 return 0;
539 if (failed() == NewtonFailure::InvalidResidual)
540 {
541 double test = dw.scalarProductDofs( dw );
543 !std::isnan(test)) )
544 delta_ = 2.*deltaOld; // enter line search
545 }
546 double factor = 1.0;
547 int noLineSearch = (delta_ < deltaOld)?1:0;
548 int lineSearchIteration = 0;
549 const bool lsVerbose = verbose() && Parameter::verbose( Parameter::extendedStatistics );
550 while (delta_ >= deltaOld)
551 {
552 double deltaPrev = delta_;
553 factor *= 0.5;
554 if( lsVerbose )
555 std::cout << " line search:" << delta_ << ">" << deltaOld << std::endl;
556 if (std::abs(delta_-deltaOld) < 1e-5*delta_) // || !converged()) // line search not working
557 return -1; // failed
558 w.axpy(factor,dw);
559 (*op_)( w, residual );
560 residual -= u;
561 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
562 if (std::abs(delta_-deltaPrev) < 1e-15)
563 return -1;
564 if (failed() == NewtonFailure::InvalidResidual)
565 delta_ = 2.*deltaOld; // remain in line search
566
567 ++lineSearchIteration;
568 if( lineSearchIteration >= maxLineSearchIterations_ )
569 return -1; // failed
570 }
571 return noLineSearch;
572 }
573
575 const std::vector<double>& timing() const { return timing_; }
576
578 SolverInfoType info() const { return SolverInfoType( converged(), linearIterations(), iterations(), timing() ); }
579
580 protected:
581 void bindOperatorAndPreconditioner( JacobianOperatorType& jOp ) const
582 {
583 // if preconditioner was given pass it on to linear solver
584 if constexpr ( preconditioningAvailable )
585 {
586 if( preconditioner_ )
587 {
588 jInv_.bind( jOp, *preconditioner_ );
589 return ;
590 }
591 }
592
593 // if preconditioning not enabled or set, then only set jOp
594 jInv_.bind( jOp );
595 }
596
597 // hold pointer to jacobian operator, if memory reallocation is needed, the operator should know how to handle this.
598 template< class ... Args>
599 JacobianOperatorType& jacobian ( Args && ... args ) const
600 {
601 if( !jOp_ )
602 jOp_.reset( new JacobianOperatorType( std::forward< Args >( args ) ...) ); //, parameter_.parameter() ) );
603 return *jOp_;
604 }
605
606 protected:
607 const OperatorType *op_ = nullptr;
608 const PreconditionerType* preconditioner_ = nullptr;
609
610 const bool verbose_;
611 const int maxLineSearchIterations_;
612
613 mutable DomainFieldType delta_;
614 mutable int iterations_;
615 mutable int linearIterations_;
616 mutable LinearInverseOperatorType jInv_;
617 mutable std::unique_ptr< JacobianOperatorType > jOp_;
618 ParameterType parameter_;
619 mutable int stepCompleted_;
620 const int lsMethod_;
621 ErrorMeasureType finished_;
622 const int forcing_;
623 EisenstatWalkerStrategy eisenstatWalker_;
624
625 mutable std::vector<double> timing_;
626 };
627
628
629 // Implementation of NewtonInverseOperator
630 // ---------------------------------------
631
632 template< class JacobianOperator, class LInvOp >
633 inline void NewtonInverseOperator< JacobianOperator, LInvOp >
634 ::operator() ( const DomainFunctionType &u, RangeFunctionType &w ) const
635 {
636 assert( op_ );
637 std::fill(timing_.begin(), timing_.end(), 0.0 );
638
639 // obtain information about operator to invert
640 const bool nonlinear = op_->nonlinear() || parameter_.forceNonLinear();
641
642 Dune::Timer allTimer;
643 DomainFunctionType residual( u );
644 RangeFunctionType dw( w );
645
646 Dune::Timer jacTimer;
647 double jacTime = 0.0;
648 JacobianOperatorType& jOp = jacobian( "jacobianOperator", dw.space(), u.space(), parameter_.solverParameter() );
649 jacTime += jacTimer.elapsed();
650
651 stepCompleted_ = true;
652 iterations_ = 0;
653 linearIterations_ = 0;
654 // compute initial residual
655 (*op_)( w, residual ); // r=S[w], r=w-g on bnd
656 residual -= u; // r=S[w]-u, r=w-g-u on bnd (note: we should start with w=g+u on bnd so r=0)
657 delta_ = std::sqrt( residual.scalarProductDofs( residual ) );
658 updateLinearTolerance();
659
660 // this is true for Newton, and false simplified Newton after first iteration
661 bool computeJacobian = true;
662 const bool simplifiedNewton = parameter_.simplified();
663
664 const bool newtonVerbose = verbose() && nonlinear;
665 if( newtonVerbose )
666 {
667 std::cout << "Start Newton: tol = " << parameter_.tolerance() << " (forcing = " << ParameterType::Forcing::to_string(forcing_) << " | linear tol = " << parameter_.linear().tolerance() << ")"<<std::endl;
668 std::cout << "Newton iteration " << iterations_ << ": |residual| = " << delta_;
669 }
670 while( true )
671 {
672 if( newtonVerbose )
673 std::cout << std::endl;
674
675 if( computeJacobian )
676 {
677 // evaluate operator's Jacobian
678 jacTimer.reset();
679 (*op_).jacobian( w, jOp );
680
681 // if simplified Newton is activated do not compute Jacobian again
682 computeJacobian = ! simplifiedNewton;
683 }
684
685 // bind jOp to jInv including preconditioner if enabled and set
686 bindOperatorAndPreconditioner( jOp );
687 jacTime += jacTimer.elapsed();
688
689 if ( parameter_.maxLinearIterations() - linearIterations_ <= 0 )
690 break;
691 jInv_.setMaxIterations( parameter_.maxLinearIterations() - linearIterations_ );
692
693 dw.clear();
694 jInv_( residual, dw ); // dw = DS[w]^{-1}(S[w]-u)
695 // dw=w-g-u on bnd
696 if (jInv_.iterations() < 0) // iterations are negative if solver didn't converge
697 {
698 linearIterations_ = jInv_.iterations();
699 break;
700 }
701 linearIterations_ += jInv_.iterations();
702 w -= dw; // w = w - DS[w]^{-1}(S[w]-u)
703 // w = g+u
704
705 // the following only for nonlinear problems
706 if( nonlinear )
707 {
708 // compute new residual
709 (*op_)( w, residual );
710 residual -= u;
711
712 // line search if enabled
713 int ls = lineSearch(w,dw,u,residual);
714 stepCompleted_ = ls >= 0;
715 updateLinearTolerance();
716 ++iterations_;
717
718 if( newtonVerbose )
719 std::cout << "Newton iteration " << iterations_ << ": |residual| = " << delta_ << std::flush;
720 // if ( (ls==1 && finished_(w, dw, delta_)) || !converged())
721 if ( (finished_(w, dw, delta_)) || !converged())
722 {
723 if( newtonVerbose )
724 {
725 std::cout << std::endl;
726 std::cout << "Linear iterations: " << linearIterations_ << std::endl;
727 }
728 break;
729 }
730 }
731 else // in linear case do not continue
732 break ;
733 } // end Newton loop
734
735 if( newtonVerbose )
736 std::cout << std::endl;
737
738 jInv_.unbind();
739
740 // store time measurements
741 timing_[0] = allTimer.elapsed();
742 timing_[1] = jacTime;
743 timing_[2] = timing_[0] - jacTime;
744 }
745
746 } // namespace Fem
747
748} // namespace Dune
749
750#endif // #ifndef DUNE_FEM_NEWTONINVERSEOPERATOR_HH
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:344
NewtonInverseOperator(LinearInverseOperatorType jInv, const DomainFieldType &epsilon, const ParameterType &parameter)
Definition: newtoninverseoperator.hh:421
Impl::SolverInfo SolverInfoType
performance info about last solver call
Definition: newtoninverseoperator.hh:401
static constexpr bool preconditioningAvailable
type of preconditioner for linear solver
Definition: newtoninverseoperator.hh:388
JacobianOperator JacobianOperatorType
type of operator's Jacobian
Definition: newtoninverseoperator.hh:379
NewtonInverseOperator(const ParameterType &parameter=ParameterType(Parameter::container()))
Definition: newtoninverseoperator.hh:445
const std::vector< double > & timing() const
returns [overall, jacobian, solve] timings in seconds for last operator () call.
Definition: newtoninverseoperator.hh:575
SolverInfoType info() const
return performance information about last solver run *‍/
Definition: newtoninverseoperator.hh:578
NewtonInverseOperator(const DomainFieldType &epsilon, const ParameterReader &parameter=Parameter::container())
Definition: newtoninverseoperator.hh:467
void setErrorMeasure(ErrorMeasureType finished)
Definition: newtoninverseoperator.hh:480
DifferentiableOperator< JacobianOperatorType > OperatorType
type of operator to invert
Definition: newtoninverseoperator.hh:382
LInvOp LinearInverseOperatorType
type of linear inverse operator
Definition: newtoninverseoperator.hh:385
NewtonInverseOperator(const DomainFieldType &epsilon, const ParameterType &parameter)
Definition: newtoninverseoperator.hh:456
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
Default exception if a function was called while the object is not in a valid state for that function...
Definition: exceptions.hh:281
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
STL namespace.
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
A simple timing class.
Creative Commons License   |  Legal Statements / Impressum  |  Hosted by TU Dresden  |  generated with Hugo v0.111.3 (Jul 27, 22:29, 2024)