Skip to content

Commit

Permalink
ESFR Split Formulation (#111)
Browse files Browse the repository at this point in the history
* ESFR Split forms. Contains all unsteady unit and integration tests. Makes use of operators in DG strong. Provides weight-adjusted curvilinear Mass matrices. Includes free-stream preserving metric terms.

* Removed the accidentally pushed mesh file. Will rebase last 4 commits into 1.

* Cleaning up the accidental added line at end of some files and removed #if 0 #endif commented blocks.

* And this file deleted last line.

* Finished removing #if 0 #endif blocks, added some comments and included new numerical fluxes in the numerical_flux_conservation test.

* Apply suggestions from code review

dg.cpp minor edits

* Implemented sum factorization in operators class. All operations can be written as a combination of matrix-vector products and inner products. A unit test verifies by testing the cputime for A*u and also M*u where M is a mass matrix--uses both matrix-vector product and inner product forms. All that is left is to clean up the unit test a bit to fail at wrong orders.

* Apply suggestions from code review

* Apply suggestions from code review

* Apply suggestions from code review

* Update src/parameters/all_parameters.cpp

* Update with all changes requested from pull request. Only missing merge conflict with ode solver base then pull request changes complete.

* Small cleanup changes before I merge upstream master in my branch.

* Made corrections to explicit ode solver with Butcher tableau c values. Updated unsteady tests. Continued to clean up and removed deprecated Burgers Rewienski lines.

* Cleaned up last few comments on pull request wrt Flux reconstruction operators and flags.

* Removed old references to Runge-Kutta order.

* Cleaned up re-used code in operators, and other comments from PR.

* Removed collection tuple from dg. Removed finite element and quadrature collections from DG. Made consistent throughout the code to call operators finite element and quadrature collections from the operators collection tuple.

* Fixed typos in error messages.

* Created initial condition base class with interpolate and projection capabilities for different initial condition functions. This generalizes the initial condition class.

* Turned axuiliary mass matrix into a single rather than array of dim because we use the same mass matrix for each dim direction. This reduces memory consumption.

* Templated initial condition base by nstate and the functions therein.

* Added a strong form Navier-Stokes integration test.

* Made mapping support points arrays instead of vectors. Added flag in dg allocate system for the implicit matrix/vectors to allocate to reduce memory costs.

* Fix minor changes from Pranshul.

* Small update. Switching branch for other work.

* Auxiliary variable correctly computed for NAvier-Stokes equation now. Verified through viscous TGV test strong.

* Fixed small compiling error.

* Fix TGV viscous strong control file

* Strong viscous TGV energy check test confirmed pass.

* Added definitions for projection.

* Changed initial condition base to just initial condition since nothing is derived from it.

* Current status of new operators backup

* Made entropy conserving flux work for all physics types. Will return to my other branch with restructuring operators class for efficiency now.

* Recent version, new operators quarter done.

* For energy tests, only initializes ode solver on first iteration now.

* For Julien to debug his flow solver case. I will revert these changes after so that the test case is mroe reasonable when using ctests.

* Fixed the Burgers' energy inviscid initial condition.

* Fixed stash error

* Apply suggestions from code review

* cleaning up InitialCondition; changed to SetInitialCondition

* removing commented lines from previous commit

* fixing bug that would run two tgv energy check quick tests

* cleaning up src/parameter/ files; fixing comments marked as fixed that were not actually fixed

* minor editorial changes

* correcting all_parameters.cpp from last commit; indentation and doxygen fixes

* indentation clean up in unit tests and euler split tgv

* cleaning up src/testing/ files

* removing unused CurvManifold class declaration in advection_explicit_periodic.h

* changing tabs to spaces in burgers_stability.cpp

* cleaning up ConvectionDiffusionPeriodic class files in src/testing/

* reducing code repetition in CMakeList for flow_variable_tests

* reviewing src/dg, src/numerical_flux, and src/ode_solver/ files; moving all convective num fluxes to convective_numerical_flux.<cpp/hpp>; converting tabs to spaces in convective_numerical_flux.cpp; general clean up in numerical flux directory; indentation fixes

* New operators class completed with passing unit tests. Only unit tests to change atm are sum factorization, metric splitting and weight adjusted inverse. Next step is to deprecate the previous operators class and make respective changes throughout dg, tests etc.

* reviewing src/mesh/grids files

* making repeated constants class members in NonsymmetricCurvedGridManifold

* correcting "set test_type = flow_solver" to "set run_type = flow_simulation" in prm files

* The sum factorization test.

* Changed mapping shape functions class so metric operators less variables pass to construct.

* fixing time refinement study parameter file

* New operators class complete with top-nothc efficiency :)

* adding print statements for operators allocation status

* adding forgotten print statements

* comment fix

* resolving a PR comment

* Implemented new operators class throughout DG/DG strong. All that is left is having it pass the tests. It currently compiles.

* I have DG strong conservative working, now need to tweak split forms and pass all tests.

* Conservative DG works 2D curvilinear. Now need cuvilinear split form to work properly, then will do auxtesting/tgv and finito.

* Got curvilinear stability and weight-adjusted curvilinear working perfectly. Now only needs to pass auxiliary/conv_diff explicit and it's all done!

* 3D TGV works. Now just auxiliary.

* bug fix for writing pvtu files in subdirectory

* setting default value for WALE model constant to that recommended by literature

* Auxiliary and conv diffusion passes.

* Inverse mass on the fly and mass evaluated on the fly in application per cell done. Only doesnt work for curvilinear at the moment. Has flag to use. For curvilinear, do not use inverse on the fly yet. Works perfectly for linear grids.

* 2pt flux Hadamard sum after the Hadamard product now O n^d+1. All is finished.

* Made mass matrix computation more efficient. FINALLY PASSES NACA 0012 OPTIMIZATION I'm so happy!

* compiles. Have not yet tested since the merge.

* Fixed TGV Euler split form test that got stuff deleted during the merge. Also, in mass matrix DG, changed condition of factoring out det of Jac by Cartesian element rather than linear. This is because unstructured linear meshes do NOT have a constant metric Jacobian determinant, only Cartesian meshes do. Will run ctest and clean up documentation now.

* Moved the entropy consevring, entropy stable split, and central numerical fluxes into convective numerical flux.

* Changed tabs to spaces in burgers epxlicit test.

* Added documentation equations to DG strong.

* Modified TGV split test to use initial condition TGV function.

* Fixed Polynomial degree ramping issue.

* Run curvilinear mesh on Narval. Also, made 3D periodic nonsymm curv grid.

* Added energy file declaration from control file. Also increased warping of grid.

* small clean up

* fixing pde_type flag in strong dg

* correcting initial condition setting in split tgv

* Finished with curv TGV work for conference

* 1D_BURGERS_STABILITY_ORDERS_OF_ACCURACY_LONG passing

* 1D_TIME_REFINEMENT_STUDY_ADVECTION_EXPLICIT now passes and behaves as supposed to.

* 1D periodic now CONFIRMED to work with dealii matched faces. Thus, the hardcoded 1D periodic was removed. All tests that are affected by this pass.

* Viscous TGV energy check quick STRONG passing.

* Smoothed out auxiliary test to reach asymptotic convergence in L infinity norm in a reasonable time/grid level.

* Unit test verifying DG Strong Auxiliary equations' right-hand-side for d\in[1,3], for Navier-Stokes equations.

* Fixed CMake files and cleaned up the include header files in unit test.

* Resolved conflicts from merge that caused the tests to fail. Tests are passing now.

* Removed use_strong_form flag in dg.cpp. Instead uses polymorphism to build operators needed for strong or fevalues needed for weak and assembles the residual functions therein. Also, corrected parameter files for advection unsteady weight adjusted curvilinear tests.

* Made a few small minor changes to operators.

* Small bug fix I saw.

* fixing Gaussian bump flow case merge commit; related tests now passing

* adding physics_model to use_aux_equation flag

* Refactoring NumericalFluxConvective

* introducing has_nonzero_diffusion bool in physics

* assigning has_nonzero_diffusion to use_auxiliary_eqn

* bug fix

* Added viscous pseudotime to converge the diffusion with explicit steady state (both weak and strong needed this). Added the max_dt_cell for strong form calculation. Verified the boundary integrals in strong form. Fully verified viscous strong form, with energy tests recovering the exact provable stability bound to machine precision. Added a central viscous flux to achieve the exact provable stability condition.

* Fixed 3D periodic nonsymmetric grid. Setup TGV for curvilinear grid. Fixed bug in weight-adjusted on-the-fly for curvilinear and now passes both 2D and 3D tests. Added condition for sum-factorization tests for cpu orders of convergence.

* improving MPI_VISCOUS_TAYLOR_GREEN_VORTEX_RESTART_FROM_PARAMETER_FILE_CHECK

* Update. Switching branches.

* Added check for convergence in Hadamard product sum-factorized test. The test is still the same but it checks if the computed error was off because it didn't consider enough polynomial points.

* This always passes.

* Speed up TGV run.

* Fixed bug with diffusion implicit convergence times.

* Cleaned up TGV test for curvilinear grid.

* Fix nonsymmetric grid for 2D advection, the 1/5 was too much warping, changed back to 1/10.

* Adding Ismail-Roe split form convective numerical flux; introducing parameter 'two_point_num_flux_type'.

* FlowSolver using set_initial_condition; can be used for curvilinear grids now

* adding safeguard for parameter: number_of_grid_elements_per_dimension

* Fixed projection IC for multi-state.

* The test parameter file for multi-state curvilinear projection.

* renaming "entropy_conserving_flux" to "two_point_flux"

* using pcout in ODE factory

* adding output_high_order_grid parameter

* adding constant_time_step parameter for TGV DNS verification

* minor merge fix

* bug fix in parameters for constant_time_step

* updating ode_solver_type in missed prm files from explicit to runge_kutta; all tests expected to pass are passing

* allowing for negative grid bounds; needed for verifying viscous TGV

* Fixing bug which adds dissipation to Euler

* Test to confirm conservation of entropy

* PR comments re: entropy check test

* Changing physics per PR comments; using isothermal TGV initialization

* Adding comment re: MPI behaviour of dot product.

* Move entropy calculation into physics

* Fixing an accidental change

* Addressing final PR comments

* fixing ctest command for TGV restart tests when MPIMAX is not a power of 2

* setting output_high_order_grid to false by default

* removing commented code in tgv shell script

* Bug fixed for auxiliary rhs test to work with general processors.

* Small fix from last commit.

* Sum-factorized Hadamard product works with general diagonal weights for other tensor directions. This enables the use of general matrices for 2pt fluxes (stiffness operator rather than derivative).

* Setup volume skew-symmetric form for DG solver. Setup surface Hadamard products using sum-factorization type algorithms with corresponding unit tests. Hadamard products handle basis of variable sizes with arbitrary diagonal products.

* Put surface two point flux in dg strong. Uncollocated updated version works perfectly for Burgers' and curvilinear. Exploring why not yet machine precision entropy conservation for Euler TGV uncollocated IR.

* PeriodicTurbulence Adaptive Time Step MPI Bug Fix (#3)

* flipping sign on viscous flux

* reverting sign flip on viscous flux

* renaming mean_specific_energy and trying equivalent pressure gradient method

* unused var fix

* removing misleading compute_dimensional_temperature

* const member initialization for sutherlands law temperatures

* bug fix for adaptive time step; using MPI max

* making temperature_inf an input parameter that must be consistent with the Prandtl number

* removing commented code in header

* doxygen fix

* Added Chandrashekar flux. General uncollocated two-point fluxes works perfectly. Verified with 3D TGV curvilinear FR c+ uncollocated entropy conservation. Found a bug with weight-adjusted curvilinear mass inverse with uncollocated and overintegration. To be fixed in future only overintegration doesn't work as expected with uncollocated curvilinear weight-adjusted.

* Clean up. Giong to merge.

* Deleted commented out debugging code.

* Cleaned up euler/physics_model as per comments. Added in strong DG to interpolate the conservative variables to the face for the numerical flux if conservative to pass the TGV quick tets. In the future, I think that it should be the interpolation of the entropy variables to the face even for conservative DG.

* Added Ranocha entropy conserving, KEP and PEP numerical flux. Added mapping support points extraction that scales on order (grid_degre+1)^dim to alleviate previous bottleneck of computing the mapping support nodes that prevnted total scaling from (p+1)^dim.

* Added test verifying that the global inverse mass matrix and global mass matrix on the fly recover same vector for multi state and any FR scheme fully veryfing the mass matrix application.

* Integrated quantities for periodic turbulence now uses sum-factorization algorithms to reduce round-off error build up and provide scaling speed-up.

* improvements and addressing PR comments

* using constexpr where possible in operators.cpp

* editorial changes

* adding abort condition for aux equation

* Replacing exit(1) by std::abort(), editorial changes to weak_dg.hpp

* correcting abort for non-diffusive problems

* cleaning up added polymorphism to DGBase (functions that are not called in DGBase and only in the derived DGStrong class); 1D, 2D, 3D_AUXILIARY_RHS_TEST are passing

* Unifying the two versions of compute_entropy_variables in Euler physics

* moving allocate_auxiliary_equation() definition to DGBase

* Changing auxiliary explicit timestepping check to NOT-implicit. This will allow ODE solvers such as rrk_explicit to solve diffusive terms.

---------

Co-authored-by: Alexander <alexander@localhost.localdomain>
Co-authored-by: Julien Brillon <43619715+jbrillon@users.noreply.github.com>
Co-authored-by: Carolyn <c.pethrick@gmail.com>
  • Loading branch information
4 people committed Feb 11, 2023
1 parent 9e22e0e commit ee3bdb4
Show file tree
Hide file tree
Showing 177 changed files with 21,932 additions and 6,039 deletions.
2 changes: 1 addition & 1 deletion generate_job_parameters_file_PHiLiP.sh
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# This file quickly generates the job paramters file
# This file quickly generates the job parameters file

filename="my_job_parameters_file.sh"
walltime="2:00:00" # wall time
Expand Down
6 changes: 3 additions & 3 deletions src/deprecated/ode_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -513,7 +513,7 @@ void Implicit_ODESolver<dim,real,MeshType>::allocate_ode_system ()
//std::shared_ptr<ODESolver<dim,real,MeshType>> ODESolverFactory<dim,real,MeshType>::create_ODESolver(Parameters::ODESolverParam::ODESolverEnum ode_solver_type)
//{
// using ODEEnum = Parameters::ODESolverParam::ODESolverEnum;
// if(ode_solver_type == ODEEnum::explicit_solver) return std::make_shared<Explicit_ODESolver<dim,real>>();
// if(ode_solver_type == ODEEnum::runge_kutta_solver) return std::make_shared<Explicit_ODESolver<dim,real>>();
// if(ode_solver_type == ODEEnum::implicit_solver) return std::make_shared<Implicit_ODESolver<dim,real>>();
// else {
// pcout << "Can't create ODE solver since explicit/implicit solver is not clear." << std::endl;
Expand All @@ -525,15 +525,15 @@ std::shared_ptr<ODESolver<dim,real,MeshType>> ODESolverFactory<dim,real,MeshType
{
using ODEEnum = Parameters::ODESolverParam::ODESolverEnum;
ODEEnum ode_solver_type = dg_input->all_parameters->ode_solver_param.ode_solver_type;
if(ode_solver_type == ODEEnum::explicit_solver) return std::make_shared<Explicit_ODESolver<dim,real,MeshType>>(dg_input);
if(ode_solver_type == ODEEnum::runge_kutta_solver) return std::make_shared<Explicit_ODESolver<dim,real,MeshType>>(dg_input);
if(ode_solver_type == ODEEnum::implicit_solver) return std::make_shared<Implicit_ODESolver<dim,real,MeshType>>(dg_input);
else {
dealii::ConditionalOStream pcout(std::cout, dealii::Utilities::MPI::this_mpi_process(MPI_COMM_WORLD)==0);
pcout << "********************************************************************" << std::endl;
pcout << "Can't create ODE solver since explicit/implicit solver is not clear." << std::endl;
pcout << "Solver type specified: " << ode_solver_type << std::endl;
pcout << "Solver type possible: " << std::endl;
pcout << ODEEnum::explicit_solver << std::endl;
pcout << ODEEnum::runge_kutta_solver << std::endl;
pcout << ODEEnum::implicit_solver << std::endl;
pcout << "********************************************************************" << std::endl;
std::abort();
Expand Down
6 changes: 3 additions & 3 deletions src/dg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@ foreach(dim RANGE 1 3)
string(CONCAT PostprocessingLib Postprocessing_${dim}D)
string(CONCAT NumericalFluxLib NumericalFlux_${dim}D)
string(CONCAT PhysicsLib Physics_${dim}D)
## string(CONCAT OperatorsLib Operator_Lib_${dim}D)
string(CONCAT OperatorsLib Operator_Lib_${dim}D)
target_link_libraries(${DiscontinuousGalerkinLib} ${HighOrderGridLib})
target_link_libraries(${DiscontinuousGalerkinLib} ${PostprocessingLib})
target_link_libraries(${DiscontinuousGalerkinLib} ${NumericalFluxLib})
target_link_libraries(${DiscontinuousGalerkinLib} ${PhysicsLib})
## target_link_libraries(${DiscontinuousGalerkinLib} ${OperatorsLib})
target_link_libraries(${DiscontinuousGalerkinLib} ${OperatorsLib})
# Setup target with deal.II
if(NOT DOC_ONLY)
DEAL_II_SETUP_TARGET(${DiscontinuousGalerkinLib})
Expand All @@ -36,6 +36,6 @@ foreach(dim RANGE 1 3)
unset(DiscontinuousGalerkinLib)
unset(NumericalFluxLib)
unset(PhysicsLib)
##unset(OperatorsLib)
unset(OperatorsLib)

endforeach()
1,491 changes: 1,130 additions & 361 deletions src/dg/dg.cpp

Large diffs are not rendered by default.

276 changes: 266 additions & 10 deletions src/dg/dg.h

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions src/dg/residual_sparsity_patterns.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ dealii::SparsityPattern DGBase<dim,real,MeshType>::get_dRdX_sparsity_pattern ()
for (; cell != dof_handler.end(); ++cell, ++metric_cell) {
if (!cell->is_locally_owned()) continue;

const unsigned int n_resi_cell = fe_collection[cell->active_fe_index()].n_dofs_per_cell();
const unsigned int n_resi_cell = this->fe_collection[cell->active_fe_index()].n_dofs_per_cell();
resi_indices.resize(n_resi_cell);
cell->get_dof_indices (resi_indices);

Expand Down Expand Up @@ -173,7 +173,7 @@ dealii::SparsityPattern DGBase<dim,real,MeshType>::get_dRdXs_sparsity_pattern ()
for (; cell != dof_handler.end(); ++cell) {
if (!cell->is_locally_owned()) continue;

const unsigned int n_resi_cell = fe_collection[cell->active_fe_index()].n_dofs_per_cell();
const unsigned int n_resi_cell = this->fe_collection[cell->active_fe_index()].n_dofs_per_cell();
resi_indices.resize(n_resi_cell);
cell->get_dof_indices (resi_indices);

Expand Down
3,201 changes: 2,465 additions & 736 deletions src/dg/strong_dg.cpp

Large diffs are not rendered by default.

272 changes: 268 additions & 4 deletions src/dg/strong_dg.hpp

Large diffs are not rendered by default.

319 changes: 302 additions & 17 deletions src/dg/weak_dg.cpp

Large diffs are not rendered by default.

137 changes: 133 additions & 4 deletions src/dg/weak_dg.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,128 @@ class DGWeak : public DGBaseState<dim, nstate, real, MeshType>

private:

/// Builds the necessary fe values and assembles volume residual.
void assemble_volume_term_and_build_operators(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
const dealii::types::global_dof_index current_cell_index,
const std::vector<dealii::types::global_dof_index> &cell_dofs_indices,
const std::vector<dealii::types::global_dof_index> &metric_dof_indices,
const unsigned int poly_degree,
const unsigned int grid_degree,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis*/,
OPERATOR::local_basis_stiffness<dim,2*dim> &/*flux_basis_stiffness*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper*/,
OPERATOR::mapping_shape_functions<dim,2*dim> &/*mapping_basis*/,
std::array<std::vector<real>,dim> &/*mapping_support_points*/,
dealii::hp::FEValues<dim,dim> &fe_values_collection_volume,
dealii::hp::FEValues<dim,dim> &fe_values_collection_volume_lagrange,
const dealii::FESystem<dim,dim> &current_fe_ref,
dealii::Vector<real> &local_rhs_int_cell,
std::vector<dealii::Tensor<1,dim,real>> &/*local_auxiliary_RHS*/,
const bool /*compute_auxiliary_right_hand_side*/,
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);

/// Builds the necessary fe values and assembles boundary residual.
void assemble_boundary_term_and_build_operators(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
const dealii::types::global_dof_index current_cell_index,
const unsigned int iface,
const unsigned int boundary_id,
const real penalty,
const std::vector<dealii::types::global_dof_index> &cell_dofs_indices,
const std::vector<dealii::types::global_dof_index> &metric_dof_indices,
const unsigned int poly_degree,
const unsigned int grid_degree,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis*/,
OPERATOR::local_basis_stiffness<dim,2*dim> &/*flux_basis_stiffness*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper*/,
OPERATOR::mapping_shape_functions<dim,2*dim> &/*mapping_basis*/,
std::array<std::vector<real>,dim> &/*mapping_support_points*/,
dealii::hp::FEFaceValues<dim,dim> &fe_values_collection_face_int,
const dealii::FESystem<dim,dim> &current_fe_ref,
dealii::Vector<real> &local_rhs_int_cell,
std::vector<dealii::Tensor<1,dim,real>> &/*local_auxiliary_RHS*/,
const bool /*compute_auxiliary_right_hand_side*/,
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);

/// Builds the necessary fe values and assembles face residual.
void assemble_face_term_and_build_operators(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
typename dealii::DoFHandler<dim>::active_cell_iterator neighbor_cell,
const dealii::types::global_dof_index current_cell_index,
const dealii::types::global_dof_index neighbor_cell_index,
const unsigned int iface,
const unsigned int neighbor_iface,
const real penalty,
const std::vector<dealii::types::global_dof_index> &current_dofs_indices,
const std::vector<dealii::types::global_dof_index> &neighbor_dofs_indices,
const std::vector<dealii::types::global_dof_index> &current_metric_dofs_indices,
const std::vector<dealii::types::global_dof_index> &neighbor_metric_dofs_indices,
const unsigned int /*poly_degree_int*/,
const unsigned int /*poly_degree_ext*/,
const unsigned int /*grid_degree_int*/,
const unsigned int /*grid_degree_ext*/,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis_int*/,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis_ext*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis_int*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis_ext*/,
OPERATOR::local_basis_stiffness<dim,2*dim> &/*flux_basis_stiffness*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper_int*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper_ext*/,
OPERATOR::mapping_shape_functions<dim,2*dim> &/*mapping_basis*/,
std::array<std::vector<real>,dim> &/*mapping_support_points*/,
dealii::hp::FEFaceValues<dim,dim> &fe_values_collection_face_int,
dealii::hp::FEFaceValues<dim,dim> &fe_values_collection_face_ext,
dealii::Vector<real> &current_cell_rhs,
dealii::Vector<real> &neighbor_cell_rhs,
std::vector<dealii::Tensor<1,dim,real>> &/*current_cell_rhs_aux*/,
dealii::LinearAlgebra::distributed::Vector<double> &rhs,
std::array<dealii::LinearAlgebra::distributed::Vector<double>,dim> &/*rhs_aux*/,
const bool /*compute_auxiliary_right_hand_side*/,
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);

/// Builds the necessary fe values and assembles subface residual.
void assemble_subface_term_and_build_operators(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
typename dealii::DoFHandler<dim>::active_cell_iterator neighbor_cell,
const dealii::types::global_dof_index current_cell_index,
const dealii::types::global_dof_index neighbor_cell_index,
const unsigned int iface,
const unsigned int neighbor_iface,
const unsigned int neighbor_i_subface,
const real penalty,
const std::vector<dealii::types::global_dof_index> &current_dofs_indices,
const std::vector<dealii::types::global_dof_index> &neighbor_dofs_indices,
const std::vector<dealii::types::global_dof_index> &current_metric_dofs_indices,
const std::vector<dealii::types::global_dof_index> &neighbor_metric_dofs_indices,
const unsigned int /*poly_degree_int*/,
const unsigned int /*poly_degree_ext*/,
const unsigned int /*grid_degree_int*/,
const unsigned int /*grid_degree_ext*/,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis_int*/,
OPERATOR::basis_functions<dim,2*dim> &/*soln_basis_ext*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis_int*/,
OPERATOR::basis_functions<dim,2*dim> &/*flux_basis_ext*/,
OPERATOR::local_basis_stiffness<dim,2*dim> &/*flux_basis_stiffness*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper_int*/,
OPERATOR::metric_operators<real,dim,2*dim> &/*metric_oper_ext*/,
OPERATOR::mapping_shape_functions<dim,2*dim> &/*mapping_basis*/,
std::array<std::vector<real>,dim> &/*mapping_support_points*/,
dealii::hp::FEFaceValues<dim,dim> &fe_values_collection_face_int,
dealii::hp::FESubfaceValues<dim,dim> &fe_values_collection_subface,
dealii::Vector<real> &current_cell_rhs,
dealii::Vector<real> &neighbor_cell_rhs,
std::vector<dealii::Tensor<1,dim,real>> &/*current_cell_rhs_aux*/,
dealii::LinearAlgebra::distributed::Vector<double> &rhs,
std::array<dealii::LinearAlgebra::distributed::Vector<double>,dim> &/*rhs_aux*/,
const bool /*compute_auxiliary_right_hand_side*/,
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);

/// Assembles the auxiliary equations' residuals and solves for the auxiliary variables.
void assemble_auxiliary_residual ();

/// Main function responsible for evaluating the integral over the cell volume and the specified derivatives.
/** This function templates the solution and metric coefficients in order to possible AD the residual.
*/
Expand Down Expand Up @@ -243,7 +365,6 @@ class DGWeak : public DGBaseState<dim, nstate, real, MeshType>
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);

private:

/// Evaluate the integral over the cell volume.
/** Compute the right-hand side only. */
void assemble_volume_residual(
Expand Down Expand Up @@ -305,15 +426,18 @@ class DGWeak : public DGBaseState<dim, nstate, real, MeshType>
dealii::Vector<real> &local_rhs_ext_cell,
const bool compute_dRdW, const bool compute_dRdX, const bool compute_d2R);


/// Evaluate the integral over the cell volume
void assemble_volume_term_explicit(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
const dealii::types::global_dof_index current_cell_index,
const dealii::FEValues<dim,dim> &fe_values_volume,
const std::vector<dealii::types::global_dof_index> &current_dofs_indices,
const std::vector<dealii::types::global_dof_index> &metric_dof_indices,
const unsigned int poly_degree,
const unsigned int grid_degree,
dealii::Vector<real> &current_cell_rhs,
const dealii::FEValues<dim,dim> &fe_values_lagrange);

/// Evaluate the integral over the cell edges that are on domain boundaries
void assemble_boundary_term_explicit(
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
Expand All @@ -323,22 +447,27 @@ class DGWeak : public DGBaseState<dim, nstate, real, MeshType>
const real penalty,
const std::vector<dealii::types::global_dof_index> &current_dofs_indices,
dealii::Vector<real> &current_cell_rhs);

/// Evaluate the integral over the internal cell edges
void assemble_face_term_explicit(
const unsigned int /*iface*/,
const unsigned int /*neighbor_iface*/,
typename dealii::DoFHandler<dim>::active_cell_iterator cell,
const dealii::types::global_dof_index current_cell_index,
const dealii::types::global_dof_index neighbor_cell_index,
const unsigned int poly_degree,
const unsigned int grid_degree,
const dealii::FEFaceValuesBase<dim,dim> &fe_values_face_int,
const dealii::FEFaceValuesBase<dim,dim> &fe_values_face_ext,
const real penalty,
const std::vector<dealii::types::global_dof_index> &current_dofs_indices,
const std::vector<dealii::types::global_dof_index> &neighbor_dofs_indices,
const std::vector<dealii::types::global_dof_index> &metric_dof_indices_int,
const std::vector<dealii::types::global_dof_index> &metric_dof_indices_ext,
dealii::Vector<real> &current_cell_rhs,
dealii::Vector<real> &neighbor_cell_rhs);

using DGBase<dim,real,MeshType>::mpi_communicator; ///< MPI communicator
using DGBase<dim,real,MeshType>::pcout; ///< Parallel std::cout that only outputs on mpi_rank==0

}; // end of DGWeak class

} // PHiLiP namespace
Expand Down
10 changes: 5 additions & 5 deletions src/flow_solver/flow_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <vector>
#include <sstream>
#include "reduced_order/pod_basis_offline.h"
#include "physics/initial_conditions/set_initial_condition.h"
#include "mesh/mesh_adaptation.h"

namespace PHiLiP {
Expand Down Expand Up @@ -49,9 +50,6 @@ FlowSolver<dim, nstate>::FlowSolver(

flow_solver_case->display_flow_solver_setup(dg);

dealii::LinearAlgebra::distributed::Vector<double> solution_no_ghost;
solution_no_ghost.reinit(dg->locally_owned_dofs, this->mpi_communicator);

if(flow_solver_param.restart_computation_from_file == true) {
if(dim == 1) {
pcout << "Error: restart_computation_from_file is not possible for 1D. Set to false." << std::endl;
Expand All @@ -71,15 +69,17 @@ FlowSolver<dim, nstate>::FlowSolver(

// Note: Future development with hp-capabilities, see section "Note on usage with DoFHandler with hp-capabilities"
// ----- Ref: https://www.dealii.org/current/doxygen/deal.II/classparallel_1_1distributed_1_1SolutionTransfer.html
dealii::LinearAlgebra::distributed::Vector<double> solution_no_ghost;
solution_no_ghost.reinit(dg->locally_owned_dofs, this->mpi_communicator);
dealii::parallel::distributed::SolutionTransfer<dim, dealii::LinearAlgebra::distributed::Vector<double>, dealii::DoFHandler<dim>> solution_transfer(dg->dof_handler);
solution_transfer.deserialize(solution_no_ghost);
dg->solution = solution_no_ghost; //< assignment
#endif
} else {
// Initialize solution from initial_condition_function
pcout << "Initializing solution with initial condition function... " << std::flush;
dealii::VectorTools::interpolate(dg->dof_handler, *(flow_solver_case->initial_condition_function), solution_no_ghost);
SetInitialCondition<dim,nstate,double>::set_initial_condition(flow_solver_case->initial_condition_function, dg, &all_param);
}
dg->solution = solution_no_ghost; //< assignment
dg->solution.update_ghost_values();
pcout << "done." << std::endl;
ode_solver->allocate_ode_system();
Expand Down
1 change: 0 additions & 1 deletion src/flow_solver/flow_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@

// for FlowSolver class:
#include "flow_solver_cases/flow_solver_case_base.h"
#include "physics/initial_conditions/initial_condition.h"
#include "physics/physics.h"
#include "parameters/all_parameters.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#define __1D_BURGERS_REWIENSKI_SNAPSHOT__

// for FlowSolver class:
#include "physics/initial_conditions/initial_condition.h"
#include "physics/initial_conditions/initial_condition_function.h"
#include "dg/dg.h"
#include "physics/physics.h"
#include "parameters/all_parameters.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#define __1D_BURGERS_VISCOUS_SNAPSHOT__

// for FlowSolver class:
#include "physics/initial_conditions/initial_condition.h"
#include "physics/initial_conditions/initial_condition_function.h"
#include "dg/dg.h"
#include "physics/physics.h"
#include "parameters/all_parameters.h"
Expand Down
Loading

0 comments on commit ee3bdb4

Please sign in to comment.