Skip to content

Commit

Permalink
Merge branch 'HandleOutputIssue' into 'master'
Browse files Browse the repository at this point in the history
Relax tolerance in fixed output times / fixed timestepping

See merge request ogs/ogs!4981
  • Loading branch information
endJunction committed May 3, 2024
2 parents 9090374 + 9f34288 commit 1d94a3d
Show file tree
Hide file tree
Showing 17 changed files with 462 additions and 14 deletions.
4 changes: 2 additions & 2 deletions NumLib/TimeStepping/Algorithms/FixedTimeStepping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,12 +124,12 @@ void incorporateFixedTimesForOutput(
begin(delta_ts), begin(delta_ts) + interval_number, t_initial);
auto const upper_bound = lower_bound + delta_ts[interval_number];
if (fixed_time_for_output - lower_bound <=
std::numeric_limits<double>::epsilon())
TimeStep::minimalTimeStepSize)
{
continue;
}
if (upper_bound - fixed_time_for_output <=
std::numeric_limits<double>::epsilon())
TimeStep::minimalTimeStepSize)
{
continue;
}
Expand Down
7 changes: 0 additions & 7 deletions NumLib/TimeStepping/Algorithms/FixedTimeStepping.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,13 +55,6 @@ class FixedTimeStepping final : public TimeStepAlgorithm
NumLib::TimeStep& ts_previous,
NumLib::TimeStep& ts_current) override;

/// reset the current step size from the previous time
void resetCurrentTimeStep(const double dt, TimeStep& /*ts_previous*/,
TimeStep& /*ts_current*/) override
{
_dt_vector.push_back(dt);
}

private:
/// a vector of time step sizes
std::vector<double> _dt_vector;
Expand Down
3 changes: 3 additions & 0 deletions NumLib/TimeStepping/TimeStep.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,9 @@ class TimeStep final
void setAccepted(bool const accepted) { _is_accepted = accepted; }
bool isAccepted() const { return _is_accepted; }

static constexpr double minimalTimeStepSize =
1000 * std::numeric_limits<double>::epsilon();

private:
/// previous time step
double _previous;
Expand Down
13 changes: 8 additions & 5 deletions ProcessLib/Output/OutputDataSpecification.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@

#include "OutputDataSpecification.h"

#include "NumLib/TimeStepping/TimeStep.h"

namespace ProcessLib
{
OutputDataSpecification::OutputDataSpecification(
Expand Down Expand Up @@ -49,11 +51,12 @@ bool OutputDataSpecification::isOutputStep(int timestep,
{
auto isFixedOutputStep = [this](double const time) -> bool
{
auto const fixed_output_time = std::lower_bound(
cbegin(fixed_output_times), cend(fixed_output_times), time);
return ((fixed_output_time != cend(fixed_output_times)) &&
(std::abs(*fixed_output_time - time) <
std::numeric_limits<double>::epsilon()));
return std::any_of(cbegin(fixed_output_times), cend(fixed_output_times),
[&](auto fixed_output_time)
{
return (std::abs(fixed_output_time - time) <
NumLib::TimeStep::minimalTimeStepSize);
});
};

auto isPairRepeatsEachTimeStepOutput = [this](int timestep) -> bool
Expand Down
12 changes: 12 additions & 0 deletions ProcessLib/SteadyStateDiffusion/Tests.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,18 @@ foreach(mesh_size 1e4 2e4 3e4 4e4 5e4 1e5 1e6)
)
endforeach()

# Test FixedTimeStepping and fixed output times
AddTest(
NAME SteadyStateDiffusion_square_1x1_quad_1e1_FixedTimeStepping_FixedOutputTimes
PATH Elliptic/square_1x1_SteadyStateDiffusion/FixedTimeSteppingFixedOutputTimes
EXECUTABLE ogs
EXECUTABLE_ARGS square_1e1-fixed_timestepping-fixed_output_times.prj -m ../
TESTER vtkdiff
REQUIREMENTS NOT OGS_USE_MPI
DIFF_DATA
GLOB square_1e1_ts_*.vtu pressure pressure 1e-15 1e-15
)

# Quadratic hex element.
AddTest(
NAME SteadyStateDiffusion_cube_1x1x1_1e0_QuadraticHex
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
<?xml version="1.0" encoding="ISO-8859-1"?>
<OpenGeoSysProject>
<mesh>square_1x1_quad_1e1.vtu</mesh>
<geometry>square_1x1.gml</geometry>
<processes>
<process>
<name>SteadyStateDiffusion</name>
<type>STEADY_STATE_DIFFUSION</type>
<integration_order>2</integration_order>
<process_variables>
<process_variable>pressure</process_variable>
</process_variables>
<secondary_variables>
<secondary_variable internal_name="darcy_velocity" output_name="v"/>
</secondary_variables>
</process>
</processes>
<media>
<medium id="0">
<phases/>
<properties>
<property>
<name>diffusion</name>
<type>Constant</type>
<value>1</value>
</property>
<property>
<name>reference_temperature</name>
<type>Constant</type>
<value>293.15</value>
</property>
</properties>
</medium>
</media>
<time_loop>
<processes>
<process ref="SteadyStateDiffusion">
<nonlinear_solver>basic_picard</nonlinear_solver>
<convergence_criterion>
<type>DeltaX</type>
<norm_type>NORM2</norm_type>
<abstol>1.e-6</abstol>
</convergence_criterion>
<time_discretization>
<type>BackwardEuler</type>
</time_discretization>
<time_stepping>
<type>FixedTimeStepping</type>
<t_initial>0</t_initial>
<t_end>1</t_end>
<timesteps>
<pair>
<repeat>100</repeat>
<delta_t>1.e-2</delta_t>
</pair>
</timesteps>
</time_stepping>
</process>
</processes>
<output>
<type>VTK</type>
<prefix>square_1e1</prefix>
<timesteps>
<pair>
<repeat>1</repeat>
<each_steps>1000</each_steps>
</pair>
</timesteps>
<fixed_output_times>.1 .2 .3 .4 .5 .6 .7 .8 .9 1</fixed_output_times>
<variables>
<variable> pressure </variable>
<variable> v </variable>
</variables>
<suffix>_ts_{:0>3timestep}_t_{:time}</suffix>
</output>
</time_loop>
<parameters>
<parameter>
<name>p0</name>
<type>Constant</type>
<value>0</value>
</parameter>
<parameter>
<name>p_Dirichlet_left</name>
<type>Constant</type>
<value>1</value>
</parameter>
<parameter>
<name>p_Dirichlet_right</name>
<type>Constant</type>
<value>-1</value>
</parameter>
</parameters>
<process_variables>
<process_variable>
<name>pressure</name>
<components>1</components>
<order>1</order>
<initial_condition>p0</initial_condition>
<boundary_conditions>
<boundary_condition>
<geometrical_set>square_1x1_geometry</geometrical_set>
<geometry>left</geometry>
<type>Dirichlet</type>
<parameter>p_Dirichlet_left</parameter>
</boundary_condition>
<boundary_condition>
<geometrical_set>square_1x1_geometry</geometrical_set>
<geometry>right</geometry>
<type>Dirichlet</type>
<parameter>p_Dirichlet_right</parameter>
</boundary_condition>
</boundary_conditions>
</process_variable>
</process_variables>
<nonlinear_solvers>
<nonlinear_solver>
<name>basic_picard</name>
<type>Picard</type>
<max_iter>10</max_iter>
<linear_solver>general_linear_solver</linear_solver>
</nonlinear_solver>
</nonlinear_solvers>
<linear_solvers>
<linear_solver>
<name>general_linear_solver</name>
<lis>-i cg -p jacobi -tol 1e-16 -maxiter 10000</lis>
<eigen>
<solver_type>CG</solver_type>
<precon_type>DIAGONAL</precon_type>
<max_iteration_step>10000</max_iteration_step>
<error_tolerance>1e-16</error_tolerance>
</eigen>
<petsc>
<prefix>gw</prefix>
<parameters>-gw_ksp_type cg -gw_pc_type bjacobi -gw_ksp_rtol 1e-16 -gw_ksp_max_it 10000</parameters>
</petsc>
</linear_solver>
</linear_solvers>
</OpenGeoSysProject>
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<VTKFile type="UnstructuredGrid" version="1.0" byte_order="LittleEndian" header_type="UInt64" compressor="vtkZLibDataCompressor">
<UnstructuredGrid>
<FieldData>
<DataArray type="Int8" Name="OGS_VERSION" NumberOfTuples="19" format="appended" RangeMin="45" RangeMax="103" offset="0" />
</FieldData>
<Piece NumberOfPoints="16" NumberOfCells="9" >
<PointData>
<DataArray type="Float64" Name="pressure" format="appended" RangeMin="0" RangeMax="0" offset="80" />
<DataArray type="Float64" Name="v" NumberOfComponents="2" format="appended" RangeMin="0" RangeMax="0" offset="140" />
</PointData>
<CellData>
</CellData>
<Points>
<DataArray type="Float64" Name="Points" NumberOfComponents="3" format="appended" RangeMin="0" RangeMax="1.4142135624" offset="200" />
</Points>
<Cells>
<DataArray type="Int64" Name="connectivity" format="appended" RangeMin="" RangeMax="" offset="344" />
<DataArray type="Int64" Name="offsets" format="appended" RangeMin="" RangeMax="" offset="480" />
<DataArray type="UInt8" Name="types" format="appended" RangeMin="" RangeMax="" offset="568" />
</Cells>
</Piece>
</UnstructuredGrid>
<AppendedData encoding="base64">
_AQAAAAAAAAAAgAAAAAAAABMAAAAAAAAAGwAAAAAAAAA=eF4z0zPVM9Q1NLLUTU81Mk41NkxKBgAp6wSuAQAAAAAAAAAAgAAAAAAAAIAAAAAAAAAADAAAAAAAAAA=eF5jYBhYAAAAgAABAQAAAAAAAAAAgAAAAAAAAAABAAAAAAAADAAAAAAAAAA=eF5jYBjZAAABAAABAQAAAAAAAAAAgAAAAAAAAIABAAAAAAAASQAAAAAAAAA=eF5jYMAO/ENB4Ko9ungEWPwphjgEfMAhjmkejI8uDjMfu/0fcIhjugumDl0cxsfujw84xBHyMBaqOz5gmI8ujspHiAMAt187AQ==AQAAAAAAAAAAgAAAAAAAACABAAAAAAAARQAAAAAAAAA=eF5djDkOwCAAw6AXbenx/98yEC/OYsmyUspcDfdwk1/CQx1+DZs6fuiv8JSnv9Xh+e3q+KF/w0ee/lOH5/dXNwBz+AEPAQAAAAAAAAAAgAAAAAAAAEgAAAAAAAAAIAAAAAAAAAA=eF5jYYAADijNA6UFoLQIlJaA0jJQWgFKq0BpABToALU=AQAAAAAAAAAAgAAAAAAAAAkAAAAAAAAACwAAAAAAAAA=eF7j5IQCAAGeAFI=
</AppendedData>
</VTKFile>
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<VTKFile type="UnstructuredGrid" version="1.0" byte_order="LittleEndian" header_type="UInt64" compressor="vtkZLibDataCompressor">
<UnstructuredGrid>
<FieldData>
<DataArray type="Int8" Name="OGS_VERSION" NumberOfTuples="19" format="appended" RangeMin="45" RangeMax="103" offset="0" />
</FieldData>
<Piece NumberOfPoints="16" NumberOfCells="9" >
<PointData>
<DataArray type="Float64" Name="pressure" format="appended" RangeMin="-1" RangeMax="1" offset="80" />
<DataArray type="Float64" Name="v" NumberOfComponents="2" format="appended" RangeMin="2" RangeMax="2" offset="176" />
</PointData>
<CellData>
</CellData>
<Points>
<DataArray type="Float64" Name="Points" NumberOfComponents="3" format="appended" RangeMin="0" RangeMax="1.4142135624" offset="424" />
</Points>
<Cells>
<DataArray type="Int64" Name="connectivity" format="appended" RangeMin="" RangeMax="" offset="568" />
<DataArray type="Int64" Name="offsets" format="appended" RangeMin="" RangeMax="" offset="704" />
<DataArray type="UInt8" Name="types" format="appended" RangeMin="" RangeMax="" offset="792" />
</Cells>
</Piece>
</UnstructuredGrid>
<AppendedData encoding="base64">
_AQAAAAAAAAAAgAAAAAAAABMAAAAAAAAAGwAAAAAAAAA=eF4z0zPVM9Q1NLLUTU81Mk41NkxKBgAp6wSuAQAAAAAAAAAAgAAAAAAAAIAAAAAAAAAAJwAAAAAAAAA=eF5jYACBD/aJoSBw1T4JQu9ngIjDaLh8Ig75JAL6YfLo+gFhPyZtAQAAAAAAAAAAgAAAAAAAAAABAAAAAAAAmQAAAAAAAAA=eF5jZAADh5Cz8+JE1BptGKB8qdRDTtc318L5q3wiXlRtm72HEcr/+h8E5u/5B6b/20OEJ+z5D+WLOPt2r7ZfAdd/wihx4eubdXD5pWDzVsP1vwdT/XDzvxW1xOyYOBeuX0NYbNe8t/P2wPhX37x0TRTaCZcPgLofZl4G1P1/ofxwNZ0S29tL9/yC8uNmbrjwNWf6HgCRF3l6AQAAAAAAAAAAgAAAAAAAAIABAAAAAAAASQAAAAAAAAA=eF5jYMAO/ENB4Ko9ungEWPwphjgEfMAhjmkejI8uDjMfu/0fcIhjugumDl0cxsfujw84xBHyMBaqOz5gmI8ujspHiAMAt187AQ==AQAAAAAAAAAAgAAAAAAAACABAAAAAAAARQAAAAAAAAA=eF5djDkOwCAAw6AXbenx/98yEC/OYsmyUspcDfdwk1/CQx1+DZs6fuiv8JSnv9Xh+e3q+KF/w0ee/lOH5/dXNwBz+AEPAQAAAAAAAAAAgAAAAAAAAEgAAAAAAAAAIAAAAAAAAAA=eF5jYYAADijNA6UFoLQIlJaA0jJQWgFKq0BpABToALU=AQAAAAAAAAAAgAAAAAAAAAkAAAAAAAAACwAAAAAAAAA=eF7j5IQCAAGeAFI=
</AppendedData>
</VTKFile>
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<VTKFile type="UnstructuredGrid" version="1.0" byte_order="LittleEndian" header_type="UInt64" compressor="vtkZLibDataCompressor">
<UnstructuredGrid>
<FieldData>
<DataArray type="Int8" Name="OGS_VERSION" NumberOfTuples="19" format="appended" RangeMin="45" RangeMax="103" offset="0" />
</FieldData>
<Piece NumberOfPoints="16" NumberOfCells="9" >
<PointData>
<DataArray type="Float64" Name="pressure" format="appended" RangeMin="-1" RangeMax="1" offset="80" />
<DataArray type="Float64" Name="v" NumberOfComponents="2" format="appended" RangeMin="2" RangeMax="2" offset="176" />
</PointData>
<CellData>
</CellData>
<Points>
<DataArray type="Float64" Name="Points" NumberOfComponents="3" format="appended" RangeMin="0" RangeMax="1.4142135624" offset="424" />
</Points>
<Cells>
<DataArray type="Int64" Name="connectivity" format="appended" RangeMin="" RangeMax="" offset="568" />
<DataArray type="Int64" Name="offsets" format="appended" RangeMin="" RangeMax="" offset="704" />
<DataArray type="UInt8" Name="types" format="appended" RangeMin="" RangeMax="" offset="792" />
</Cells>
</Piece>
</UnstructuredGrid>
<AppendedData encoding="base64">
_AQAAAAAAAAAAgAAAAAAAABMAAAAAAAAAGwAAAAAAAAA=eF4z0zPVM9Q1NLLUTU81Mk41NkxKBgAp6wSuAQAAAAAAAAAAgAAAAAAAAIAAAAAAAAAAJwAAAAAAAAA=eF5jYACBD/aJoSBw1T4JQu9ngIjDaLh8Ig75JAL6YfLo+gFhPyZtAQAAAAAAAAAAgAAAAAAAAAABAAAAAAAAmQAAAAAAAAA=eF5jZAADh5Cz8+JE1BptGKB8qdRDTtc318L5q3wiXlRtm72HEcr/+h8E5u/5B6b/20OEJ+z5D+WLOPt2r7ZfAdd/wihx4eubdXD5pWDzVsP1vwdT/XDzvxW1xOyYOBeuX0NYbNe8t/P2wPhX37x0TRTaCZcPgLofZl4G1P1/ofxwNZ0S29tL9/yC8uNmbrjwNWf6HgCRF3l6AQAAAAAAAAAAgAAAAAAAAIABAAAAAAAASQAAAAAAAAA=eF5jYMAO/ENB4Ko9ungEWPwphjgEfMAhjmkejI8uDjMfu/0fcIhjugumDl0cxsfujw84xBHyMBaqOz5gmI8ujspHiAMAt187AQ==AQAAAAAAAAAAgAAAAAAAACABAAAAAAAARQAAAAAAAAA=eF5djDkOwCAAw6AXbenx/98yEC/OYsmyUspcDfdwk1/CQx1+DZs6fuiv8JSnv9Xh+e3q+KF/w0ee/lOH5/dXNwBz+AEPAQAAAAAAAAAAgAAAAAAAAEgAAAAAAAAAIAAAAAAAAAA=eF5jYYAADijNA6UFoLQIlJaA0jJQWgFKq0BpABToALU=AQAAAAAAAAAAgAAAAAAAAAkAAAAAAAAACwAAAAAAAAA=eF7j5IQCAAGeAFI=
</AppendedData>
</VTKFile>
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<VTKFile type="UnstructuredGrid" version="1.0" byte_order="LittleEndian" header_type="UInt64" compressor="vtkZLibDataCompressor">
<UnstructuredGrid>
<FieldData>
<DataArray type="Int8" Name="OGS_VERSION" NumberOfTuples="19" format="appended" RangeMin="45" RangeMax="103" offset="0" />
</FieldData>
<Piece NumberOfPoints="16" NumberOfCells="9" >
<PointData>
<DataArray type="Float64" Name="pressure" format="appended" RangeMin="-1" RangeMax="1" offset="80" />
<DataArray type="Float64" Name="v" NumberOfComponents="2" format="appended" RangeMin="2" RangeMax="2" offset="176" />
</PointData>
<CellData>
</CellData>
<Points>
<DataArray type="Float64" Name="Points" NumberOfComponents="3" format="appended" RangeMin="0" RangeMax="1.4142135624" offset="424" />
</Points>
<Cells>
<DataArray type="Int64" Name="connectivity" format="appended" RangeMin="" RangeMax="" offset="568" />
<DataArray type="Int64" Name="offsets" format="appended" RangeMin="" RangeMax="" offset="704" />
<DataArray type="UInt8" Name="types" format="appended" RangeMin="" RangeMax="" offset="792" />
</Cells>
</Piece>
</UnstructuredGrid>
<AppendedData encoding="base64">
_AQAAAAAAAAAAgAAAAAAAABMAAAAAAAAAGwAAAAAAAAA=eF4z0zPVM9Q1NLLUTU81Mk41NkxKBgAp6wSuAQAAAAAAAAAAgAAAAAAAAIAAAAAAAAAAJwAAAAAAAAA=eF5jYACBD/aJoSBw1T4JQu9ngIjDaLh8Ig75JAL6YfLo+gFhPyZtAQAAAAAAAAAAgAAAAAAAAAABAAAAAAAAmQAAAAAAAAA=eF5jZAADh5Cz8+JE1BptGKB8qdRDTtc318L5q3wiXlRtm72HEcr/+h8E5u/5B6b/20OEJ+z5D+WLOPt2r7ZfAdd/wihx4eubdXD5pWDzVsP1vwdT/XDzvxW1xOyYOBeuX0NYbNe8t/P2wPhX37x0TRTaCZcPgLofZl4G1P1/ofxwNZ0S29tL9/yC8uNmbrjwNWf6HgCRF3l6AQAAAAAAAAAAgAAAAAAAAIABAAAAAAAASQAAAAAAAAA=eF5jYMAO/ENB4Ko9ungEWPwphjgEfMAhjmkejI8uDjMfu/0fcIhjugumDl0cxsfujw84xBHyMBaqOz5gmI8ujspHiAMAt187AQ==AQAAAAAAAAAAgAAAAAAAACABAAAAAAAARQAAAAAAAAA=eF5djDkOwCAAw6AXbenx/98yEC/OYsmyUspcDfdwk1/CQx1+DZs6fuiv8JSnv9Xh+e3q+KF/w0ee/lOH5/dXNwBz+AEPAQAAAAAAAAAAgAAAAAAAAEgAAAAAAAAAIAAAAAAAAAA=eF5jYYAADijNA6UFoLQIlJaA0jJQWgFKq0BpABToALU=AQAAAAAAAAAAgAAAAAAAAAkAAAAAAAAACwAAAAAAAAA=eF7j5IQCAAGeAFI=
</AppendedData>
</VTKFile>
Loading

0 comments on commit 1d94a3d

Please sign in to comment.