diff --git a/include/pressio/ode/concepts/ode_policy_has_call_overload_for_userdefined_action_on_stencil.hpp b/include/pressio/ode/concepts/ode_policy_has_call_overload_for_userdefined_action_on_stencil.hpp new file mode 100644 index 000000000..5fb0bbb41 --- /dev/null +++ b/include/pressio/ode/concepts/ode_policy_has_call_overload_for_userdefined_action_on_stencil.hpp @@ -0,0 +1,78 @@ +/* +//@HEADER +// ************************************************************************ +// +// ode_has_const_discrete_time_residual_method_accept_step_time_dt_result_states_return_void.hpp +// Pressio +// Copyright 2019 +// National Technology & Engineering Solutions of Sandia, LLC (NTESS) +// +// Under the terms of Contract DE-NA0003525 with NTESS, the +// U.S. Government retains certain rights in this software. +// +// Pressio is licensed under BSD-3-Clause terms of use: +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// 3. Neither the name of the copyright holder nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +// HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +// STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +// IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// +// Questions? Contact Francesco Rizzi (fnrizzi@sandia.gov) +// +// ************************************************************************ +//@HEADER +*/ + +#ifndef ODE_POLICY_HAS_CALL_OVERLOAD_FOR_USERDEFINED_ACTION_ON_STENCIL_HPP_ +#define ODE_POLICY_HAS_CALL_OVERLOAD_FOR_USERDEFINED_ACTION_ON_STENCIL_HPP_ + +namespace pressio{ namespace ode{ + +template +using policy_has_call_overload_for_userdefined_action_on_stencil_states_t = + decltype + ( + std::declval() + ( + std::declval(), + std::declval(), + std::declval(), + std::declval const & >(), + std::declval & >(), + std::declval< ::pressio::ode::StepEndAt >(), + std::declval< ::pressio::ode::StepCount >(), + std::declval< ::pressio::ode::StepSize >(), + std::declval(), +#ifdef PRESSIO_ENABLE_CXX17 + std::declval< std::optional >() +#else + std::declval< typename T::jacobian_type* >() +#endif + ) + ); + +}} +#endif diff --git a/include/pressio/ode/concepts/ode_system.hpp b/include/pressio/ode/concepts/ode_system.hpp index e95489d6f..b0c58e0f7 100644 --- a/include/pressio/ode/concepts/ode_system.hpp +++ b/include/pressio/ode/concepts/ode_system.hpp @@ -4,6 +4,7 @@ #include "ode_predicates_for_system.hpp" #include "ode_has_const_discrete_residual_jacobian_method.hpp" +#include "ode_policy_has_call_overload_for_userdefined_action_on_stencil.hpp" namespace pressio{ namespace ode{ @@ -338,5 +339,18 @@ struct ImplicitResidualJacobianPolicy< > > : std::true_type{}; +template +struct ImplicitResidualJacobianPolicyForUserDefinedStencilStatesAction + : std::false_type{}; + +template +struct ImplicitResidualJacobianPolicyForUserDefinedStencilStatesAction< + T, + ::pressio::mpl::enable_if_t< + ImplicitResidualJacobianPolicy::value && + mpl::is_detected< policy_has_call_overload_for_userdefined_action_on_stencil_states_t >::value + > + > : std::true_type{}; + }} #endif diff --git a/include/pressio/ode/concepts/ode_system_cxx20.hpp b/include/pressio/ode/concepts/ode_system_cxx20.hpp index f1f0c54cc..fde81a1a4 100644 --- a/include/pressio/ode/concepts/ode_system_cxx20.hpp +++ b/include/pressio/ode/concepts/ode_system_cxx20.hpp @@ -4,6 +4,7 @@ #include #include "ode_has_const_discrete_residual_jacobian_method.hpp" +#include "ode_policy_has_call_overload_for_userdefined_action_on_stencil.hpp" namespace pressio{ namespace ode{ @@ -194,6 +195,25 @@ concept ImplicitResidualJacobianPolicy = stencilVelocities, rhsEvaluationTime, stepNumber, dt, R, J); }; + +template +concept ImplicitResidualJacobianPolicyForUserDefinedStencilStatesAction = + ImplicitResidualJacobianPolicy + && requires(const T & A, + StepScheme schemeName, + const typename T::state_type & predictedState, + const ImplicitStencilStatesDynamicContainer & stencilStatesManager, + ImplicitStencilRightHandSideDynamicContainer & stencilVelocities, + const ::pressio::ode::StepEndAt & rhsEvaluationTime, + ::pressio::ode::StepCount stepNumber, + const ::pressio::ode::StepSize & dt, + typename T::residual_type & R, + std::optional & J) + { + A(StencilStatesPotentiallyOverwrittenByUser(), schemeName, predictedState, + stencilStatesManager, stencilVelocities, rhsEvaluationTime, stepNumber, dt, R, J); + }; + // // auxiliary stuff // diff --git a/include/pressio/ode/impl/ode_implicit_stepper_standard.hpp b/include/pressio/ode/impl/ode_implicit_stepper_standard.hpp index 2a396bf9c..856758cc0 100644 --- a/include/pressio/ode/impl/ode_implicit_stepper_standard.hpp +++ b/include/pressio/ode/impl/ode_implicit_stepper_standard.hpp @@ -56,7 +56,7 @@ template< class StateType, class ResidualType, class JacobianType, - class ResidualJacobianPolicyType + class ResidualJacobianPolicyPossiblyRefType > class ImplicitStepperStandardImpl { @@ -84,13 +84,15 @@ class ImplicitStepperStandardImpl // for cn : y_n ImplicitStencilStatesDynamicContainer stencil_states_; - ::pressio::utils::InstanceOrReferenceWrapper rj_policy_; + ::pressio::utils::InstanceOrReferenceWrapper rj_policy_; // stencilRightHandSide contains: // for bdf1,2: nothing // for cn: f(y_n,t_n) and f(y_np1, t_np1) mutable ImplicitStencilRightHandSideDynamicContainer stencil_rhs_; + mutable bool userActionCallback_ = false; + public: ImplicitStepperStandardImpl() = delete; ImplicitStepperStandardImpl(const ImplicitStepperStandardImpl & other) = default; @@ -99,35 +101,58 @@ class ImplicitStepperStandardImpl // *** BDF1 ***// ImplicitStepperStandardImpl(::pressio::ode::BDF1, - ResidualJacobianPolicyType && rjPolicyObj) + ResidualJacobianPolicyPossiblyRefType && rjPolicyObj) : name_(StepScheme::BDF1), recovery_state_{rjPolicyObj.createState()}, stencil_states_{rjPolicyObj.createState()}, - rj_policy_(std::forward(rjPolicyObj)) + rj_policy_(std::forward(rjPolicyObj)) {} // *** BDF2 ***// ImplicitStepperStandardImpl(::pressio::ode::BDF2, - ResidualJacobianPolicyType && rjPolicyObj) + ResidualJacobianPolicyPossiblyRefType && rjPolicyObj) : name_(StepScheme::BDF2), recovery_state_{rjPolicyObj.createState()}, stencil_states_{rjPolicyObj.createState(), rjPolicyObj.createState()}, - rj_policy_(std::forward(rjPolicyObj)) + rj_policy_(std::forward(rjPolicyObj)) {} // *** CN ***// ImplicitStepperStandardImpl(::pressio::ode::CrankNicolson, - ResidualJacobianPolicyType && rjPolicyObj) + ResidualJacobianPolicyPossiblyRefType && rjPolicyObj) : name_(StepScheme::CrankNicolson), recovery_state_{rjPolicyObj.createState()}, stencil_states_{rjPolicyObj.createState()}, - rj_policy_(std::forward(rjPolicyObj)), + rj_policy_(std::forward(rjPolicyObj)), stencil_rhs_{rj_policy_.get().createResidual(), rj_policy_.get().createResidual()} {} public: + + template + void operator()(StateType & odeState, + const ::pressio::ode::StepStartAt & stepStartVal, + ::pressio::ode::StepCount stepNumber, + const ::pressio::ode::StepSize & stepSize, + UserDefinedActionOnStencilStates action, + SolverType & solver, + SolverArgs && ...argsForSolver) + { + + if (name_ != ::pressio::ode::StepScheme::BDF2){ + throw std::runtime_error("User-defined action on the stencil states currently only allowed for BDF2"); + } + + PRESSIOLOG_DEBUG("implicit stepper: do step, user-defined action on stencil states"); + PRESSIOLOG_WARN("implicit stepper: overload accepting action on stencil states does not yet support strong guarantee"); + userActionCallback_ = true; + doStepImpl(::pressio::ode::BDF2(), action, odeState, + stepStartVal.get(), stepSize.get(), stepNumber.get(), + solver, std::forward(argsForSolver)...); + } + template void operator()(StateType & odeState, const ::pressio::ode::StepStartAt & stepStartVal, @@ -138,6 +163,8 @@ class ImplicitStepperStandardImpl { PRESSIOLOG_DEBUG("implicit stepper: do step"); + userActionCallback_ = false; + if (name_==::pressio::ode::StepScheme::BDF1){ doStepImpl(::pressio::ode::BDF1(), odeState, stepStartVal.get(), stepSize.get(), @@ -147,6 +174,7 @@ class ImplicitStepperStandardImpl else if (name_==::pressio::ode::StepScheme::BDF2){ doStepImpl(::pressio::ode::BDF2(), + utils::NoOperation(), odeState, stepStartVal.get(), stepSize.get(), stepNumber.get(), solver, std::forward(argsForSolver)...); @@ -172,11 +200,29 @@ class ImplicitStepperStandardImpl jacobian_type* Jo) const #endif { - rj_policy_.get()(name_, odeState, stencil_states_, stencil_rhs_, - ::pressio::ode::StepEndAt(t_np1_), - ::pressio::ode::StepCount(step_number_), - ::pressio::ode::StepSize(dt_), - R, Jo); + StepEndAt endAt(t_np1_); + StepCount count(step_number_); + StepSize stepsz(dt_); + + if constexpr(mpl::is_detected< + policy_has_call_overload_for_userdefined_action_on_stencil_states_t, + std::remove_reference_t + >::value) + { + if (userActionCallback_){ + rj_policy_.get()(StencilStatesPotentiallyOverwrittenByUser(), + name_, odeState, stencil_states_, stencil_rhs_, + endAt, count, stepsz, R, Jo); + } + else{ + rj_policy_.get()(name_, odeState, stencil_states_, stencil_rhs_, + endAt, count, stepsz, R, Jo); + } + } + else{ + rj_policy_.get()(name_, odeState, stencil_states_, stencil_rhs_, + endAt, count, stepsz, R, Jo); + } } private: @@ -189,6 +235,7 @@ class ImplicitStepperStandardImpl solver_type & solver, SolverArgs&& ...argsForSolver) { + PRESSIOLOG_DEBUG("implicit BDF1 stepper"); /* - we are at step = stepNumber @@ -225,8 +272,9 @@ class ImplicitStepperStandardImpl } } - template + template void doStepImpl(::pressio::ode::BDF2, + UserDefinedActionOnStencilStates action, state_type & odeState, const IndVarType & currentTime, const IndVarType & dt, @@ -234,6 +282,7 @@ class ImplicitStepperStandardImpl solver_type & solver, SolverArgs&& ...argsForSolver) { + PRESSIOLOG_DEBUG("implicit BDF2 stepper"); dt_ = dt; t_np1_ = currentTime + dt; @@ -246,6 +295,7 @@ class ImplicitStepperStandardImpl */ if (stepNumber == ::pressio::ode::first_step_value){ + PRESSIOLOG_DEBUG("implicit BDF2 stepper: beginning/initial step is via BDF1"); /* from t_0 to t_1 and have: odeState = the initial condition (y0) @@ -255,6 +305,7 @@ class ImplicitStepperStandardImpl ::pressio::ops::deep_copy(odeState_n, odeState); } else{ + PRESSIOLOG_DEBUG("implicit BDF2 stepper: actual BDF2 step"); /* for step == 2, we are going from t_1 to t_2 and: odeState = the state at t1 @@ -268,6 +319,7 @@ class ImplicitStepperStandardImpl ::pressio::ops::deep_copy(odeState_n, odeState); } + action(stencil_states_); try{ solver.solve(*this, odeState, std::forward(argsForSolver)...); } diff --git a/include/pressio/ode/ode_enum_and_tags.hpp b/include/pressio/ode/ode_enum_and_tags.hpp index 431ad870f..05498b3f0 100644 --- a/include/pressio/ode/ode_enum_and_tags.hpp +++ b/include/pressio/ode/ode_enum_and_tags.hpp @@ -96,6 +96,8 @@ class nMinusTwo{}; class nMinusThree{}; class nMinusFour{}; +struct StencilStatesPotentiallyOverwrittenByUser{}; + }}//end namespace pressio::ode #endif // ODE_ODE_ENUM_AND_TAGS_HPP_ diff --git a/include/pressio/rom/galerkin_unsteady_implicit.hpp b/include/pressio/rom/galerkin_unsteady_implicit.hpp index a13acc7ed..e5005af73 100644 --- a/include/pressio/rom/galerkin_unsteady_implicit.hpp +++ b/include/pressio/rom/galerkin_unsteady_implicit.hpp @@ -9,6 +9,8 @@ #include "impl/galerkin_unsteady_system_masked_rhs_and_jacobian.hpp" #include "impl/galerkin_unsteady_system_fully_discrete_fom.hpp" #include "impl/galerkin_unsteady_system_hypred_fully_discrete_fom.hpp" +#include "impl/mixed_fom_rom_unsteady_problem.hpp" +#include "impl/galerkin_unsteady_default_problem_mixed_fom.hpp" namespace pressio{ namespace rom{ namespace galerkin{ @@ -235,5 +237,53 @@ auto create_unsteady_implicit_problem(const TrialSubspaceType & trialSpace, TotalNumberOfDesiredStates>(std::move(galSystem)); } +// ------------------------------------------------------------- +// mixed fom/rom +// ------------------------------------------------------------- +namespace experimental{ + +// because this is the mixed case FOM/ROM, we need to check that the FomSystem +// meets the API needed for ROM but also that needed for doing ode stepping directly on it +template +#ifdef PRESSIO_ENABLE_CXX20 +requires PossiblyAffineRealValuedTrialColumnSubspace +&& RealValuedSemiDiscreteFomWithJacobianAction +&& std::same_as +&& ::pressio::ode::RealValuedOdeSystemFusingRhsAndJacobian +#endif +auto create_unsteady_implicit_problem_mixed_fom(::pressio::ode::StepScheme schemeName, + const TrialSubspaceType & trialSpace, + const FomSystemType & fomSystem) +{ + +#if !defined PRESSIO_ENABLE_CXX20 + static_assert(PossiblyAffineTrialColumnSubspace::value); + static_assert(RealValuedSemiDiscreteFomWithJacobianAction< + FomSystemType, typename TrialSubspaceType::basis_matrix_type>::value); + static_assert(::pressio::ode::RealValuedOdeSystemFusingRhsAndJacobian::value); +#endif + + if ( schemeName != ::pressio::ode::StepScheme::BDF1 + && schemeName != ::pressio::ode::StepScheme::BDF2) + { + throw std::runtime_error("galerkin mixed fom/rom currently accepting BDF1 or BDF2"); + } + + using ind_var_type = typename FomSystemType::time_type; + using reduced_state_type = typename TrialSubspaceType::reduced_state_type; + using default_types = ImplicitGalerkinDefaultReducedOperatorsTraits; + using reduced_residual_type = typename default_types::reduced_residual_type; + using reduced_jacobian_type = typename default_types::reduced_jacobian_type; + + using galerkin_system = impl::GalerkinDefaultOdeSystemRhsAndJacobian< + ind_var_type, reduced_state_type, reduced_residual_type, + reduced_jacobian_type, TrialSubspaceType, FomSystemType>; + + using return_type = impl::GalerkinUnsteadyDefaultProblemRomFom< + ind_var_type, FomSystemType, TrialSubspaceType, galerkin_system, impl::MixedFomRomStepper>; + return return_type(schemeName, trialSpace, fomSystem); +} +}//end namespace experimental + }}} // end pressio::rom::galerkin #endif // ROM_GALERKIN_UNSTEADY_IMPLICIT_HPP_ diff --git a/include/pressio/rom/impl/galerkin_unsteady_default_problem_mixed_fom.hpp b/include/pressio/rom/impl/galerkin_unsteady_default_problem_mixed_fom.hpp new file mode 100644 index 000000000..9bac0c3c2 --- /dev/null +++ b/include/pressio/rom/impl/galerkin_unsteady_default_problem_mixed_fom.hpp @@ -0,0 +1,86 @@ + +#ifndef ROM_GALERKIN_UNSTEADY_DEFAULT_PROBLEM_MIXED_FOM_HPP_ +#define ROM_GALERKIN_UNSTEADY_DEFAULT_PROBLEM_MIXED_FOM_HPP_ + +#include "mixed_fom_rom_unsteady_problem.hpp" + +namespace pressio{ namespace rom{ namespace impl{ + +template < + class IndVarType, + class FomSystemType, + class TrialSubspaceType, + class GalerkinSystemType, + template class MixedFomRomStepper + > +class GalerkinUnsteadyDefaultProblemRomFom +{ + +public: + using independent_variable_type = IndVarType; + using fom_state_type = typename FomSystemType::state_type; + using rom_state_type = typename GalerkinSystemType::state_type; + using rom_residual_type = typename GalerkinSystemType::rhs_type; + using rom_jacobian_type = typename GalerkinSystemType::jacobian_type; + + using fom_stepper_type = decltype(ode::create_implicit_stepper(std::declval(), + std::declval())); + using rom_stepper_type = decltype(ode::create_implicit_stepper(std::declval(), + std::declval())); + + using mixed_stepper_t = MixedFomRomStepper< + FomSystemType, fom_stepper_type, TrialSubspaceType, rom_stepper_type>; + + GalerkinUnsteadyDefaultProblemRomFom(ode::StepScheme odeSchemeName, + const TrialSubspaceType & trialSubspace, + const FomSystemType & fomSystem) + : fomStepper_(ode::create_implicit_stepper(odeSchemeName, fomSystem)) + , trialSubspace_(trialSubspace) + , romStepper_(ode::create_implicit_stepper(odeSchemeName, GalerkinSystemType(trialSubspace, fomSystem))) + , mixed_(odeSchemeName, fomSystem, trialSubspace, fomStepper_, romStepper_) + { + assert(odeSchemeName == ode::StepScheme::BDF1 || + odeSchemeName == ode::StepScheme::BDF2); + } + + template + mpl::enable_if_t< std::is_same_v || std::is_same_v > + operator()(Tag tag, + StateType & fomOrRomState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + static_assert(std::is_same_v || + std::is_same_v); + mixed_(tag, fomOrRomState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + + template + mpl::enable_if_t< std::is_same_v || + std::is_same_v > + operator()(Tag tag, + fom_state_type & fomState, + rom_state_type & romState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + mixed_(tag, fomState, romState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + +private: + fom_stepper_type fomStepper_; + std::reference_wrapper trialSubspace_; + rom_stepper_type romStepper_; + mixed_stepper_t mixed_; +}; + +}}} // end pressio::rom::impl +#endif // ROM_IMPL_LSPG_UNSTEADY_PROBLEM_HPP_ diff --git a/include/pressio/rom/impl/lspg_unsteady_problem_mixed_fom.hpp b/include/pressio/rom/impl/lspg_unsteady_problem_mixed_fom.hpp new file mode 100644 index 000000000..23534a7f1 --- /dev/null +++ b/include/pressio/rom/impl/lspg_unsteady_problem_mixed_fom.hpp @@ -0,0 +1,87 @@ + +#ifndef ROM_IMPL_LSPG_UNSTEADY_PROBLEM_FOMROM_HPP_ +#define ROM_IMPL_LSPG_UNSTEADY_PROBLEM_FOMROM_HPP_ + +namespace pressio{ namespace rom{ namespace impl{ + +template < + class IndepVarType, + class FomSystemType, + class TrialSubspaceType, + class ResJacPolicyType, + template class MixedFomRomStepper + > +class LspgUnsteadyProblemRomFom +{ + +public: + using independent_variable_type = IndepVarType; + using fom_state_type = typename FomSystemType::state_type; + using rom_state_type = typename TrialSubspaceType::reduced_state_type; + using fom_stepper_type = decltype(ode::create_implicit_stepper(ode::StepScheme::BDF1, + std::declval())); + using rom_stepper_type = decltype(ode::create_implicit_stepper(ode::StepScheme::BDF1, + std::declval())); + + using mixed_stepper_t = MixedFomRomStepper< + FomSystemType, fom_stepper_type, TrialSubspaceType, rom_stepper_type>; + + template + LspgUnsteadyProblemRomFom(::pressio::ode::StepScheme odeSchemeName, + const TrialSubspaceType & trialSubspace, + const FomSystemType & fomSystem, + Args && ... args) + : fomStepper_(ode::create_implicit_stepper(odeSchemeName, fomSystem)) + , trialSubspace_(trialSubspace) + , fomStatesManager_(create_lspg_fom_states_manager(odeSchemeName, trialSubspace)) + , romStepperPolicy_(trialSubspace, fomSystem, fomStatesManager_, std::forward(args)...) + , romStepper_(ode::create_implicit_stepper(odeSchemeName, romStepperPolicy_)) + , mixed_(odeSchemeName, fomSystem, trialSubspace, fomStepper_, romStepper_) + { + assert(odeSchemeName == ode::StepScheme::BDF1 || + odeSchemeName == ode::StepScheme::BDF2); + } + + template + mpl::enable_if_t< std::is_same_v || std::is_same_v > + operator()(Tag tag, + StateType & fomOrRomState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + static_assert(std::is_same_v || + std::is_same_v); + mixed_(tag, fomOrRomState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + + template + mpl::enable_if_t< std::is_same_v || + std::is_same_v > + operator()(Tag tag, + fom_state_type & fomState, + rom_state_type & romState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + mixed_(tag, fomState, romState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + +private: + fom_stepper_type fomStepper_; + std::reference_wrapper trialSubspace_; + LspgFomStatesManager fomStatesManager_; + ResJacPolicyType romStepperPolicy_; + rom_stepper_type romStepper_; + mixed_stepper_t mixed_; +}; + +}}} // end pressio::rom::impl +#endif // ROM_IMPL_LSPG_UNSTEADY_PROBLEM_HPP_ diff --git a/include/pressio/rom/impl/lspg_unsteady_rj_policy_default.hpp b/include/pressio/rom/impl/lspg_unsteady_rj_policy_default.hpp index 71a74a9e1..c6edb33f3 100644 --- a/include/pressio/rom/impl/lspg_unsteady_rj_policy_default.hpp +++ b/include/pressio/rom/impl/lspg_unsteady_rj_policy_default.hpp @@ -93,6 +93,30 @@ class LspgUnsteadyResidualJacobianPolicy return fomSystem_.get().createResultOfJacobianActionOn(phi); } + template + void operator()(::pressio::ode::StencilStatesPotentiallyOverwrittenByUser /*tag*/, + ::pressio::ode::StepScheme odeSchemeName, + const state_type & predictedReducedState, + const StencilStatesContainerType & reducedStatesStencilManager, + StencilRhsContainerType & fomRhsStencilManger, + const ::pressio::ode::StepEndAt & rhsEvaluationTime, + ::pressio::ode::StepCount step, + const ::pressio::ode::StepSize & dt, + residual_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jo) const +#else + jacobian_type * Jo) const +#endif + { + + std::cout << "!!!! ******* NEW COOL POLICY ******* \n"; + + (*this)(false, /*communicate that it is NOT safe to rely on the stored history */ + odeSchemeName, predictedReducedState, reducedStatesStencilManager, + fomRhsStencilManger, rhsEvaluationTime, step, dt, R, Jo); + } + template void operator()(::pressio::ode::StepScheme odeSchemeName, const state_type & predictedReducedState, @@ -109,23 +133,49 @@ class LspgUnsteadyResidualJacobianPolicy #endif { + (*this)(true, /*communicate that it is safe to rely on the stored history */ + odeSchemeName, predictedReducedState, reducedStatesStencilManager, + fomRhsStencilManger, rhsEvaluationTime, step, dt, R, Jo); + } + +private: + template + void operator()(const bool isSafeToRelyOnSavedHistory, + ::pressio::ode::StepScheme odeSchemeName, + const state_type & predictedReducedState, + const StencilStatesContainerType & reducedStatesStencilManager, + StencilRhsContainerType & fomRhsStencilManger, + const ::pressio::ode::StepEndAt & rhsEvaluationTime, + ::pressio::ode::StepCount step, + const ::pressio::ode::StepSize & dt, + residual_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jo) const +#else + jacobian_type * Jo) const +#endif + { + if (odeSchemeName == ::pressio::ode::StepScheme::BDF1){ (*this).template compute_impl_bdf - (predictedReducedState, reducedStatesStencilManager, - rhsEvaluationTime.get(), dt.get(), step.get(), R, Jo); + (isSafeToRelyOnSavedHistory, predictedReducedState, + reducedStatesStencilManager, rhsEvaluationTime.get(), + dt.get(), step.get(), R, Jo); } else if (odeSchemeName == ::pressio::ode::StepScheme::BDF2) { if (step.get() == ::pressio::ode::first_step_value){ (*this).template compute_impl_bdf - (predictedReducedState, reducedStatesStencilManager, - rhsEvaluationTime.get(), dt.get(), step.get(), R, Jo); + (isSafeToRelyOnSavedHistory, predictedReducedState, + reducedStatesStencilManager, rhsEvaluationTime.get(), + dt.get(), step.get(), R, Jo); } else{ (*this).template compute_impl_bdf - (predictedReducedState, reducedStatesStencilManager, - rhsEvaluationTime.get(), dt.get(), step.get(), R, Jo); + (isSafeToRelyOnSavedHistory, predictedReducedState, + reducedStatesStencilManager, rhsEvaluationTime.get(), + dt.get(), step.get(), R, Jo); } } @@ -134,14 +184,14 @@ class LspgUnsteadyResidualJacobianPolicy } } -private: template - void compute_impl_bdf(const state_type & predictedReducedState, - const StencilStatesContainerType & reducedStatesStencilManager, - const IndVarType & rhsEvaluationTime, - const IndVarType & dt, - const typename ::pressio::ode::StepCount::value_type & step, - residual_type & R, + void compute_impl_bdf(const bool isSafeToRelyOnSavedHistory, + const state_type & predictedReducedState, + const StencilStatesContainerType & reducedStatesStencilManager, + const IndVarType & rhsEvaluationTime, + const IndVarType & dt, + const typename ::pressio::ode::StepCount::value_type & step, + residual_type & R, #ifdef PRESSIO_ENABLE_CXX17 std::optional & Jo) const #else @@ -164,11 +214,20 @@ class LspgUnsteadyResidualJacobianPolicy The method below does not recompute all previous states, but only recomputes the n-th state and updates/shifts back all the other FOM states stored. */ - if (stepTracker_ != step){ + if (stepTracker_ != step) + { const auto & lspgStateAt_n = reducedStatesStencilManager(::pressio::ode::n()); - fomStatesManager_.get().reconstructAtWithStencilUpdate(lspgStateAt_n, - ::pressio::ode::n()); + if (!isSafeToRelyOnSavedHistory){ + fomStatesManager_.get().reconstructAtWithoutStencilUpdate(lspgStateAt_n, ode::n()); + if constexpr(std::is_same::value){ + const auto & lspgStateAt_nm1 = reducedStatesStencilManager(ode::nMinusOne()); + fomStatesManager_.get().reconstructAtWithoutStencilUpdate(lspgStateAt_nm1, ode::nMinusOne()); + } + } + else{ + fomStatesManager_.get().reconstructAtWithStencilUpdate(lspgStateAt_n, ode::n()); + } stepTracker_ = step; } diff --git a/include/pressio/rom/impl/mixed_fom_rom_unsteady_problem.hpp b/include/pressio/rom/impl/mixed_fom_rom_unsteady_problem.hpp new file mode 100644 index 000000000..884e3c770 --- /dev/null +++ b/include/pressio/rom/impl/mixed_fom_rom_unsteady_problem.hpp @@ -0,0 +1,214 @@ + +#ifndef ROM_MIXED_FOM_ROM_UNSTEADY_PROBLEM_HPP_ +#define ROM_MIXED_FOM_ROM_UNSTEADY_PROBLEM_HPP_ + +namespace pressio{ namespace rom{ namespace impl{ + +template < + class FomSystemType, + class FomStepperType, + class TrialSubspaceType, + class RomStepperType + > +class MixedFomRomStepper +{ + enum class StepKind{ fom, rom, none }; + +public: + static_assert( std::is_same_v< + typename FomStepperType::independent_variable_type, + typename RomStepperType::independent_variable_type>); + using independent_variable_type = typename FomStepperType::independent_variable_type; + using fom_state_type = typename FomStepperType::state_type; + using rom_state_type = typename RomStepperType::state_type; + + MixedFomRomStepper(ode::StepScheme odeSchemeName, + const FomSystemType & fomSystem, + const TrialSubspaceType & trialSubspace, + FomStepperType & fomStepper, + RomStepperType & romStepper) + : odeSchemeName_(odeSchemeName) + , fomStepper_(fomStepper) + , fomAuxStateForTransitionFomToRom_(fomSystem.createState()) + , fomAuxStateForTransitionRomToFom_(fomSystem.createState()) + , fomScratchState_(fomSystem.createState()) + , trialSubspace_(trialSubspace) + , romStepper_(romStepper) + , romAuxStateForTransitionRomToFom_(trialSubspace.createReducedState()) + { + assert(odeSchemeName_ == ode::StepScheme::BDF1 || + odeSchemeName_ == ode::StepScheme::BDF2); + } + + template + void operator()(impl::FomStepTag /*unused*/, + fom_state_type & fomState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + + //preconditions + if (activeFlag_ == StepKind::rom){ + const std::string msg = "You cannot take a FOM step starting from a ROM one. " \ + "You must first transition from ROM to FOM, and then you can execute a regular FOM step"; + throw std::runtime_error(msg); + } + + PRESSIOLOG_DEBUG("FOM is active: doing **FOM** step = ", sCount.get(), "\n"); + activeFlag_ = StepKind::fom; + + if (odeSchemeName_ == ode::StepScheme::BDF2){ + pressio::ops::deep_copy(fomAuxStateForTransitionFomToRom_, fomState); + } + fomStepper_(fomState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + + template + void operator()(impl::RomStepTag /*unused*/, + rom_state_type & romState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + + //preconditions + if (activeFlag_ == StepKind::fom){ + const std::string msg = "You cannot take a ROM step starting from a FOM one. " + "You must first transition from FOM to ROM, and then you can execute a regular ROM step"; + throw std::runtime_error(msg); + } + + PRESSIOLOG_DEBUG("ROM is active: doing **ROM** step = ", sCount.get(), "\n"); + activeFlag_ = StepKind::rom; + + if (odeSchemeName_ == ode::StepScheme::BDF2){ + pressio::ops::deep_copy(romAuxStateForTransitionRomToFom_, romState); + } + romStepper_(romState, sStart, sCount, sSize, + solver, std::forward(argsop)...); + } + + template + void operator()(impl::TransitionToRomAndDoStepTag /*unused*/, + fom_state_type & fomState, + rom_state_type & romState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + + //preconditions + if (activeFlag_ != StepKind::fom){ + throw std::runtime_error("Transitioning from FOM to ROM must be done from a FOM context."); + } + + PRESSIOLOG_DEBUG("Trasitioning FOM->ROM, and doing **ROM** step = ", sCount.get(), "\n"); + activeFlag_ = StepKind::rom; + + const auto & phi = trialSubspace_.get().basisOfTranslatedSpace(); + const auto & shift = trialSubspace_.get().translationVector(); + + // 1. project the FOM state to compute the rom state to start from + // romState = phi^T (fomState - shift) + pressio::ops::update(fomScratchState_, 0, fomState, 1, shift, -1); + pressio::ops::product(::pressio::transpose(), 1., phi, fomScratchState_, 0., romState); + + // 2. take the ROM step + if (odeSchemeName_ == ode::StepScheme::BDF1){ + // things are easy, I don't need to overwrite any history since BDF1 only depends on current state + romStepper_(romState, sStart, sCount, sSize, solver, std::forward(argsop)...); + } + else{ + assert(odeSchemeName_ == ode::StepScheme::BDF2); + + // I have to save the state for transitioning that might be used later + pressio::ops::deep_copy(romAuxStateForTransitionRomToFom_, romState); + + // I have to modify the ROM state stored in the ode stencils at n-1 by doing + auto FomToRomTransition = [&](auto & odeStencilStates){ + auto romStateTmp = pressio::ops::clone(romState); + pressio::ops::update(fomScratchState_, 0, fomAuxStateForTransitionFomToRom_, 1, shift, -1); + pressio::ops::product(::pressio::transpose(), 1., phi, fomScratchState_, 0., romStateTmp); + + auto & y_nm1 = odeStencilStates(ode::nMinusOne()); + pressio::ops::deep_copy(y_nm1, romStateTmp); + }; + + // call the stepper + romStepper_(romState, sStart, sCount, sSize, FomToRomTransition, + solver, std::forward(argsop)...); + } + } + + template + void operator()(impl::TransitionToFomAndDoStepTag /*unused*/, + fom_state_type & fomState, + rom_state_type & romState, + pressio::ode::StepStartAt sStart, + pressio::ode::StepCount sCount, + pressio::ode::StepSize sSize, + SolverType & solver, + ArgsOp && ...argsop) + { + + //preconditions + if (activeFlag_ != StepKind::rom){ + throw std::runtime_error("Transitioning from ROM to FOM must be done from a ROM context."); + } + + PRESSIOLOG_DEBUG("Trasitioning ROM->FOM, and doing **FOM** step = ", sCount.get(), "\n"); + activeFlag_ = StepKind::fom; + + // 1. reconstruct the fom state from the current rom state + trialSubspace_.get().mapFromReducedState(romState, fomState); + + // 2. take the FOM step + if (odeSchemeName_ == ode::StepScheme::BDF1){ + // things are easy, I don't need to overwrite any history since BDF1 only depends on current state + fomStepper_(fomState, sStart, sCount, sSize, solver, std::forward(argsop)...); + } + else{ + assert(odeSchemeName_ == ode::StepScheme::BDF2); + + // I have to save the state for transitioning that might be used later + pressio::ops::deep_copy(fomAuxStateForTransitionFomToRom_, fomState); + + // I have to modify the state stored at n-1 using the projection of the FOM + auto RomToFomTransition = [&](auto & odeStencilStates){ + trialSubspace_.get().mapFromReducedState( romAuxStateForTransitionRomToFom_, fomScratchState_); + auto & y_nm1 = odeStencilStates(ode::nMinusOne()); + pressio::ops::deep_copy(y_nm1, fomScratchState_); + }; + + // call the stepper + fomStepper_(fomState, sStart, sCount, sSize, RomToFomTransition, + solver, std::forward(argsop)...); + } + } + +private: + StepKind activeFlag_ = StepKind::none; + ode::StepScheme odeSchemeName_; + + // members for fom + std::reference_wrapper fomStepper_; + fom_state_type fomAuxStateForTransitionFomToRom_; + fom_state_type fomAuxStateForTransitionRomToFom_; + fom_state_type fomScratchState_; + + // members for rom + std::reference_wrapper trialSubspace_; + std::reference_wrapper romStepper_; + rom_state_type romAuxStateForTransitionRomToFom_; +}; + +}}} // end pressio::rom::impl +#endif // ROM_IMPL_LSPG_UNSTEADY_PROBLEM_HPP_ diff --git a/include/pressio/rom/lspg_unsteady.hpp b/include/pressio/rom/lspg_unsteady.hpp index ddb1471cf..954a5d026 100644 --- a/include/pressio/rom/lspg_unsteady.hpp +++ b/include/pressio/rom/lspg_unsteady.hpp @@ -10,6 +10,8 @@ #include "./impl/lspg_unsteady_mask_decorator.hpp" #include "./impl/lspg_unsteady_scaling_decorator.hpp" #include "./impl/lspg_unsteady_problem.hpp" +#include "./impl/mixed_fom_rom_unsteady_problem.hpp" +#include "./impl/lspg_unsteady_problem_mixed_fom.hpp" namespace pressio{ namespace rom{ namespace lspg{ @@ -281,5 +283,51 @@ auto create_unsteady_problem(const TrialSubspaceType & trialSpace, /*(6)*/ return return_type(trialSpace, fomSystem); } + +// ------------------------------------------------------------- +// mixed fom/rom +// ------------------------------------------------------------- +namespace experimental{ + +// because this is the mixed case FOM/ROM, we need to check that the FomSystem +// meets the API needed for ROM but also that needed for doing ode stepping directly on it +template +#ifdef PRESSIO_ENABLE_CXX20 +requires PossiblyAffineRealValuedTrialColumnSubspace +&& RealValuedSemiDiscreteFomWithJacobianAction +&& std::same_as +&& ::pressio::ode::RealValuedOdeSystemFusingRhsAndJacobian +#endif +auto create_unsteady_problem_mixed_fom(::pressio::ode::StepScheme schemeName, + const TrialSubspaceType & trialSpace, + const FomSystemType & fomSystem) +{ + +#if !defined PRESSIO_ENABLE_CXX20 + static_assert(PossiblyAffineTrialColumnSubspace::value); + static_assert(RealValuedSemiDiscreteFomWithJacobianAction< + FomSystemType, typename TrialSubspaceType::basis_matrix_type>::value); + static_assert(::pressio::ode::RealValuedOdeSystemFusingRhsAndJacobian::value); +#endif + + impl::valid_scheme_for_lspg_else_throw(schemeName); + + using ind_var_type = typename FomSystemType::time_type; + using reduced_state_type = typename TrialSubspaceType::reduced_state_type; + using lspg_residual_type = typename FomSystemType::rhs_type; + using lspg_jacobian_type = + decltype(fomSystem.createResultOfJacobianActionOn(trialSpace.basisOfTranslatedSpace())); + + using rom_rj_policy_type = impl::LspgUnsteadyResidualJacobianPolicy< + ind_var_type, reduced_state_type, + lspg_residual_type, lspg_jacobian_type, + TrialSubspaceType, FomSystemType>; + + using return_type = impl::LspgUnsteadyProblemRomFom< + ind_var_type, FomSystemType, TrialSubspaceType, rom_rj_policy_type, impl::MixedFomRomStepper>; + return return_type(schemeName, trialSpace, fomSystem); +} +}//end namespace experimental + }}} // end pressio::rom::lspg #endif // ROM_LSPG_UNSTEADY_HPP_ diff --git a/include/pressio/rom/rom_tags.hpp b/include/pressio/rom/rom_tags.hpp new file mode 100644 index 000000000..cb0c944d7 --- /dev/null +++ b/include/pressio/rom/rom_tags.hpp @@ -0,0 +1,20 @@ + +#ifndef ROM_TAGS_HPP_ +#define ROM_TAGS_HPP_ + +namespace pressio{ namespace rom{ + +namespace impl{ +struct FomStepTag{}; +struct RomStepTag{}; +struct TransitionToRomAndDoStepTag{}; +struct TransitionToFomAndDoStepTag{}; +} + +constexpr impl::FomStepTag FomStep{}; +constexpr impl::RomStepTag RomStep{}; +constexpr impl::TransitionToRomAndDoStepTag TransitionToRomAndDoStep{}; +constexpr impl::TransitionToFomAndDoStepTag TransitionToFomAndDoStep{}; + +}} // end pressio::rom +#endif diff --git a/include/pressio/rom_galerkin_unsteady.hpp b/include/pressio/rom_galerkin_unsteady.hpp index d2e605802..982806183 100644 --- a/include/pressio/rom_galerkin_unsteady.hpp +++ b/include/pressio/rom_galerkin_unsteady.hpp @@ -59,6 +59,7 @@ #include "./ode.hpp" #include "rom_concepts.hpp" +#include "rom/rom_tags.hpp" #include "rom/reduced_operators_traits.hpp" #include "rom/galerkin_unsteady_explicit.hpp" #include "rom/galerkin_unsteady_implicit.hpp" diff --git a/include/pressio/rom_lspg_unsteady.hpp b/include/pressio/rom_lspg_unsteady.hpp index 74c04303b..74be6f0f2 100644 --- a/include/pressio/rom_lspg_unsteady.hpp +++ b/include/pressio/rom_lspg_unsteady.hpp @@ -59,6 +59,7 @@ #include "./ode.hpp" #include "rom_concepts.hpp" +#include "rom/rom_tags.hpp" #include "rom/reduced_operators_traits.hpp" #if defined PRESSIO_ENABLE_TPL_TRILINOS #include "./rom/rom_lspg_unsteady_hypred_updater_trilinos.hpp" diff --git a/tests/functional_small/rom/CMakeLists.txt b/tests/functional_small/rom/CMakeLists.txt index 7da03f941..269c58c99 100644 --- a/tests/functional_small/rom/CMakeLists.txt +++ b/tests/functional_small/rom/CMakeLists.txt @@ -69,4 +69,18 @@ if(PRESSIO_ENABLE_TPL_EIGEN) add_serial_utest(${TESTING_LEVEL}_rom_lspg_unsteady ${SOURCES_LSPG_UNSTEADY}) add_serial_utest(${TESTING_LEVEL}_rom_linear linear_rom.cc) + + set(SOURCES_MIXED_FOM_LSPG_UNSTEADY + ${CMAKE_CURRENT_SOURCE_DIR}/lspg_unsteady_mixed_fom/main1_bdf1.cc + ${CMAKE_CURRENT_SOURCE_DIR}/lspg_unsteady_mixed_fom/main1_bdf2.cc + ${CMAKE_CURRENT_SOURCE_DIR}/lspg_unsteady_mixed_fom/main2_bdf1.cc + ${CMAKE_CURRENT_SOURCE_DIR}/lspg_unsteady_mixed_fom/main2_bdf2.cc + ${CMAKE_CURRENT_SOURCE_DIR}/lspg_unsteady_mixed_fom/main3_bdf2.cc) + add_serial_utest(${TESTING_LEVEL}_rom_lspg_mixed_fom_unsteady ${SOURCES_MIXED_FOM_LSPG_UNSTEADY}) + + set(SOURCES_MIXED_FOM_GALERKIN_UNSTEADY + ${CMAKE_CURRENT_SOURCE_DIR}/galerkin_unsteady_mixed_fom/main1_bdf1.cc + ${CMAKE_CURRENT_SOURCE_DIR}/galerkin_unsteady_mixed_fom/main2_bdf1.cc) + add_serial_utest(${TESTING_LEVEL}_rom_galerkin_mixed_fom_unsteady ${SOURCES_MIXED_FOM_GALERKIN_UNSTEADY}) + endif() diff --git a/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.cc b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.cc new file mode 100644 index 000000000..225c37d58 --- /dev/null +++ b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.cc @@ -0,0 +1,271 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; +namespace galex = pressio::rom::galerkin::experimental; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF1; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type timeIn, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + rhs(yIn, timeIn, R); + } + + void rhs(const state_type & yIn, + independent_variable_type timeIn, + rhs_type & r) const + { + std::cout << yIn << std::endl; + pressio::ops::deep_copy(r, yIn); + for (int i=0; i + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_m); goldR3.setConstant(-56.); + r_t goldR4(_m); goldR4.setConstant(-57.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_n); goldR1 << -224., -448., -672.; + r_t goldR2(_n); goldR2 << -319., -639., -959.; + r_t goldR5(_n); goldR5 << -46688., -93376., -140064.; + r_t goldR6(_n); goldR6 << -46783., -93567., -140351.; + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(galex::create_unsteady_implicit_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(galex::create_unsteady_implicit_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(2.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + ASSERT_DOUBLE_EQ(startTime, 0.); + mixedProblem_(prom::RomStep, romState_, startAt, stepNumber, dt, romNonLinSolver_); + } + + else if (step == 2){ + ASSERT_DOUBLE_EQ(startTime, 0.+dtIn); + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + else if (step == 3){ + ASSERT_DOUBLE_EQ(startTime, 2*dtIn); + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_galerkin_unsteady_implicit, test_bdf1_rom_fom_rom) +{ + /* + stepID 1 2 3 + o -------- o -------- o -------- o + rom fom rom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 1; + const int numRomSteps = 2; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 26.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 210.; goldRomState[1] = 418.; goldRomState[2] = 626.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ) << computedRomState; + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.pdf b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.pdf new file mode 100644 index 000000000..87d5941e1 Binary files /dev/null and b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main1_bdf1.pdf differ diff --git a/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.cc b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.cc new file mode 100644 index 000000000..9617fee97 --- /dev/null +++ b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.cc @@ -0,0 +1,273 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; +namespace galex = pressio::rom::galerkin::experimental; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF1; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type timeIn, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + rhs(yIn, timeIn, R); + } + + void rhs(const state_type & yIn, + independent_variable_type timeIn, + rhs_type & r) const + { + std::cout << yIn << std::endl; + pressio::ops::deep_copy(r, yIn); + for (int i=0; i + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-24.); + r_t goldR2(_m); goldR2.setConstant(-25.); + r_t goldR5(_m); goldR5.setConstant(-2724.); + r_t goldR6(_m); goldR6.setConstant(-2725.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_n); goldR3 << -21568., -43136., -64704.; + r_t goldR4(_n); goldR4 << -21663., -43327., -64991.; + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(galex::create_unsteady_implicit_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(galex::create_unsteady_implicit_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(2.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + ASSERT_DOUBLE_EQ(startTime, 0.); + mixedProblem_(prom::FomStep, fomState_, startAt, stepNumber, dt, fomNonLinSolver_); + } + + else if (step == 2){ + ASSERT_DOUBLE_EQ(startTime, 0.+dtIn); + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + + else if (step == 3){ + ASSERT_DOUBLE_EQ(startTime, 2*dtIn); + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_galerkin_unsteady_implicit, test_bdf1_fom_rom_fom) +{ + /* + stepID 1 2 3 + o -------- o -------- o -------- o + fom rom fom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 2; + const int numRomSteps = 1; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 1358.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 98.; goldRomState[1] = 194.; goldRomState[2] = 290.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ) << computedRomState; + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.pdf b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.pdf new file mode 100644 index 000000000..2fa37b57c Binary files /dev/null and b/tests/functional_small/rom/galerkin_unsteady_mixed_fom/main2_bdf1.pdf differ diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.cc b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.cc new file mode 100644 index 000000000..2df4c57cf --- /dev/null +++ b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.cc @@ -0,0 +1,270 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF1; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + R.setConstant(1.); + } + + void rhs(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R) const + { + R.setConstant(1.); + } + + template + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_m); goldR3.setConstant(-2.); + r_t goldR4(_m); goldR4.setConstant(-1.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-2.); + r_t goldR2(_m); goldR2.setConstant(4.); + r_t goldR5(_m); goldR5.setConstant(-2.); + r_t goldR6(_m); goldR6.setConstant(4.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(2.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + ASSERT_DOUBLE_EQ(startTime, 0.); + mixedProblem_(prom::RomStep, romState_, startAt, stepNumber, dt, romNonLinSolver_); + } + + else if (step == 2){ + ASSERT_DOUBLE_EQ(startTime, 0.+dtIn); + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + else if (step == 3){ + ASSERT_DOUBLE_EQ(startTime, 2*dtIn); + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_lspg_unsteady, test_bdf1_rom_fom_rom) +{ + /* + stepID 1 2 3 + + o -------- o -------- o -------- o + rom fom rom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 1; + const int numRomSteps = 2; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 26.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 210.; goldRomState[1] = 418.; goldRomState[2] = 626.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ) << computedRomState; + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.pdf b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.pdf new file mode 100644 index 000000000..f68b260aa Binary files /dev/null and b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf1.pdf differ diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.cc b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.cc new file mode 100644 index 000000000..8ade32e58 --- /dev/null +++ b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.cc @@ -0,0 +1,268 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF2; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + R.setConstant(1.); + } + + void rhs(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R) const + { + R.setConstant(1.); + } + + template + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_m); goldR3.setConstant(-16./3.); + r_t goldR4(_m); goldR4.setConstant(-13./3.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-2.); + r_t goldR2(_m); goldR2.setConstant(4.); + r_t goldR5(_m); goldR5.setConstant(-76.); + r_t goldR6(_m); goldR6.setConstant(-70.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(2.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + ASSERT_DOUBLE_EQ(startTime, 0.); + mixedProblem_(prom::RomStep, romState_, startAt, stepNumber, dt, romNonLinSolver_); + } + + else if (step == 2){ + ASSERT_DOUBLE_EQ(startTime, 0.+dtIn); + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + + else if (step == 3){ + ASSERT_DOUBLE_EQ(startTime, 2*dtIn); + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_lspg_unsteady, test_bdf2_rom_fom_rom) +{ + /* + stepID 1 2 3 + o -------- o -------- o -------- o + rom fom rom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 1; + const int numRomSteps = 2; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 26.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 210.; goldRomState[1] = 418.; goldRomState[2] = 626.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ) << computedRomState; + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.pdf b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.pdf new file mode 100644 index 000000000..8dc70edbe Binary files /dev/null and b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main1_bdf2.pdf differ diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.cc b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.cc new file mode 100644 index 000000000..50eae9658 --- /dev/null +++ b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.cc @@ -0,0 +1,272 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF1; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + R.setConstant(1.); + } + + void rhs(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R) const + { + R.setConstant(1.); + } + + template + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-2.); + r_t goldR2(_m); goldR2.setConstant(-1.); + r_t goldR5(_m); goldR5.setConstant(-2.); + r_t goldR6(_m); goldR6.setConstant(-1.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_m); goldR3.setConstant(-2.); + r_t goldR4(_m); goldR4.setConstant(4.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(1.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + if (step == 1){ ASSERT_DOUBLE_EQ(startTime, 0.); } + else if (step == 2){ ASSERT_DOUBLE_EQ(startTime, dtIn); } + else if (step == 3){ ASSERT_DOUBLE_EQ(startTime, 2*dtIn); } + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + mixedProblem_(prom::FomStep, fomState_, startAt, stepNumber, dt, fomNonLinSolver_); + } + + else if (step == 2){ + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + + else if (step == 3){ + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_lspg_unsteady, test_bdf1_fom_rom_fom) +{ + /* + stepID 1 2 3 + + o -------- o -------- o -------- o + fom rom fom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 2; + const int numRomSteps = 1; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 1358.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 98.; goldRomState[1] = 194.; goldRomState[2] = 290.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ); + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.pdf b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.pdf new file mode 100644 index 000000000..f4f29eba3 Binary files /dev/null and b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf1.pdf differ diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.cc b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.cc new file mode 100644 index 000000000..663c2d22e --- /dev/null +++ b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.cc @@ -0,0 +1,270 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF2; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + R.setConstant(1.); + } + + void rhs(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R) const + { + R.setConstant(1.); + } + + template + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-2.); + r_t goldR2(_m); goldR2.setConstant(-1.); + r_t goldR5(_m); goldR5.setConstant(-16./3.); + r_t goldR6(_m); goldR6.setConstant(-13./3.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR5) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR3(_m); goldR3.setConstant(-76.); + r_t goldR4(_m); goldR4.setConstant(-70.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR3) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(1.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + if (step == 1){ ASSERT_DOUBLE_EQ(startTime, 0.); } + else if (step == 2){ ASSERT_DOUBLE_EQ(startTime, dtIn); } + else if (step == 3){ ASSERT_DOUBLE_EQ(startTime, 2*dtIn); } + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step == 1){ + mixedProblem_(prom::FomStep, fomState_, startAt, stepNumber, dt, fomNonLinSolver_); + } + + else if (step == 2){ + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + + else if (step == 3){ + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + auto fomState() const{ return fomState_; } + auto romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_lspg_unsteady, test_bdf2_fom_rom_fom) +{ + /* + stepID 1 2 3 + o -------- o -------- o -------- o + fom rom fom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 2; + const int numRomSteps = 1; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + Eigen::VectorXd goldFomState(_m); + pressio::ops::fill(goldFomState, 1358.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + Eigen::VectorXd goldRomState(_n); + goldRomState[0] = 98.; goldRomState[1] = 194.; goldRomState[2] = 290.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ); + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.pdf b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.pdf new file mode 100644 index 000000000..7fabcc3bd Binary files /dev/null and b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main2_bdf2.pdf differ diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.cc b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.cc new file mode 100644 index 000000000..92a695c37 --- /dev/null +++ b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.cc @@ -0,0 +1,283 @@ + +#include +#include "pressio/type_traits.hpp" +#include "pressio/rom.hpp" + +namespace +{ + +namespace pode = pressio::ode; +namespace prom = pressio::rom; + +constexpr int _m = 8; +constexpr int _n = 3; +constexpr pode::StepScheme odeScheme = pode::StepScheme::BDF2; + +using vec_t = Eigen::VectorXd; +using phi_t = Eigen::Matrix; + +void write_vec_cout(const std::string & s, const Eigen::VectorXd & v){ + std::cout << s << " "; + for (int i=0; i; + + state_type createState() const{ + state_type s(_m); + s.setConstant(0.); + return s; + } + + rhs_type createRhs() const{ + rhs_type R(_m); + R.setConstant(0.); + return R; + } + + jacobian_type createJacobian() const{ + jacobian_type JJ(_m,_m); + return JJ; + }; + + template + OperandType createResultOfJacobianActionOn(const OperandType & B) const{ + OperandType A(_m, B.cols()); + A.setConstant(0.); + return A; + } + + void rhsAndJacobian(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R, +#ifdef PRESSIO_ENABLE_CXX17 + std::optional Jin) const +#else + jacobian_type* Jin) const +#endif + { + R.setConstant(1.); + } + + void rhs(const state_type & yIn, + independent_variable_type /*unused*/, + rhs_type & R) const + { + R.setConstant(1.); + } + + template + void applyJacobian(const state_type & state, + const OperandType & B, + time_type time, + OperandType & A) const + {} +}; + +struct MyFakeNonLinSolverForFOM{ + int count_ = 0; + + template + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR1(_m); goldR1.setConstant(-2.); + r_t goldR2(_m); goldR2.setConstant(-1.); + r_t goldR3(_m); goldR3.setConstant(-2.); + r_t goldR4(_m); goldR4.setConstant(-1.); + r_t goldR9(_m); goldR9.setConstant(-16./3.); + r_t goldR10(_m); goldR10.setConstant(-13./3.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR1) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR3) ); } + else if (count_ == 3){ ASSERT_TRUE( R.isApprox(goldR9) ); } + for (int i=0; i + void solve(const SystemType & system, StateType & state) + { + count_++; + + using r_t = typename SystemType::residual_type; + r_t goldR5(_m); goldR5.setConstant(-76.); + r_t goldR6(_m); goldR6.setConstant(-70.); + r_t goldR7(_m); goldR7.setConstant(-16/3.); + r_t goldR8(_m); goldR8.setConstant(2./3.); + + auto R = system.createResidual(); + auto J = system.createJacobian(); + + // mimic solve step 1 + system.residualAndJacobian(state, R, &J); + write_vec_cout("R = ", R); std::cout << "\n"; + if (count_ == 1){ ASSERT_TRUE( R.isApprox(goldR5) ); } + else if (count_ == 2){ ASSERT_TRUE( R.isApprox(goldR7) ); } + for (int i=0; i(std::declval(), + std::declval(), + false)); + using mixed_problem_t = + decltype(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + std::declval(), + std::declval())); + + Subdomain(const vec_t & shift, const phi_t & phiIn) + : fomObj_(), fomState_(_m), romState_(_n), + romSubspace_(prom::create_trial_column_subspace(phiIn, shift, false)), + mixedProblem_(prom::lspg::experimental::create_unsteady_problem_mixed_fom(odeScheme, + romSubspace_, + fomObj_)), + fomNonLinSolver_(), + romNonLinSolver_() + { + fomState_.setConstant(10.); + romState_.setConstant(1.); + } + + void doStep(const double startTime, const int step, const double dtIn) + { + const pode::StepStartAt startAt(startTime); + const pode::StepCount stepNumber(step); + const pode::StepSize dt(dtIn); + std::cout << "\n***** DOING STEP " << step << " *****\n"; + std::cout << "-----------------------------\n"; + + if (step == 1){ ASSERT_DOUBLE_EQ(startTime, 0.); } + else if (step == 2){ ASSERT_DOUBLE_EQ(startTime, dtIn); } + else if (step == 3){ ASSERT_DOUBLE_EQ(startTime, 2*dtIn); } + else if (step == 4){ ASSERT_DOUBLE_EQ(startTime, 3*dtIn); } + else if (step == 5){ ASSERT_DOUBLE_EQ(startTime, 4*dtIn); } + + write_vec_cout("before step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("before step, romState = ", romState_); std::cout << '\n'; + + if (step <= 2){ + mixedProblem_(prom::FomStep, fomState_, startAt, stepNumber, dt, fomNonLinSolver_); + } + else if (step == 3){ + mixedProblem_(prom::TransitionToRomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, romNonLinSolver_); + } + else if (step == 4){ + mixedProblem_(prom::RomStep, romState_, startAt, stepNumber, dt, romNonLinSolver_); + } + else if (step == 5){ + mixedProblem_(prom::TransitionToFomAndDoStep, fomState_, romState_, startAt, + stepNumber, dt, fomNonLinSolver_); + } + + write_vec_cout("after step, fomState = ", fomState_); std::cout << '\n'; + write_vec_cout("after step, romState = ", romState_); std::cout << '\n'; + } + + int fomSolverCount() const { return fomNonLinSolver_.count_; } + int romSolverCount() const { return romNonLinSolver_.count_; } + const auto & fomState() const{ return fomState_; } + const auto & romState() const{ return romState_; } + +private: + fom_state_t getFomState() const{ return fomState_; } + + MyFom fomObj_; + fom_state_t fomState_; + rom_state_t romState_; + trial_subspace_t romSubspace_; + mixed_problem_t mixedProblem_; + MyFakeNonLinSolverForFOM fomNonLinSolver_; + MyFakeNonLinSolverForROM romNonLinSolver_; +}; +} + +TEST(rom_lspg_unsteady, test_bdf2_fom_fom_rom_rom_fom) +{ + /* + stepID 1 2 3 4 5 + + o -------- o -------- o -------- o -------- o -------- o + fom fom rom rom fom + */ + + pressio::log::initialize(pressio::logto::terminal); + pressio::log::setVerbosity({pressio::log::level::debug}); + + vec_t shift(_m); + shift.setConstant(0.); + + phi_t phi(_m, _n); + for (int j=0; j<_n; ++j){ + phi.col(j).setConstant( (double) (j+1)); + } + std::cout << phi << "\n"; + + Subdomain subdom(shift, phi); + + const int numFomSteps = 3; + const int numRomSteps = 2; + const int numSteps = numFomSteps + numRomSteps; + const double dt = 2.; + double time = 0.; + for (int i=1; i<=numSteps; ++i){ + subdom.doStep(time, i, dt); + time += dt; + } + + // verify things + ASSERT_TRUE(subdom.fomSolverCount() == numFomSteps); + ASSERT_TRUE(subdom.romSolverCount() == numRomSteps); + + const auto & computedFomState = subdom.fomState(); + const auto & computedRomState = subdom.romState(); + auto goldFomState = pressio::ops::clone(computedFomState); + pressio::ops::fill(goldFomState, 1594.); + ASSERT_TRUE( goldFomState.isApprox(computedFomState) ); + + auto goldRomState = pressio::ops::clone(computedRomState); + goldRomState[0] = 116.; goldRomState[1] = 228.; goldRomState[2] = 340.; + ASSERT_TRUE( goldRomState.isApprox(computedRomState) ); + + pressio::log::finalize(); +} diff --git a/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.pdf b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.pdf new file mode 100644 index 000000000..24436a8d4 Binary files /dev/null and b/tests/functional_small/rom/lspg_unsteady_mixed_fom/main3_bdf2.pdf differ