Compare commits

...

4 Commits

Author SHA1 Message Date
8af7eee267
Multiple cahnges :D 2021-10-25 18:45:54 +02:00
362ec38dd2
Clang-format 2021-10-25 15:45:29 +02:00
07b1f194a6
Added benchmark of old commit 2021-10-25 15:35:01 +02:00
7eac132a5f
Added EMPXX and EMPYY 2021-10-25 15:34:34 +02:00
31 changed files with 953 additions and 1065 deletions

View File

@ -1,12 +1,15 @@
AccessModifierOffset: -2
AlignAfterOpenBracket: DontAlign
---
Language: Cpp
# BasedOnStyle: Google
AccessModifierOffset: -1
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: false
AlignConsecutiveDeclarations: false
AlignEscapedNewlines: Left
AlignOperands: true
AlignTrailingComments: false
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortBlocksOnASingleLine: true
AlignOperands: true
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: true
AllowShortBlocksOnASingleLine: false
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: All
AllowShortIfStatementsOnASingleLine: true
@ -14,85 +17,92 @@ AllowShortLoopsOnASingleLine: true
AlwaysBreakAfterDefinitionReturnType: None
AlwaysBreakAfterReturnType: None
AlwaysBreakBeforeMultilineStrings: true
AlwaysBreakTemplateDeclarations: false
BinPackArguments: false
BinPackParameters: false
BraceWrapping:
AfterClass: true
AlwaysBreakTemplateDeclarations: true
BinPackArguments: true
BinPackParameters: true
BraceWrapping:
AfterClass: false
AfterControlStatement: false
AfterEnum: false
AfterFunction: true
AfterNamespace: false
AfterEnum: false
AfterFunction: false
AfterNamespace: false
AfterObjCDeclaration: false
AfterStruct: true
AfterUnion: false
BeforeCatch: false
BeforeElse: false
IndentBraces: false
SplitEmptyFunction: false
SplitEmptyNamespace: true
AfterStruct: false
AfterUnion: false
BeforeCatch: false
BeforeElse: false
IndentBraces: false
SplitEmptyFunction: true
SplitEmptyRecord: true
BreakAfterJavaFieldAnnotations: true
BreakBeforeBinaryOperators: NonAssignment
BreakBeforeBraces: Custom
BreakBeforeInheritanceComma: true
SplitEmptyNamespace: true
BreakBeforeBinaryOperators: None
BreakBeforeBraces: Attach
BreakBeforeInheritanceComma: false
BreakBeforeTernaryOperators: true
BreakConstructorInitializers: BeforeColon
BreakConstructorInitializersBeforeComma: false
BreakConstructorInitializers: BeforeColon
BreakAfterJavaFieldAnnotations: false
BreakStringLiterals: true
ColumnLimit: 0
CommentPragmas: '^ IWYU pragma:'
ColumnLimit: 80
CommentPragmas: '^ IWYU pragma:'
CompactNamespaces: false
ConstructorInitializerAllOnOneLineOrOnePerLine: false
ConstructorInitializerIndentWidth: 2
ContinuationIndentWidth: 2
Cpp11BracedListStyle: false
DerivePointerAlignment: false
DisableFormat: false
ExperimentalAutoDetectBinPacking: true
ConstructorInitializerAllOnOneLineOrOnePerLine: true
ConstructorInitializerIndentWidth: 4
ContinuationIndentWidth: 4
Cpp11BracedListStyle: true
DerivePointerAlignment: true
DisableFormat: false
ExperimentalAutoDetectBinPacking: false
FixNamespaceComments: true
ForEachMacros:
- foreach
- Q_FOREACH
- BOOST_FOREACH
IncludeCategories:
- Priority: 2
Regex: ^"(llvm|llvm-c|clang|clang-c)/
- Priority: 3
Regex: ^(<|"(gtest|gmock|isl|json)/)
- Priority: 1
Regex: .*
IncludeIsMainRegex: (Test)?$
IndentCaseLabels: false
IndentWidth: 2
IndentWrappedFunctionNames: true
ForEachMacros:
- foreach
- Q_FOREACH
- BOOST_FOREACH
IncludeCategories:
- Regex: '^<.*\.h>'
Priority: 1
- Regex: '^<.*'
Priority: 2
- Regex: '.*'
Priority: 3
IncludeIsMainRegex: '([-_](test|unittest))?$'
IndentCaseLabels: true
IndentWidth: 4
IndentWrappedFunctionNames: false
JavaScriptQuotes: Leave
JavaScriptWrapImports: true
KeepEmptyLinesAtTheStartOfBlocks: true
Language: Cpp
KeepEmptyLinesAtTheStartOfBlocks: false
MacroBlockBegin: ''
MacroBlockEnd: ''
MaxEmptyLinesToKeep: 2
NamespaceIndentation: Inner
ObjCBlockIndentWidth: 7
ObjCSpaceAfterProperty: true
MacroBlockEnd: ''
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCBlockIndentWidth: 4
ObjCSpaceAfterProperty: false
ObjCSpaceBeforeProtocolList: false
PointerAlignment: Right
ReflowComments: true
SortIncludes: false
SortUsingDeclarations: false
PenaltyBreakAssignment: 2
PenaltyBreakBeforeFirstCallParameter: 1
PenaltyBreakComment: 300
PenaltyBreakFirstLessLess: 120
PenaltyBreakString: 1000
PenaltyExcessCharacter: 1000000
PenaltyReturnTypeOnItsOwnLine: 200
PointerAlignment: Left
ReflowComments: true
SortIncludes: true
SortUsingDeclarations: true
SpaceAfterCStyleCast: false
SpaceAfterTemplateKeyword: false
SpaceAfterTemplateKeyword: true
SpaceBeforeAssignmentOperators: true
SpaceBeforeParens: ControlStatements
SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 0
SpacesInAngles: false
SpacesInCStyleCastParentheses: false
SpacesBeforeTrailingComments: 2
SpacesInAngles: false
SpacesInContainerLiterals: true
SpacesInCStyleCastParentheses: false
SpacesInParentheses: false
SpacesInSquareBrackets: false
Standard: Cpp11
TabWidth: 8
UseTab: Never
Standard: Auto
TabWidth: 8
UseTab: Never
...

36
benchmark.81f4796.fourier Normal file
View File

@ -0,0 +1,36 @@
<?xml version="1.0" encoding="UTF-8"?>
<Catch name="benchmark">
<Group name="benchmark">
<TestCase name="Euler - Baseline" tags="[benchmark]" filename="/home/watt/jholder/Integratoren/benchmark/bench.cpp" line="12">
<BenchmarkResults name="Euler without force" samples="100" resamples="100000" iterations="179" clockResolution="19.6142" estimatedDuration="1.9511e+06">
<!--All values in nano seconds-->
<mean value="109.097" lowerBound="108.49" upperBound="109.829" ci="0.95"/>
<standardDeviation value="3.40566" lowerBound="2.90384" upperBound="3.93169" ci="0.95"/>
<outliers variance="0.267429" lowMild="0" lowSevere="0" highMild="15" highSevere="3"/>
</BenchmarkResults>
<BenchmarkResults name="Heun without force" samples="100" resamples="100000" iterations="128" clockResolution="19.6142" estimatedDuration="1.9584e+06">
<!--All values in nano seconds-->
<mean value="152.946" lowerBound="152.282" upperBound="153.785" ci="0.95"/>
<standardDeviation value="3.77535" lowerBound="3.05802" upperBound="4.579" ci="0.95"/>
<outliers variance="0.180743" lowMild="0" lowSevere="0" highMild="8" highSevere="3"/>
</BenchmarkResults>
<BenchmarkResults name="Exact without force" samples="100" resamples="100000" iterations="166" clockResolution="19.6142" estimatedDuration="1.9588e+06">
<!--All values in nano seconds-->
<mean value="118.824" lowerBound="117.587" upperBound="121.925" ci="0.95"/>
<standardDeviation value="9.21278" lowerBound="2.96214" upperBound="17.3383" ci="0.95"/>
<outliers variance="0.696897" lowMild="0" lowSevere="0" highMild="0" highSevere="7"/>
</BenchmarkResults>
<BenchmarkResults name="BDAS without force" samples="100" resamples="100000" iterations="114" clockResolution="19.6142" estimatedDuration="1.9722e+06">
<!--All values in nano seconds-->
<mean value="173.079" lowerBound="171.528" upperBound="176.479" ci="0.95"/>
<standardDeviation value="11.1774" lowerBound="6.53959" upperBound="22.4088" ci="0.95"/>
<outliers variance="0.605598" lowMild="0" lowSevere="0" highMild="0" highSevere="1"/>
</BenchmarkResults>
<OverallResult success="true"/>
</TestCase>
<OverallResults successes="0" failures="0" expectedFailures="0"/>
<OverallResultsCases successes="1" failures="0" expectedFailures="0"/>
</Group>
<OverallResults successes="0" failures="0" expectedFailures="0"/>
<OverallResultsCases successes="1" failures="0" expectedFailures="0"/>
</Catch>

View File

@ -6,27 +6,25 @@
#define CATCH_CONFIG_ENABLE_BENCHMARKING
#include <catch2/catch.hpp>
#include "Rod2d.hpp"
#include "Integratoren2d_forceless.h"
#include "Rod2d.hpp"
TEST_CASE("Euler - Baseline", "[benchmark]")
{
TEST_CASE("Euler - Baseline", "[benchmark]") {
Rod2d rod(1.0);
Simulation sim(0.01, Catch::rngSeed());
BENCHMARK("Euler without force")
{
Integratoren2d_forceless::Set1_Euler(rod, sim);
};
BENCHMARK("Heun without force")
{
Integratoren2d_forceless::Set2_Heun(rod, sim);
};
BENCHMARK("Exact without force")
{
Integratoren2d_forceless::Set3_Exact(rod, sim);
};
BENCHMARK("BDAS without force")
{
Integratoren2d_forceless::Set4_BDAS(rod, sim);
};
BENCHMARK("Euler without force") {
Integratoren2d_forceless::Set1_Euler(rod, sim);
};
BENCHMARK("Heun without force") {
Integratoren2d_forceless::Set2_Heun(rod, sim);
};
BENCHMARK("Exact without force") {
Integratoren2d_forceless::Set3_Exact(rod, sim);
};
BENCHMARK("BDAS without force") {
Integratoren2d_forceless::Set4_BDAS(rod, sim);
};
BENCHMARK("MBD without force") {
Integratoren2d_forceless::Set5_MBD(rod, sim);
};
}

View File

@ -6,46 +6,48 @@
#include <utility>
void Calculation::run(size_t steps) {
for (size_t step = 0; step < steps; ++step) {
m_integrator(rod, sim);
for (auto &comp: computes) { comp.eval(rod); }
for (auto &comp : computes) {
comp.eval(rod);
}
}
}
const Rod2d &Calculation::getRod() const {
return rod;
}
const Rod2d &Calculation::getRod() const { return rod; }
Calculation::Calculation(std::function<void(Rod2d &, Simulation &)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes, double deltaT,
size_t seed)
: sim(deltaT, seed), m_integrator(
std::move(t_integrator)) {
for (const auto &pair: t_computes) {
Calculation::Calculation(
std::function<void(Rod2d &, Simulation &)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes,
double deltaT, size_t seed,double length)
: rod(length), sim(deltaT, seed),m_integrator(std::move(t_integrator)) {
for (const auto &pair : t_computes) {
computes.emplace_back(Compute(rod, pair.first, pair.second, sim));
}
}
Calculation::Calculation(
std::function<void(Rod2d &, Simulation &, std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)>)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes, double deltaT,
size_t seed, std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque)
: sim(deltaT, seed) {
m_integrator = [&](Rod2d &t_rod, Simulation &t_sim) { t_integrator(t_rod, t_sim, force, torque); };
for (const auto &pair: t_computes) {
std::function<
void(Rod2d &, Simulation &,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)>)>
t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes,
double deltaT, size_t seed,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque, double length)
:rod(length), sim(deltaT, seed) {
m_integrator = [&](Rod2d &t_rod, Simulation &t_sim) {
t_integrator(t_rod, t_sim, force, torque);
};
for (const auto &pair : t_computes) {
computes.emplace_back(Compute(rod, pair.first, pair.second, sim));
}
}
const std::vector<Compute> &Calculation::getComputes() const {
return computes;
}
const Simulation &Calculation::getSim() const {
return sim;
}
const Simulation &Calculation::getSim() const { return sim; }

View File

@ -2,35 +2,37 @@
// Created by jholder on 22.10.21.
//
#ifndef MYPROJECT_CALCULATION_H
#define MYPROJECT_CALCULATION_H
#pragma once
#include <functional>
#include "Compute.h"
#include "Rod2d.hpp"
#include "Simulation.h"
#include "functional"
#include "Compute.h"
class Calculation {
private:
Rod2d rod = Rod2d(1.0);
private:
Rod2d rod;
Simulation sim;
std::function<void(Rod2d &, Simulation &)> m_integrator;
std::vector<Compute> computes;
public:
const Simulation &getSim() const;
public:
[[nodiscard]] const Simulation &getSim() const;
using force_type = std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>;
using torque_type = std::function<double(Eigen::Vector2d, Eigen::Vector2d)>;
using inte_force_type = std::function<void(Rod2d &, Simulation &, force_type, torque_type)>;
Calculation(
std::function<void(Rod2d &, Simulation &, std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)>)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes, double deltaT, size_t seed,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque);
inte_force_type
t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes,
double deltaT, size_t seed,
force_type force,
torque_type torque, double length = 1.0);
explicit Calculation(std::function<void(Rod2d &, Simulation &)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes, double deltaT,
size_t seed);
explicit Calculation(
std::function<void(Rod2d &, Simulation &)> t_integrator,
std::initializer_list<std::pair<Compute::Type, size_t>> t_computes,
double deltaT, size_t seed, double length = 1.0);
[[nodiscard]] const std::vector<Compute> &getComputes() const;
@ -38,6 +40,3 @@ public:
[[nodiscard]] const Rod2d &getRod() const;
};
#endif //MYPROJECT_CALCULATION_H

View File

@ -4,8 +4,9 @@
#include "Compute.h"
#include <utility>
#include <iostream>
#include <utility>
#include "Rod2d.hpp"
#include "Simulation.h"
@ -23,12 +24,21 @@ void Compute::evalOAF(const Rod2d &rod2D) {
agg.feed(oaf);
}
void Compute::eval_empXX(const Rod2d & /*rod2D*/) {
//TODO
void Compute::eval_empXX(const Rod2d &rod2D) {
const auto &new_pos = rod2D.getPos();
auto old_pos = start_rod.getPos();
auto old_e = start_rod.getE();
double empxx = pow((new_pos - old_pos).dot(old_e), 2.0)/2.0 / time;
agg.feed(empxx);
}
void Compute::eval_empYY(const Rod2d & /*rod2D*/) {
//TODO
void Compute::eval_empYY(const Rod2d &rod2D) {
const auto &new_pos = rod2D.getPos();
auto old_pos = start_rod.getPos();
auto old_e = start_rod.getE();
Eigen::Vector2d old_e_ortho = {-old_e[1], old_e[0]};
double empxx = pow((new_pos - old_pos).dot(old_e_ortho), 2.0)/2.0 / time;
agg.feed(empxx);
}
void Compute::eval(const Rod2d &rod2D) {
@ -50,44 +60,53 @@ void Compute::eval(const Rod2d &rod2D) {
}
start_rod = rod2D;
}
}
Compute::Compute(Rod2d rod, Type t_type, size_t t_every, Simulation &sim)
: start_rod(std::move(rod)), every(t_every), time_step(0), type(t_type) {
auto time = sim.getMDeltaT() * static_cast<double>(every);
: start_rod(std::move(rod)), every(t_every), time_step(0), type(t_type) {
time = sim.getMDeltaT() * static_cast<double>(every);
switch (type) {
case Type::msd:
case Type::msd:{
type_str = "msd";
target = 4.0 * 0.5 * (rod.getDiff().trace()) * time;
break;
case Type::oaf:
break;}
case Type::oaf: {
type_str = "oaf";
target = std::exp(-rod.getDRot() * time);
break;
case Type::empxx:
target = 0;
break;
case Type::empyy:
target = 0;
break;
}
case Type::empxx: {
type_str = "empxx";
const double Dmean = 0.5 * (rod.getDiff().trace());
const double u = 4.0;
const double deltaD = rod.getDiff()(1, 1) - rod.getDiff()(0, 0);
target = Dmean - deltaD / 2.0 *
(1 - exp(-u * rod.getDRot() * time)) / u /
rod.getDRot() / time;
} break;
case Type::empyy: {
type_str = "empyy";
const double Dmean = 0.5 * (rod.getDiff().trace());
const double u = 4.0;
const double deltaD = rod.getDiff()(1, 1) - rod.getDiff()(0, 0);
target = Dmean + deltaD / 2.0 *
(1 - exp(-u * rod.getDRot() * time)) / u /
rod.getDRot() / time ;
} break;
}
}
const LiveAgg &Compute::getAgg() const {
return agg;
}
const LiveAgg &Compute::getAgg() const { return agg; }
Compute::Type Compute::getType() const {
return type;
}
Compute::Type Compute::getType() const { return type; }
double Compute::getTime() const {
return static_cast<double>(every);
}
double Compute::getTime() const { return static_cast<double>(every); }
double Compute::getTarget() const {
return target;
}
double Compute::getTarget() const { return target; }
double Compute::getDifference() const {
return abs(agg.getMean() -target);
}
double Compute::getDifference() const { return abs(agg.getMean() - target); }
std::ostream &operator<<(std::ostream &os, const Compute &compute) {
os << "agg: " << compute.agg << " type: " << compute.type_str;
return os;
}

View File

@ -5,17 +5,14 @@
#ifndef MYPROJECT_COMPUTE_H
#define MYPROJECT_COMPUTE_H
#include <ostream>
#include "LiveAgg.hpp"
#include "Rod2d.hpp"
#include "Simulation.h"
class Compute {
public:
enum class Type {
msd, oaf, empxx, empyy
};
public:
enum class Type { msd, oaf, empxx, empyy };
explicit Compute(Rod2d rod, Type t_type, size_t t_every, Simulation &sim);
@ -39,6 +36,7 @@ public:
double getDifference() const;
friend std::ostream &operator<<(std::ostream &os, const Compute &compute);
private:
Rod2d start_rod;
@ -47,8 +45,8 @@ private:
size_t time_step;
Type type;
double target;
double time;
std::string type_str;
};
#endif //MYPROJECT_COMPUTE_H
#endif // MYPROJECT_COMPUTE_H

View File

@ -3,23 +3,13 @@
//
#include "Integratoren2d_force.h"
#include "vec_trafos.h"
constexpr double kBT = 1.0;
using Vector = Eigen::Vector2d;
using Matrix = Eigen::Matrix2d;
Vector Integratoren2d_force::ortho(Vector e) {
return Vector{-e[1], e[0]};
}
Eigen::Matrix2d Integratoren2d_force::MatTraf(Vector e) {
Eigen::Matrix2d mat;
mat << e[0], -e[1],
e[1], e[0];
return mat;
}
void Integratoren2d_force::Set0_deterministic(Rod2d &rod2D, Simulation & /*sim*/) {
void Integratoren2d_force::Set0_deterministic(Rod2d &rod2D,
Simulation & /*sim*/) {
auto trans_lab = Vector({0, 0.01});
rod2D.setPos(rod2D.getPos() + trans_lab);
Eigen::Rotation2D<double> rot(0.1);
@ -28,144 +18,177 @@ void Integratoren2d_force::Set0_deterministic(Rod2d &rod2D, Simulation & /*sim*/
const Vector Integratoren2d_force::unitVec = {1, 0};
void Integratoren2d_force::Set1_Euler(
Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force,
const std::function<double(Vector, Vector)> &torque) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
// translation
Vector rand = {sim.getNorm(std), sim.getNorm(std)}; // gaussian noise
Vector trans_part = rod2D.getDiff_Sqrt() * rand;
Vector trans_lab = rotation_Matrix(rod2D.getE()) * trans_part;
void Integratoren2d_force::Set5_MBD(Rod2d &/*rod2D*/, Simulation &/*sim*/) {
}
void Integratoren2d_force::Set1_Euler(Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force,
const std::function<double(Vector, Vector)> &torque) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
//translation
Vector rand = {sim.getNorm(std), sim.getNorm(std)}; //gaussian noise
Vector trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Vector trans_lab = rod2D.getE_Base_matrix() * trans_part;
//Force
// Force
Vector F_lab = force(rod2D.getPos(), rod2D.getE());
Vector F_part = rod2D.getE_Base_matrix().inverse() * F_lab;
Vector F_part = rotation_Matrix(rod2D.getE()).inverse() * F_lab;
Vector F_trans = rod2D.getDiff_Sqrt() * F_part;
F_trans *= sim.getMDeltaT() / kBT;
F_trans *= sim.getMDeltaT();
//rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();// rotationsmatrix verwenden.
// rotation
double rot =
sim.getNorm(std) * rod2D.getDRot_Sqrt(); // rotationsmatrix verwenden.
Vector e = rod2D.getE();
double M_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() / kBT * sim.getMDeltaT();
double M_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() * sim.getMDeltaT();
Vector new_e = e + (rot + M_rot) * ortho(e);
new_e.normalize();
//apply
// apply
rod2D.setPos(rod2D.getPos() + trans_lab + F_trans);
rod2D.setE(new_e);
}
Vector Integratoren2d_force::Heun_predictor_pos(const Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force) {
Vector Integratoren2d_force::Heun_predictor_pos(
const Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force) {
auto standard_dev = sim.getSTD();
Vector rand_pred = {sim.getNorm(standard_dev), sim.getNorm(standard_dev)}; //gaussian noise
Vector trans_pred_part = rod2D.getDiff_Sqrt() * rand_pred; //translation vector in Particle System
Vector trans_pred_lab = rod2D.getE_Base_matrix() * trans_pred_part;
Vector rand_pred = {sim.getNorm(standard_dev),
sim.getNorm(standard_dev)}; // gaussian noise
Vector trans_pred_part =
rod2D.getDiff_Sqrt() *
rand_pred; // translation vector in Particle System
Vector trans_pred_lab = rotation_Matrix(rod2D.getE()) * trans_pred_part;
Vector F_pred_lab = force(rod2D.getPos(), rod2D.getE());
Vector F_pred_part = rod2D.getE_Base_matrix().inverse() * F_pred_lab;
Vector F_pred_part = rotation_Matrix(rod2D.getE()).inverse() * F_pred_lab;
Vector F_pred_trans = rod2D.getDiff_Sqrt() * F_pred_part;
F_pred_trans *= sim.getMDeltaT() / kBT;
F_pred_trans *= sim.getMDeltaT() ;
return F_pred_trans + trans_pred_lab;
}
Vector Integratoren2d_force::Heun_predictor_rot(const Rod2d &rod2D, Simulation &sim,
const std::function<double(Vector, Vector)> &torque) {
Vector Integratoren2d_force::Heun_predictor_rot(
const Rod2d &rod2D, Simulation &sim,
const std::function<double(Vector, Vector)> &torque) {
auto std = sim.getSTD();
double rot_predict = sim.getNorm(std) * rod2D.getDRot_Sqrt();// rotationsmatrix verwenden.
Vector e = rod2D.getE();
double M_predict_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() / kBT * sim.getMDeltaT();
double rot_predict =
sim.getNorm(std) * rod2D.getDRot_Sqrt(); // rotationsmatrix verwenden.
const Vector& e = rod2D.getE();
double M_predict_rot = torque(rod2D.getPos(), rod2D.getE()) *
rod2D.getDRot() * sim.getMDeltaT();
Vector e_change_predict = (rot_predict + M_predict_rot) * ortho(e);
return e_change_predict;
}
void Integratoren2d_force::Set2_Heun(Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force,
const std::function<double(Vector, Vector)> &torque) {
void Integratoren2d_force::Set2_Heun(
Rod2d &rod2D, Simulation &sim,
const std::function<Vector(Vector, Vector)> &force,
const std::function<double(Vector, Vector)> &torque) {
Vector delta_pos_predictor = Heun_predictor_pos(rod2D, sim, force);
Vector pos_predictor = rod2D.getPos() + delta_pos_predictor;
Vector delta_e_predictor = Heun_predictor_rot(rod2D, sim, torque);
Vector e_predict = rod2D.getE() + delta_e_predictor;
e_predict.normalize();
Vector e_predictor = rod2D.getE() + delta_e_predictor;
e_predictor.normalize();
Rod2d pred_rod = rod2D;
pred_rod.setPos(pos_predictor);
pred_rod.setE(e_predict);
pred_rod.setE(e_predictor);
Vector delta_pos_future = Heun_predictor_pos(pred_rod, sim, force);
Vector delta_e_future = Heun_predictor_rot(pred_rod, sim, torque);
//integration
Vector pos_integrated = 0.5 * rod2D.getPos() + 0.5 * pos_predictor + 0.5 * delta_pos_future;
Vector e_integrated = rod2D.getE() + 0.5 * (delta_e_predictor + delta_e_future);
//apply
rod2D.setPos(pos_integrated);
Vector e_integrated =
rod2D.getE() + 0.5 * (delta_e_predictor + delta_e_future);
// apply
rod2D.setPos(pos_predictor);
rod2D.setE(e_integrated.normalized());
}
void Integratoren2d_force::Set3_Exact(Rod2d &rod2D, Simulation &sim,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
//translation
Vector rand = {sim.getNorm(std), sim.getNorm(std)}; //gaussian noise
Vector trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
void Integratoren2d_force::Set3_Exact(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
// translation
Vector rand = {sim.getNorm(std), sim.getNorm(std)}; // gaussian noise
Vector trans_part =
rod2D.getDiff_Sqrt() * rand; // translation vector in Particle System
Vector F_lab = force(rod2D.getPos(), rod2D.getE());
Vector F_part = rod2D.getE_Base_matrix().inverse() * F_lab;
Vector F_part = rotation_Matrix(rod2D.getE()).inverse() * F_lab;
Vector F_trans = rod2D.getDiff_Sqrt() * F_part;
F_trans *= sim.getMDeltaT() / kBT;
Vector trans_lab = rod2D.getE_Base_matrix() * trans_part;
F_trans *= sim.getMDeltaT();
Vector trans_lab = rotation_Matrix(rod2D.getE()) * trans_part;
//rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();// rotationsmatrix verwenden.
// rotation
double rot =
sim.getNorm(std) * rod2D.getDRot_Sqrt(); // rotationsmatrix verwenden.
Vector e = rod2D.getE();
double M_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() / kBT * sim.getMDeltaT();
auto correction = -0.5 * pow(rod2D.getDRot(), 2) / pow(kBT, 2) * sim.getMDeltaT();
double M_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() * sim.getMDeltaT();
auto correction =
-0.5 * pow(rod2D.getDRot(), 2) * sim.getMDeltaT();
Vector new_e = e + (rot + M_rot) * ortho(e) + correction * e;
new_e.normalize();
//apply
// apply
rod2D.setPos(rod2D.getPos() + trans_lab + F_trans);
rod2D.setE(new_e);
}
void Integratoren2d_force::Set4_BDAS(Rod2d &rod2D, Simulation &sim,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> /*torque*/) {
auto std = sim.getSTD();
//translation
auto rand = Vector(sim.getNorm(std), sim.getNorm(std));
auto trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Eigen::Rotation2D rotMat(acos(unitVec.dot(rod2D.getE())));
auto trans_lab = rotMat * trans_part;
void Integratoren2d_force::Set4_BDAS(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
Vector e = rod2D.getE();
// translation
Vector rand = {sim.getNorm(std), sim.getNorm(std)}; // gaussian noise
Vector trans_part = rod2D.getDiff_Sqrt() * rand;
Vector trans_lab = rotation_Matrix(rod2D.getE()) * trans_part;
// Force
Vector F_lab = force(rod2D.getPos(), rod2D.getE());
Vector F_part = rotMat.inverse() * F_lab;
Vector F_part = rotation_Matrix(rod2D.getE()).inverse() * F_lab;
Vector F_trans = rod2D.getDiff_Sqrt() * F_part;
F_trans *= sim.getMDeltaT() / kBT;
F_trans *= sim.getMDeltaT();
// rotation
double rot =
sim.getNorm(std) * rod2D.getDRot_Sqrt(); // rotationsmatrix verwenden.
auto rot = Eigen::Rotation2D<double>(sim.getNorm(std) * rod2D.getDRot_Sqrt());
Eigen::Rotation2Dd rotation(rot);
auto e_new = (rotation.toRotationMatrix() * rod2D.getE()).normalized();
// Normalisation should not be necessary if a proper angular representation is used.
// But with vector e it is done in case of numerical errors
rod2D.setPos(rod2D.getPos() + trans_lab);
rod2D.setE(e_new);
double M_rot = torque(rod2D.getPos(), rod2D.getE()) * rod2D.getDRot() * sim.getMDeltaT();
Vector new_e = Eigen::Rotation2D<double>(rot + M_rot) * e;
new_e.normalize();
// apply
rod2D.setPos(rod2D.getPos() + trans_lab + F_trans);
rod2D.setE(new_e);
}
void Integratoren2d_force::Set5_MBD(Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque) {
Vector delta_pos_predictor = Heun_predictor_pos(rod2D, sim, force);
[[maybe_unused]] Vector pos_predictor = rod2D.getPos() + delta_pos_predictor;
Vector delta_e_predictor = Heun_predictor_rot(rod2D, sim, torque);
Vector e_predictor = rod2D.getE() + delta_e_predictor;
e_predictor.normalize();
auto std = sim.getSTD();
Eigen::Vector2d e = rod2D.getE();
Eigen::Matrix2d Diff_combined = 0.5*(rod2D.getDiff() + rotation_Matrix(e).inverse() * rotation_Matrix(e_predictor)*rod2D.getDiff());
Eigen::Matrix2d D_combined_sqrt = Diff_combined.llt().matrixL();
auto rand = Eigen::Vector2d(sim.getNorm(std), sim.getNorm(std));
Eigen::Vector2d pos_integrated =rod2D.getPos() + rotation_Matrix(e) * D_combined_sqrt * rand;
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d e_integrated = e + 0.5 * (rot * ortho(e) + rot * ortho(e_predictor));
//apply
rod2D.setPos(pos_integrated);
rod2D.setE(e_integrated.normalized());
}

View File

@ -8,41 +8,44 @@
#include "Simulation.h"
class Integratoren2d_force {
public:
static void Set1_Euler(Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> &force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
public:
static void Set1_Euler(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>
&force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
static void Set2_Heun(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>
&force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
static void Set2_Heun(Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> &force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
static void Set3_Exact(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque);
static void Set3_Exact(Rod2d &rod2D, Simulation &sim,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque);
static void Set4_BDAS(Rod2d &rod2D, Simulation &sim,
std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)> force,
std::function<double(Eigen::Vector2d, Eigen::Vector2d)> torque);
static void Set4_BDAS(
Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque);
static const Eigen::Vector2d unitVec;
static void Set5_MBD(Rod2d &rod2D, Simulation &sim);
static void Set5_MBD(Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>& force,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)>& torque);
static void Set0_deterministic(Rod2d &rod2D, Simulation &sim);
private:
static Eigen::Vector2d ortho(Eigen::Vector2d e);
private:
static Eigen::Vector2d Heun_predictor_pos(
const Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d, Eigen::Vector2d)>
&force);
static Eigen::Matrix2d MatTraf(Eigen::Matrix<double, 2, 1> e);
static Eigen::Vector2d Heun_predictor_pos(const Rod2d &rod2D, Simulation &sim,
const std::function<Eigen::Vector2d(Eigen::Vector2d,
Eigen::Vector2d)> &force);
static Eigen::Vector2d
Heun_predictor_rot(const Rod2d &rod2D, Simulation &sim,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
static Eigen::Vector2d Heun_predictor_rot(
const Rod2d &rod2D, Simulation &sim,
const std::function<double(Eigen::Vector2d, Eigen::Vector2d)> &torque);
};

View File

@ -3,12 +3,10 @@
//
#include "Integratoren2d_forceless.h"
#include "vec_trafos.h"
Eigen::Vector2d Integratoren2d_forceless::ortho(Eigen::Vector2d e) {
return Eigen::Vector2d{-e[1], e[0]};
}
void Integratoren2d_forceless::Set0_deterministic(Rod2d &rod2D, Simulation & /*sim*/) {
void Integratoren2d_forceless::Set0_deterministic(Rod2d &rod2D,
Simulation & /*sim*/) {
auto trans_lab = Eigen::Vector2d({0, 0.01});
rod2D.setPos(rod2D.getPos() + trans_lab);
Eigen::Rotation2D<double> rot(0.1);
@ -16,156 +14,110 @@ void Integratoren2d_forceless::Set0_deterministic(Rod2d &rod2D, Simulation & /*s
}
void Integratoren2d_forceless::Set1_Euler(Rod2d &rod2D, Simulation &sim) {
auto std = sim.getSTD(); // sqrt(2*delta_T)
//translation
Eigen::Vector2d rand = {sim.getNorm(std), sim.getNorm(std)}; //gaussian noise
Eigen::Vector2d trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Eigen::Vector2d trans_lab = rod2D.getE_Base_matrix() * trans_part;
/* TODO
Statt Zeile 22 und 23 kannst du trans_lab = paralleler_matrix_eintrag * e plus senkrechter_matrix_eintrag * ortho(e);
*/
//rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();// rotationsmatrix verwenden.
auto std = sim.getSTD(); // sqrt(2*delta_T)
Eigen::Vector2d e = rod2D.getE();
Eigen::Vector2d new_e = e + rot * ortho(e);
new_e.normalize();
//apply
rod2D.setPos(rod2D.getPos() + trans_lab);
rod2D.setE(new_e);
// translation
Eigen::Vector2d rand = {sim.getNorm(std), sim.getNorm(std)};
Eigen::Vector2d trans_part = rod2D.getDiff_Sqrt() * rand;
Eigen::Vector2d trans_lab = rotation_Matrix(e) * trans_part;
// rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d new_e = e + rot * ortho(e);
// apply
rod2D.setPos(rod2D.getPos() + trans_lab);
rod2D.setE(new_e.normalized());
}
void Integratoren2d_forceless::Set2_Heun(Rod2d &rod2D, Simulation &sim) {
// Predict with Euler
auto std = sim.getSTD();
Eigen::Vector2d e = rod2D.getE();
Eigen::Vector2d rand = Eigen::Vector2d(sim.getNorm(std), sim.getNorm(std));
Eigen::Vector2d trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Eigen::Vector2d trans_lab = rod2D.getE_Base_matrix() * trans_part;
Eigen::Vector2d trans_part =
rod2D.getDiff_Sqrt() * rand;
Eigen::Vector2d trans_lab = rotation_Matrix(e) * trans_part;
Eigen::Vector2d pos_predictor = rod2D.getPos() + trans_lab;
/*
TODO
Siehe Set_1: Hier auch über e und orth(e)
*/
//rotation
double rot_predict = sim.getNorm(std) * rod2D.getDRot_Sqrt();// rotationsmatrix verwenden.
Eigen::Vector2d e = rod2D.getE();
// rotation
double rot_predict = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d delta_e_predict = rot_predict * ortho(e);
Eigen::Vector2d e_predict = (e + delta_e_predict).normalized();
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d e_integrated = e + 0.5 * (rot * ortho(e) + rot * ortho(e_predict));
//TODO pos integration with future system ???
// Eigen::Vector2d pos_integrated = rod2D.getPos() + 0.5 * (rot * ortho(e) + rot * ortho(e_predict));
Eigen::Vector2d e_integrated =
e + 0.5 * (rot * ortho(e) + rot * ortho(e_predict));
//apply
rod2D.setPos(pos_predictor);
// apply
rod2D.setPos(pos_predictor); // pos with Euler
rod2D.setE(e_integrated.normalized());
}
constexpr double kBT = 1.0;
void Integratoren2d_forceless::Set3_Exact(Rod2d &rod2D, Simulation &sim) {
auto std = sim.getSTD();
//translation
Eigen::Vector2d rand = {sim.getNorm(std), sim.getNorm(std)}; //gaussian noise
Eigen::Vector2d trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Eigen::Vector2d trans_lab = rod2D.getE_Base_matrix() * trans_part;
/*
TODO: Siehe Set1
*/
//rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d e = rod2D.getE();
auto correction = -0.5 * pow(rod2D.getDRot(), 2) / pow(kBT, 2) * sim.getMDeltaT();
// translation
Eigen::Vector2d rand = {sim.getNorm(std), sim.getNorm(std)};
Eigen::Vector2d trans_part = rod2D.getDiff_Sqrt() * rand;
Eigen::Vector2d trans_lab = rotation_Matrix(e) * trans_part;
// rotation
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
auto correction =
-0.5 * pow(rod2D.getDRot(), 2) * sim.getMDeltaT();
Eigen::Vector2d delta_e = correction * e + rot * ortho(e);
/*
TODO Warum hier kBT definiert?
*/
//apply
// apply
rod2D.setPos(rod2D.getPos() + trans_lab);
rod2D.setE((e + delta_e).normalized());
}
const Eigen::Vector2d Integratoren2d_forceless::unitVec = {1, 0};
//this is a slow implementation to keep the same data structure for performance analysis this must be altered
// this is a slow implementation to keep the same data structure for performance
// analysis this must be altered
// Normalisation should not be necessary if a proper angular representation
// is used. But with vector e it is done in case of numerical errors
void Integratoren2d_forceless::Set4_BDAS(Rod2d &rod2D, Simulation &sim) {
auto std = sim.getSTD();
//translation
Eigen::Vector2d e = rod2D.getE();
// translation
auto rand = Eigen::Vector2d(sim.getNorm(std), sim.getNorm(std));
auto trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
Eigen::Rotation2D rotMat(acos(unitVec.dot(rod2D.getE())));
auto trans_lab = rotMat * trans_part;
auto trans_part =
rod2D.getDiff_Sqrt() * rand; // translation vector in Particle System
Eigen::Vector2d trans_lab = rotation_Matrix(e) * trans_part;
/*
TODO: Warum hier nicht die Matrix von oben?
*/
auto rot = Eigen::Rotation2D<double>(sim.getNorm(std) * rod2D.getDRot_Sqrt());
auto rot =
Eigen::Rotation2D<double>(sim.getNorm(std) * rod2D.getDRot_Sqrt());
Eigen::Rotation2Dd rotation(rot);
auto e_new = (rotation.toRotationMatrix() * rod2D.getE()).normalized();
/*
TODO Warum Normierung? Ist der Fehler so gros? Wie siehts mit einer Winkelvariable aus,
dann musst du den Winkel nicht jedesmal berechnen?
*/
// Normalisation should not be necessary if a proper angular representation is used.
// But with vector e it is done in case of numerical errors
auto e_new = (rotation.toRotationMatrix() * e).normalized();
rod2D.setPos(rod2D.getPos() + trans_lab);
rod2D.setE(e_new);
}
Eigen::Matrix2d Integratoren2d_forceless::e_2_matrix(Eigen::Vector2d m_e) {
Eigen::Matrix2d mat;
mat << m_e[0], -m_e[1],
m_e[1], m_e[0];
return mat;
}
void Integratoren2d_forceless::Set5_MBD(Rod2d & rod2D,
Simulation & sim) {
void Integratoren2d_forceless::Set5_MBD(Rod2d &/*rod2D*/, Simulation &/*sim*/) {
/*
auto std = sim.getSTD();
auto rand = Eigen::Vector2d(sim.getNorm(std), sim.getNorm(std));
auto trans_part = rod2D.getDiff_Sqrt() * rand; //translation vector in Particle System
auto trans_lab = rod2D.getE_Base_matrix() * trans_part;
auto pos_predictor = rod2D.getPos() + trans_lab;
Eigen::Vector2d e = rod2D.getE();
//rotation
auto rot_predict = Eigen::Rotation2D<double>(sim.getNorm(std) * rod2D.getDRot_Sqrt());// rotationsmatrix verwenden.
auto e = rod2D.getE();
double rot_predict = sim.getNorm(std) *
rod2D.getDRot_Sqrt();
auto delta_e_predict = rot_predict * ortho(e);
auto e_predict = (e + delta_e_predict).normalized();
auto std_combined = rod2D.getDiff() + rod2D.getE_Base_matrix() * rod2D.getDiff(); //old + new diff
auto rot = Eigen::Rotation2D<double>(sim.getNorm(std) * rod2D.getDRot_Sqrt());
auto e_integrated = e + 0.5 * (rot * ortho(e) + rot * ortho(e_predict));
Eigen::Matrix2d Diff_combined = 0.5*(rod2D.getDiff() + rotation_Matrix(e).inverse() * rotation_Matrix(e_predict)*rod2D.getDiff());
Eigen::Matrix2d D_combined_sqrt = Diff_combined.llt().matrixL();
auto rand = Eigen::Vector2d(sim.getNorm(std), sim.getNorm(std));
Eigen::Vector2d pos_integrated =rod2D.getPos() + rotation_Matrix(e) * D_combined_sqrt * rand;
double rot = sim.getNorm(std) * rod2D.getDRot_Sqrt();
Eigen::Vector2d e_integrated = e + 0.5 * (rot * ortho(e) + rot * ortho(e_predict));
//apply
rod2D.setPos(pos_predictor);
rod2D.setPos(pos_integrated);
rod2D.setE(e_integrated.normalized());
*/
}

View File

@ -2,14 +2,13 @@
// Created by jholder on 21.10.21.
//
#ifndef MYPROJECT_INTEGRATOREN2D_FORCELESS_H
#define MYPROJECT_INTEGRATOREN2D_FORCELESS_H
#pragma once
#include "Rod2d.hpp"
#include "Simulation.h"
class Integratoren2d_forceless {
public:
public:
static void Set1_Euler(Rod2d &rod2D, Simulation &sim);
static void Set2_Heun(Rod2d &rod2D, Simulation &sim);
@ -20,15 +19,7 @@ public:
static const Eigen::Vector2d unitVec;
static Eigen::Matrix2d e_2_matrix(Eigen::Vector2d m_e);
static void Set5_MBD(Rod2d &rod2D, Simulation &sim);
static void Set0_deterministic(Rod2d &rod2D, Simulation &sim);
private:
static Eigen::Vector2d ortho(Eigen::Vector2d e);
};
#endif //MYPROJECT_INTEGRATOREN2D_FORCELESS_H

View File

@ -1,33 +1,26 @@
#include "LiveAgg.hpp"
#include <cmath>
LiveAgg::LiveAgg() : num_of_data(0), mean(0.0), S(0.0)
{
LiveAgg::LiveAgg() : num_of_data(0), mean(0.0), S(0.0) {}
double LiveAgg::getSD() const noexcept { return S / (num_of_data - 1); }
double LiveAgg::getSEM() const noexcept {
return S / (num_of_data - 1) / std::sqrt(num_of_data);
}
double LiveAgg::getSD() const noexcept
{
return S / (num_of_data - 1);
}
double LiveAgg::getMean() const noexcept { return mean; }
double LiveAgg::getSEM() const noexcept
{
return S / (num_of_data - 1) / std::sqrt(num_of_data);
void LiveAgg::feed(double value) noexcept {
num_of_data += 1;
auto delta = value - mean;
mean += delta / num_of_data;
auto delta2 = value - mean;
S += delta * delta2;
}
int LiveAgg::getNumPoints() const noexcept { return num_of_data; }
double LiveAgg::getMean() const noexcept
{
return mean;
}
void LiveAgg::feed(double value) noexcept
{
num_of_data += 1;
auto delta = value - mean;
mean += delta / num_of_data;
auto delta2 = value - mean;
S += delta * delta2;
}
int LiveAgg::getNumPoints() const noexcept
{
return num_of_data;
std::ostream &operator<<(std::ostream &os, const LiveAgg &agg) {
os << "num_of_data: " << agg.num_of_data << " mean: " << agg.mean << " S: " << agg.S;
return os;
}

View File

@ -1,20 +1,20 @@
#ifndef LIVEAGG_H
#define LIVEAGG_H
#pragma once
#include <ostream>
class LiveAgg
{
public:
LiveAgg();
[[nodiscard]] double getSD() const noexcept;
[[nodiscard]] double getSEM() const noexcept;
[[nodiscard]] double getMean() const noexcept;
[[nodiscard]] int getNumPoints() const noexcept;
void feed(double value) noexcept;
private:
int num_of_data;
double mean;
double S;
class LiveAgg {
public:
LiveAgg();
[[nodiscard]] double getSD() const noexcept;
[[nodiscard]] double getSEM() const noexcept;
[[nodiscard]] double getMean() const noexcept;
[[nodiscard]] int getNumPoints() const noexcept;
void feed(double value) noexcept;
friend std::ostream &operator<<(std::ostream &os, const LiveAgg &agg);
private:
int num_of_data;
double mean;
double S;
};
#endif // LIVEAGG_H

View File

@ -1,28 +1,30 @@
#include "Rod2d.hpp"
#include "Eigen/Dense"
constexpr double M_Pl = 3.141592653589793238462643383279502884; /* pi */
void sqrt(Eigen::Matrix2d &mat){
void sqrt(Eigen::Matrix2d &mat) {
const auto size = static_cast<size_t>(mat.size());
for (size_t i = 0; i < size; i++) {
mat.data()[i] = sqrt(mat.data()[i]);
}
}
Rod2d::Rod2d(double L) : m_pos({0, 0}), m_e({1, 0}) {
assert(L>=1.0);
assert(L >= 1.0);
if (L == 1.0) {
m_D_rot = 3.0;
m_Diff << 1, 0,
0, 1;
m_Diff << 1, 0, 0, 1;
} else {
const double D0 = 3.0 * M_Pl / L;
const double p = L;
auto D_para = D0 / (M_Pl * 2.0) * (log(p) - 0.207 + 0.980 / p - 0.133 / (p * p));
auto D_ortho = D0 / (M_Pl * 2.0) * (log(p) + 0.839 + 0.185 / p + 0.233 / (p * p));
m_D_rot = 3 * D0 / (M_Pl * L * L) * (log(p) - 0.662 + 0.917 / p - 0.050 / (p * p));
m_Diff << D_para, 0,
0, D_ortho;
auto D_para =
D0 / (M_Pl * 2.0) * (log(p) - 0.207 + 0.980 / p - 0.133 / (p * p));
auto D_ortho =
D0 / (M_Pl * 2.0) * (log(p) + 0.839 + 0.185 / p + 0.233 / (p * p));
m_D_rot = 3 * D0 / (M_Pl * L * L) *
(log(p) - 0.662 + 0.917 / p - 0.050 / (p * p));
m_Diff << D_para, 0, 0, D_ortho;
}
m_Diff_sqrt = m_Diff;
m_D_rot_sqrt = sqrt(m_D_rot);
@ -34,43 +36,19 @@ void Rod2d::reset() {
m_e = {1, 0};
}
void Rod2d::setPos(const Eigen::Vector2d &Pos) {
m_pos = Pos;
}
void Rod2d::setPos(const Eigen::Vector2d &Pos) { m_pos = Pos; }
double Rod2d::getDRot() const {
return m_D_rot;
}
double Rod2d::getDRot() const { return m_D_rot; }
const Eigen::Vector2d &Rod2d::getPos() const {
return m_pos;
}
const Eigen::Vector2d &Rod2d::getPos() const { return m_pos; }
const Eigen::Matrix2d &Rod2d::getDiff() const {
return m_Diff;
}
const Eigen::Matrix2d &Rod2d::getDiff() const { return m_Diff; }
const Eigen::Matrix2d &Rod2d::getDiff_Sqrt() const {
return m_Diff_sqrt;
}
const Eigen::Matrix2d &Rod2d::getDiff_Sqrt() const { return m_Diff_sqrt; }
double Rod2d::getDRot_Sqrt() const {
return m_D_rot_sqrt;
}
double Rod2d::getDRot_Sqrt() const { return m_D_rot_sqrt; }
const Eigen::Vector2d &Rod2d::getE() const {
return m_e;
}
void Rod2d::setE(const Eigen::Vector2d &mE) {
m_e = mE;
}
Eigen::Matrix2d Rod2d::getE_Base_matrix() const {
Eigen::Matrix2d mat;
mat << m_e[0], -m_e[1],
m_e[1], m_e[0];
return mat;
}
const Eigen::Vector2d &Rod2d::getE() const { return m_e; }
void Rod2d::setE(const Eigen::Vector2d &mE) { m_e = mE; }

View File

@ -1,9 +1,8 @@
#pragma once
#include <Eigen/Geometry>
#include <Eigen/Dense>
class Rod2d
{
public:
#include <Eigen/Geometry>
class Rod2d {
public:
explicit Rod2d(double L);
void reset();
@ -23,15 +22,11 @@ public:
[[nodiscard]] double getDRot_Sqrt() const;
Eigen::Matrix2d getE_Base_matrix() const;
private:
private:
Eigen::Matrix2d m_Diff;
Eigen::Matrix2d m_Diff_sqrt;
double m_D_rot;
double m_D_rot_sqrt;
Eigen::Vector2d m_pos; // position
Eigen::Vector2d m_pos; // position
Eigen::Vector2d m_e;
};

View File

@ -5,17 +5,15 @@
#include "Simulation.h"
double Simulation::getNorm(double t_norm) {
return t_norm*m_norm(m_generator);
return t_norm * m_norm(m_generator);
}
Simulation::Simulation(double t_delta_T, size_t seed): m_delta_T(t_delta_T),m_std(std::sqrt(t_delta_T*2.0)), m_generator(seed), m_norm(0, 1.0) {
Simulation::Simulation(double t_delta_T, size_t seed)
: m_delta_T(t_delta_T),
m_std(std::sqrt(t_delta_T * 2.0)),
m_generator(seed),
m_norm(0, 1.0) {}
}
double Simulation::getMDeltaT() const { return m_delta_T; }
double Simulation::getMDeltaT() const {
return m_delta_T;
}
double Simulation::getSTD() const {
return m_std;
}
double Simulation::getSTD() const { return m_std; }

View File

@ -2,25 +2,22 @@
// Created by jholder on 21.10.21.
//
#ifndef MYPROJECT_SIMULATION_H
#define MYPROJECT_SIMULATION_H
#pragma once
#include <random>
class Simulation {
public:
public:
explicit Simulation(double t_delta_T, size_t seed);
double getNorm(double t_norm);
private:
private:
double m_delta_T;
double m_std;
std::mt19937_64 m_generator;
std::normal_distribution<double> m_norm;
public:
public:
[[nodiscard]] double getMDeltaT() const;
[[nodiscard]] double getSTD() const;
};
#endif //MYPROJECT_SIMULATION_H

View File

@ -1,130 +0,0 @@
#include "Integratoren.hpp"
constexpr double kBT = 1.0;
void Integratoren::integrateITOEuler_1(Rod2d &rod)
{
//DLOG_SCOPE_F(1,"Integrateing Rod2d:");
double movePara = std::sqrt(2.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);
double moveOrtho = std::sqrt(2.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double tmpx1 = rod.x1 + movePara * rod.e1 - moveOrtho * rod.e2;
double tmpx2 = rod.x2 + movePara * rod.e2 + moveOrtho * rod.e1;
double rodOrtho = std::sqrt(2.0 * rod.Drot * rod.deltaT) * rod.dis(rod.generator);
double tmpe1 = rod.e1 - rodOrtho * rod.e2;
double tmpe2 = rod.e2 + rodOrtho * rod.e1;
rod.x1 = tmpx1;
rod.x2 = tmpx2;
rod.e1 = tmpe1;
rod.e2 = tmpe2;
rod.normalize();
}
void Integratoren::integrateITOHeun_2(Rod2d &rod)
{
//DLOG_SCOPE_F(1,"Integrateing Rod2d:");
double movePara = std::sqrt(2.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);
double moveOrtho = std::sqrt(2.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double tmpx1 = rod.x1 + movePara * rod.e1 - moveOrtho * rod.e2;
double tmpx2 = rod.x2 + movePara * rod.e2 + moveOrtho * rod.e1;
double rodOrtho = std::sqrt(2.0 * rod.Drot * rod.deltaT) * rod.dis(rod.generator);
double e1 = rod.e1 - rodOrtho * rod.e1;
double e2 = rod.e2 + rodOrtho * rod.e2;
double norm = std::sqrt(e1 * e1 + e2 * e2);
e1 /= norm;
e2 /= norm;
double rodOrtho1 = std::sqrt(2.0 * rod.Drot * rod.deltaT);
double rodOrthoRand = rod.dis(rod.generator);
double tmpe1 = rod.e1 - 0.5 * (rodOrtho1 * rod.e2 + rodOrtho1 * e2) * rodOrthoRand;//TODO Check if 0.5 faktor
double tmpe2 = rod.e2 + 0.5 * (rodOrtho1 * rod.e1 + rodOrtho1 * e1) * rodOrthoRand;
rod.x1 = tmpx1;
rod.x2 = tmpx2;
rod.e1 = tmpe1;
rod.e2 = tmpe2;
rod.normalize();
}
void Integratoren::integrateExact_3(Rod2d &rod)
{
//DLOG_SCOPE_F(1,"Integrateing Rod2d:");
double movePara = std::sqrt(2.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);
double moveOrtho = std::sqrt(2.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double tmpx1 = rod.x1 + movePara * rod.e1 - moveOrtho * rod.e2;
double tmpx2 = rod.x2 + movePara * rod.e2 + moveOrtho * rod.e1;
double rodOrtho = std::sqrt(2.0 * rod.Drot * rod.deltaT) * rod.dis(rod.generator);
double korr = -0.5 * rod.Drot * rod.Drot / kBT / kBT * rod.deltaT;
double tmpe1 = rod.e1 - rodOrtho * rod.e2 + korr * rod.e1;
double tmpe2 = rod.e2 + rodOrtho * rod.e1 + korr * rod.e2;
rod.x1 = tmpx1;
rod.x2 = tmpx2;
rod.e1 = tmpe1;
rod.e2 = tmpe2;
rod.normalize();
}
void Integratoren::integrateBDAS_4(Rod2d &rod)
{
double deltaRTpara = std::sqrt(2.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);
double deltaRTortho = std::sqrt(2.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double tmpx1 = rod.x1 + deltaRTpara * rod.e1 - deltaRTortho * rod.e2;
double tmpx2 = rod.x2 + deltaRTpara * rod.e2 + deltaRTortho * rod.e1;
double deltaPhi = std::sqrt(2.0 * rod.Drot * rod.deltaT) * rod.dis(rod.generator);
double tmpe1 = rod.e1 * std::cos(deltaPhi) - rod.e2 * std::sin(deltaPhi);
double tmpe2 = rod.e1 * std::sin(deltaPhi) + rod.e2 * std::cos(deltaPhi);
rod.x1 = tmpx1;
rod.x2 = tmpx2;
rod.e1 = tmpe1;
rod.e2 = tmpe2;
rod.normalize();
}
void Integratoren::integrateMBD_5(Rod2d &rod)
{
/*
double movePara = std::sqrt(2.0*rod.Dpara*rod.deltaT)*rod.dis(rod.generator); // Taken from euler
double moveOrtho = std::sqrt(2.0*rod.Dortho*rod.deltaT)*rod.dis(rod.generator); // taken from euler
double x1 = rod.x1 + movePara*rod.e1- moveOrtho*rod.e2;
double x2 = rod.x2 + movePara*rod.e2+ moveOrtho*rod.e1;
*/
// unused without force
double rodOrtho = std::sqrt(2.0 * rod.Drot * rod.deltaT) * rod.dis(rod.generator);
double e1 = rod.e1 - rodOrtho * rod.e2;
double e2 = rod.e2 + rodOrtho * rod.e1;
double norm = std::sqrt(e1 * e1 + e2 * e2);
e1 /= norm;
e2 /= norm;
double movePara1 = std::sqrt(1.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);// If difussion would be time dependend, average of the predicted D and now D
double moveOrtho1 = std::sqrt(1.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double movePara2 = std::sqrt(1.0 * rod.Dpara * rod.deltaT) * rod.dis(rod.generator);// If difussion would be time dependend, average of the predicted D and now D
double moveOrtho2 = std::sqrt(1.0 * rod.Dortho * rod.deltaT) * rod.dis(rod.generator);
double tmpx1 = rod.x1 + (movePara1 * rod.e1 - moveOrtho1 * rod.e2) + (movePara2 * e1 - moveOrtho2 * e2);
double tmpx2 = rod.x2 + (movePara1 * rod.e2 + moveOrtho1 * rod.e1) + (movePara2 * e2 + moveOrtho2 * e1);
double rodOrtho1 = std::sqrt(2.0 * rod.Drot * rod.deltaT);
double rodOrtho2 = rod.dis(rod.generator);
double tmpe1 = rod.e1 - 0.5 * (rodOrtho1 * rod.e2 + rodOrtho1 * e2) * rodOrtho2;
double tmpe2 = rod.e2 + 0.5 * (rodOrtho1 * rod.e1 + rodOrtho1 * e1) * rodOrtho2;
rod.x1 = tmpx1;
rod.x2 = tmpx2;
rod.e1 = tmpe1;
rod.e2 = tmpe2;
rod.normalize();
}

View File

@ -1,19 +0,0 @@
#ifndef INTEGRATOREN_HPP
#define INTEGRATOREN_HPP
#include "Rod2d.hpp"
class Integratoren
{
public:
static void integrateITOEuler_1(Rod2d &rod);
static void integrateITOHeun_2(Rod2d &rod);
static void integrateExact_3(Rod2d &rod);
static void integrateBDAS_4(Rod2d &rod);
static void integrateMBD_5(Rod2d &rod);
};
#endif// INTEGRATOREN_HPP

View File

@ -1,6 +0,0 @@
#include "Simulation2d.hpp"
#include <vector>
#include<iostream>
#include "LiveAgg.hpp"
template <void (*T)(Rod2d &)>
std::vector<double> simulate(double deltaT, int seed, int meanSteps);

View File

@ -1,157 +0,0 @@
#ifndef SIMULATION2D_HPP
#define SIMULATION2D_HPP
#include "Rod2d.hpp"
#include "LiveAgg.hpp"
#include <fstream>
#include <iostream>
/* This is used to calculate the convergence order of the particles
*/
inline void printProgress(double progress)
{
const int barWidth = 70;
std::cout << "[";
const int pos = static_cast<int>(barWidth * progress);
for (int i = 0; i < barWidth; ++i) {
if (i < pos) {
std::cout << "=";
} else if (i == pos) {
std::cout << ">";
} else {
std::cout << " ";
}
}
std::cout << "] " << int(progress * 100.0) << " % \r";
std::cout.flush();
}
template<void (*T)(Rod2d &)>
void simulate(double L, int seed, const std::string &filename)
{
// we now simulate the msd after 10 steps
Rod2d rod(L, 1e-5, seed);
const int sampleWidth = 1000;
std::vector<LiveAgg> msd(sampleWidth, LiveAgg());
std::vector<LiveAgg> oaf(sampleWidth, LiveAgg());
std::vector<LiveAgg> empxx(sampleWidth, LiveAgg());
std::vector<LiveAgg> empyy(sampleWidth, LiveAgg());
std::vector<double> xPos(sampleWidth, 0.0);
std::vector<double> yPos(sampleWidth, 0.0);
std::vector<double> e1(sampleWidth, 0.0);
std::vector<double> e2(sampleWidth, 0.0);
std::vector<double> targetMSD(sampleWidth, 0.0);
std::vector<double> targetOAF(sampleWidth, 0.0);
std::vector<double> targetEMPXX(sampleWidth, 0.0);
std::vector<double> targetEMPYY(sampleWidth, 0.0);
std::vector<size_t> samplePoints(sampleWidth, 1);
size_t temp = 1;
const double Dmean = 0.5 * (rod.Dpara + rod.Dortho);
const double deltaD = rod.Dortho - rod.Dpara;
for (size_t i = 0; i < samplePoints.size(); ++i) {
samplePoints[i] = temp;
temp += 100;
const double time = static_cast<double>(temp) * rod.deltaT;
targetMSD[i] = 4.0 * 0.5 * (rod.Dpara + rod.Dortho) * time;
targetOAF[i] = std::exp(-rod.Drot * time);
const double u = 4.0;
targetEMPXX[i] = Dmean - deltaD / 2.0 * (1 - exp(-u * rod.Drot * time)) / u / rod.Drot / time;
targetEMPYY[i] = Dmean + deltaD / 2.0 * (1 - exp(-u * rod.Drot * time)) / u / rod.Drot / time;
}
unsigned long long int iteration = 0;
//const unsigned long long int maxItr = ((long int)10000)*1000000;
const unsigned long long int maxItr = 10000000;
const unsigned long long int updateInter = 10000;
while (iteration < maxItr) {
T(rod);
iteration++;
for (size_t i = 0; i < samplePoints.size(); ++i) {
const size_t sample = samplePoints[i];
if (iteration % sample == 0) {
msd[i].feed((rod.x1 - xPos[i]) * (rod.x1 - xPos[i]) + (rod.x2 - yPos[i]) * (rod.x2 - yPos[i]));
oaf[i].feed(rod.e1 * e1[i] + rod.e2 * e2[i]);
empxx[i].feed(std::pow((rod.x1 - xPos[i]) * e1[i] + (rod.x2 - yPos[i]) * e2[i], 2));
empyy[i].feed(std::pow((rod.x1 - xPos[i]) * e2[i] - (rod.x2 - yPos[i]) * e1[i], 2));
xPos[i] = rod.x1;
yPos[i] = rod.x2;
e1[i] = rod.e1;
e2[i] = rod.e2;
}
}
if (iteration % updateInter == 0) {
printProgress(static_cast<double>(iteration)/ maxItr);
}
}
std::cout << "\n";
std::ofstream fileMSD(filename + "_" + std::to_string(L) + "_MSD.out");
std::ofstream fileOAF(filename + "_" + std::to_string(L) + "_OAF.out");
std::ofstream fileXX(filename + "_" + std::to_string(L) + "_XX.out");
std::ofstream fileYY(filename + "_" + std::to_string(L) + "_YY.out");
for (size_t i = 0; i < samplePoints.size(); ++i) {
fileMSD << static_cast<double>(samplePoints[i]) * rod.deltaT << "\t" << targetMSD[i] << "\t" << msd[i].getMean() << "\t" << msd[i].getSEM() << "\t" << msd[i].getSD() << "\t" << msd[i].getNumPoints() << "\n";
fileOAF << static_cast<double>(samplePoints[i]) * rod.deltaT << "\t" << targetOAF[i] << "\t" << oaf[i].getMean() << "\t" << oaf[i].getSEM() << "\t" << oaf[i].getSD() << "\t" << oaf[i].getNumPoints() << "\n";
fileXX << static_cast<double>(samplePoints[i]) * rod.deltaT << "\t" << targetEMPXX[i] << "\t" << empxx[i].getMean() << "\t" << empxx[i].getSEM() << "\t" << empxx[i].getSD() << "\t" << empxx[i].getNumPoints() << "\n";
fileYY << static_cast<double>(samplePoints[i]) * rod.deltaT << "\t" << targetEMPYY[i] << "\t" << empyy[i].getMean() << "\t" << empyy[i].getSEM() << "\t" << empyy[i].getSD() << "\t" << empyy[i].getNumPoints() << "\n";
}
fileMSD.close();
fileOAF.close();
fileXX.close();
fileYY.close();
}
template<void (*T)(Rod2d &)>
void konvergenz(double L, int seed, double deltaT, const std::string &filename)
{
// we now simulate the msd after 10 steps
Rod2d rod(L, deltaT, seed);
const double time = 2;
const int steps = static_cast<int>(time / deltaT);
const int minSteps = 1000;
//const double targetMSD = 4.0*0.5*(rod.Dpara+rod.Dortho)*time;
const double targetOAF = std::exp(-rod.Drot * time);
/*const double u = 4.0;
const double Dmean = 0.5*(rod.Dpara+rod.Dortho);
const double deltaD = rod.Dortho - rod.Dpara;
const double targetEMPXX = Dmean-deltaD/2.0*(1 - exp(-u*rod.Drot*time))/u/rod.Drot / time;
const double targetEMPYY = Dmean+deltaD/2.0*(1 - exp(-u*rod.Drot*time))/u/rod.Drot / time;*/
//LiveAgg msd;
LiveAgg oaf;
//LiveAgg empxx;
//LiveAgg empyy;
int meanCount = 0;
while (meanCount < minSteps or std::abs(targetOAF - oaf.getMean()) < oaf.getSEM() * 10) {
//reset the position
rod.reset();
for (int i = 0; i < steps; ++i) {
T(rod);
}
//msd.feed(rod.x1*rod.x1+rod.x2*rod.x2);
oaf.feed(rod.e1);
//.feed(rod.x1*rod.x1/2/time);
//empyy.feed(rod.x2*rod.x2/2/time);
if (meanCount % 100000 == 0) {
//std::cout<<msd.getSEM()<<" "<<std::abs(targetMSD-msd.getMean());
std::cout << "\t" << oaf.getSEM() << " " << std::abs(targetOAF - oaf.getMean()) << std::endl;
//std::cout<<"\t"<<empxx.getSEM()<<" "<<std::abs(targetEMPXX-empxx.getMean());
//std::cout<<"\t"<<empyy.getSEM()<<" "<<std::abs(targetEMPYY-empyy.getMean())<<std::endl;;
}
if (meanCount % 1000000 == 0) {
std::ofstream fileOAF(filename + "_length=" + std::to_string(L) + "_dt=" + std::to_string(rod.deltaT) + "_OAF.out");
fileOAF << rod.deltaT << "\t" << std::abs(targetOAF - oaf.getMean()) << "\t" << oaf.getSEM() << "\n";
fileOAF.close();
}
meanCount++;
}
std::ofstream fileOAF(filename + "_length=" + std::to_string(L) + "_dt=" + std::to_string(rod.deltaT) + "_OAF.out");
fileOAF << rod.deltaT << "\t" << std::abs(targetOAF - oaf.getMean()) << "\t" << oaf.getSEM() << "\n";
fileOAF.close();
}
#endif// SIMULATION2D_HPP

View File

@ -1,72 +0,0 @@
#include <random>
#include <span>
#include <string>
#include "legacy/Integratoren.hpp"
#include "legacy/Simulation2d.hpp"
const int seed = 12345;
[[maybe_unused]] void overTime(int sim)
{
const std::vector<double> Length = { 1.0, 1.3974, 20.0 };
const int numCases = 5;
int i = 0;
for (auto L : Length) {
if (sim == numCases * i) {
simulate<Integratoren::integrateITOEuler_1>(L, seed, "1");
}
if (sim == numCases * i + 1) {
simulate<Integratoren::integrateITOHeun_2>(L, seed, "2");
}
if (sim == numCases * i + 2) {
simulate<Integratoren::integrateExact_3>(L, seed, "3");
}
if (sim == numCases * i + 3) {
simulate<Integratoren::integrateBDAS_4>(L, seed, "4");
}
if (sim == numCases * i + 4) {
simulate<Integratoren::integrateMBD_5>(L, seed, "5");
}
i++;
}
}
[[maybe_unused]]void konvergenz(int sim)
{
const std::vector<double> Length = { 1.0, 1.3974, 20.0 };
const std::vector<double> DELTAT = { 2.0, 1.0, 0.5, 0.25, 0.2, 0.1, 0.05, 0.025, 0.02, 0.01, 0.005, 0.0025, 0.200, 0.001, 0.0005, 0.00025 };
int i = 0;
for (auto dt : DELTAT) {
for (auto L : Length) {
if (sim == i++) {
konvergenz<Integratoren::integrateITOEuler_1>(L, seed, dt, "1");
}
if (sim == i++) {
konvergenz<Integratoren::integrateITOHeun_2>(L, seed, dt, "2");
}
if (sim == i++) {
konvergenz<Integratoren::integrateExact_3>(L, seed, dt, "3");
}
if (sim == i++) {
konvergenz<Integratoren::integrateBDAS_4>(L, seed, dt, "4");
}
if (sim == i++) {
konvergenz<Integratoren::integrateMBD_5>(L, seed, dt, "5");
}
}
}
}
int main(int argc, char *argv[])
{
int sim;
auto args = std::span(argv, size_t(argc));
if (argc > 1) {
sim = std::stoi(args[1]) - 1;
} else {
sim = 0;
}
overTime(sim);
//konvergenz(sim);
return 0;
}

View File

@ -3,49 +3,49 @@
//
#include <iostream>
#include "Calculation.h"
#include "Integratoren2d_forceless.h"
#include "Integratoren2d_force.h"
#include "Integratoren2d_forceless.h"
int main() {
constexpr int numStep = 1000;
auto zero_Force = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> Eigen::Vector2d { return {0.0, 0.0}; };
auto zero_Torque = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> double { return 0.0; };
/* auto euler_Zero = [&](Rod2d &rod, Simulation &sim) {
return Integratoren2d_force::Set1_Euler(rod, sim, zero_Force, zero_Torque);
};*/
auto heun_Zero = [&](Rod2d &rod, Simulation &sim) {
return Integratoren2d_force::Set2_Heun(rod, sim, zero_Force, zero_Torque);
constexpr int numStep = 10000000;
constexpr double k = 0.01;
[[maybe_unused]] auto harmonic_Force =
[](const Eigen::Vector2d &pos,
const Eigen::Vector2d & /*torque*/) -> Eigen::Vector2d {
return -k * pos;
};
/*auto exact_Zero = [&](Rod2d &rod, Simulation &sim) {
return Integratoren2d_force::Set3_Exact(rod, sim, zero_Force, zero_Torque);
};*//*
auto bdas_Zero = [&](Rod2d &rod, Simulation &sim) {
return Integratoren2d_force::Set4_BDAS(rod, sim, zero_Force, zero_Torque);
};*/
Calculation euler(heun_Zero, {{Compute::Type::msd, 1},
{Compute::Type::msd, 2},
{Compute::Type::msd, 4},
{Compute::Type::msd, 8},
{Compute::Type::msd, 16},
{Compute::Type::oaf, 1},
{Compute::Type::oaf, 2},
{Compute::Type::oaf, 4},
{Compute::Type::oaf, 8},
{Compute::Type::oaf, 16}}, 0.01, 12345);
[[maybe_unused]] auto zero_Force =
[](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> Eigen::Vector2d {
return {0.0, 0.0};
};
[[maybe_unused]] auto zero_Torque = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> double {
return 0.0;
};
constexpr Compute::Type compute = Compute::Type::oaf;
Calculation euler(Integratoren2d_force::Set2_Heun,
{{compute, 1},
{compute, 2},
{compute, 4},
{compute, 8},
{compute, 16},
{compute, 32},
{compute, 64},
{compute, 128},
{compute, 256},
{compute, 512},
{compute, 1024}},
0.01, 12345, zero_Force,zero_Torque,1.0);
euler.run(numStep);
for (const auto &com: euler.getComputes()) {
if (com.getType() != Compute::Type::msd)
continue;
std::cout << "MSD: " << com.getDifference() << " " << com.getAgg().getMean()
<< " <-> " << com.getTarget() << std::endl;
}
for (const auto &com: euler.getComputes()) {
if (com.getType() != Compute::Type::oaf)
continue;
std::cout << "OAF: " << com.getDifference() << " " << com.getAgg().getMean()
<< " <-> "<< com.getTarget() << std::endl;
for (const auto &com : euler.getComputes()) {
if (com.getType() != compute) { continue;
}
std::cout
<< com.getAgg().getMean() << " , " << com.getTarget()
<< std::endl;
}
}

13
src/vec_trafos.h Normal file
View File

@ -0,0 +1,13 @@
//
// Created by jholder on 10/25/21.
//
#pragma once
#include <Eigen/Dense>
inline static Eigen::Vector2d ortho(Eigen::Vector2d e) {
return Eigen::Vector2d{-e[1], e[0]};
}
inline static Eigen::Matrix2d rotation_Matrix(Eigen::Vector2d e) {
Eigen::Matrix2d mat;
mat << e[0], -e[1], e[1], e[0];
return mat;
}

View File

@ -1,5 +1,3 @@
#define CATCH_CONFIG_MAIN // This tells the catch header to generate a main
#define CATCH_CONFIG_MAIN // This tells the catch header to generate a main
#include <catch2/catch.hpp>

View File

@ -2,32 +2,41 @@
// Created by jholder on 22.10.21.
//
#include "Calculation.h"
#include <catch2/catch.hpp>
#include <Calculation.h>
#include "LiveAgg.hpp"
#include "Integratoren2d_forceless.h"
#include "LiveAgg.hpp"
TEST_CASE("Basic run of Calculation") {
Calculation euler(Integratoren2d_forceless::Set1_Euler, {{Compute::Type::msd, 10},
{Compute::Type::oaf, 10}}, 1, 1);
Calculation heun(Integratoren2d_forceless::Set2_Heun, {{Compute::Type::msd, 10},
{Compute::Type::oaf, 10}}, 1, 1);
Calculation exact(Integratoren2d_forceless::Set3_Exact, {{Compute::Type::msd, 10},
{Compute::Type::oaf, 10}}, 1, 1);
Calculation bdas(Integratoren2d_forceless::Set4_BDAS, {{Compute::Type::msd, 10},
{Compute::Type::oaf, 10}}, 1, 1);
Calculation euler(Integratoren2d_forceless::Set1_Euler,
{{Compute::Type::msd, 10}, {Compute::Type::oaf, 10}}, 1,
1);
Calculation heun(Integratoren2d_forceless::Set2_Heun,
{{Compute::Type::msd, 10}, {Compute::Type::oaf, 10}}, 1,
1);
Calculation exact(Integratoren2d_forceless::Set3_Exact,
{{Compute::Type::msd, 10}, {Compute::Type::oaf, 10}}, 1,
1);
Calculation bdas(Integratoren2d_forceless::Set4_BDAS,
{{Compute::Type::msd, 10}, {Compute::Type::oaf, 10}}, 1,
1);
SECTION("Euler") {
euler.run(100);
CHECK(euler.getRod().getE().norm() == Catch::Detail::Approx(1.0));
CHECK(euler.getComputes()[0].getType() == Compute::Type::msd);
CHECK(euler.getComputes()[1].getType() == Compute::Type::oaf);
}SECTION("Heun") {
}
SECTION("Heun") {
heun.run(100);
CHECK(heun.getRod().getE().norm() == Catch::Detail::Approx(1.0));
}SECTION("Exact") {
}
SECTION("Exact") {
exact.run(100);
CHECK(exact.getRod().getE().norm() == Catch::Detail::Approx(1.0));
}SECTION("Euler") {
}
SECTION("Euler") {
bdas.run(100);
CHECK(bdas.getRod().getE().norm() == Catch::Detail::Approx(1.0));
}
@ -36,17 +45,20 @@ TEST_CASE("Basic run of Calculation") {
euler.run(100);
CHECK(euler.getComputes()[0].getAgg().getNumPoints() == 10);
CHECK(euler.getComputes()[1].getAgg().getNumPoints() == 10);
}SECTION("Deterministic") {
}
SECTION("Deterministic") {
Calculation determ(Integratoren2d_forceless::Set0_deterministic,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 1, 1);
{{Compute::Type::msd, 1}, {Compute::Type::oaf, 1}},
1, 1);
determ.run(10);
auto time = 1;
auto targetMSD = pow(0.01, 2) * time;
auto targetOAF = cos(0.1);
CHECK(determ.getComputes()[0].getAgg().getMean() == Catch::Detail::Approx(targetMSD));
CHECK(determ.getComputes()[1].getAgg().getMean() == Catch::Detail::Approx(targetOAF));
CHECK(determ.getComputes()[0].getAgg().getMean() ==
Catch::Detail::Approx(targetMSD));
CHECK(determ.getComputes()[1].getAgg().getMean() ==
Catch::Detail::Approx(targetOAF));
}
}

View File

@ -2,19 +2,20 @@
// Created by jholder on 22.10.21.
//
#include <Compute.h>
#include "catch2/catch.hpp"
#include "Compute.h"
#include <catch2/catch.hpp>
#include "Integratoren2d_forceless.h"
TEST_CASE("Compute") {
Rod2d rod(1.0);
Simulation sim(0.1,1);
Simulation sim(0.1, 1);
auto com = Compute(rod, Compute::Type::msd, 10, sim);
SECTION("Mean of same values") {
for (int i = 0; i < 100; ++i) {
com.eval(rod);
}
CHECK(com.getAgg().getNumPoints()==10);
CHECK(com.getAgg().getMean()==0.0);
CHECK(com.getAgg().getNumPoints() == 10);
CHECK(com.getAgg().getMean() == 0.0);
}
}

View File

@ -1,89 +1,357 @@
//
// Created by jholder on 24.10.21.
//
#include "Calculation.h"
#include "Compute.h"
#include "Integratoren2d_force.h"
#include "Integratoren2d_forceless.h"
#include <catch2/catch.hpp>
#include <Integratoren2d_forceless.h>
#include <Calculation.h>
#include <Compute.h>
#include <Integratoren2d_force.h>
TEST_CASE("Forceless Integratoren") {
const size_t SEED = Catch::rngSeed();
auto force = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> Eigen::Vector2d { return {0.0, 0.0}; };
auto torque = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> double { return 0.0; };
const double length = GENERATE(1.0,1.4,2.0);
constexpr int steps = 10000;
constexpr double delta = 0.1;
Calculation euler(Integratoren2d_forceless::Set1_Euler,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,length);
euler.run(steps);
Calculation heun(Integratoren2d_forceless::Set2_Heun,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,length);
heun.run(steps);
Calculation exact(Integratoren2d_forceless::Set3_Exact,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,length);
exact.run(steps);
Calculation bdas(Integratoren2d_forceless::Set4_BDAS,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,length);
bdas.run(steps);
Calculation mbd(Integratoren2d_forceless::Set5_MBD,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,length);
mbd.run(steps);
SECTION("ForceLess Euler") {
CAPTURE(length);
size_t i = 0;
for (auto &c: euler.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("ForceLess Heun") {
CAPTURE(length);
size_t i = 0;
for (auto &c: heun.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("ForceLess Exact") {
CAPTURE(length);
size_t i = 0;
for (auto &c: exact.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("ForceLess BDAS") {
CAPTURE(length);
size_t i = 0;
for (auto &c: bdas.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("ForceLess MBD") {
CAPTURE(length);
size_t i = 0;
for (auto &c: mbd.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
[[maybe_unused]] auto zero_Force =
[](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> Eigen::Vector2d {
return {0.0, 0.0};
};
[[maybe_unused]] auto zero_Torque = [](const Eigen::Vector2d & /*pos*/,
const Eigen::Vector2d & /*torque*/) -> double {
return 0.0;
};
Calculation euler_zero(Integratoren2d_force::Set1_Euler,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,zero_Force,zero_Torque,length);
euler_zero.run(steps);
Calculation heun_zero(Integratoren2d_force::Set2_Heun,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,zero_Force,zero_Torque,length);
heun_zero.run(steps);
Calculation exact_zero(Integratoren2d_force::Set3_Exact,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,zero_Force,zero_Torque,length);
exact_zero.run(steps);
Calculation bdas_zero(Integratoren2d_force::Set4_BDAS,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,zero_Force,zero_Torque,length);
bdas_zero.run(steps);
Calculation mbd_zero(Integratoren2d_force::Set5_MBD,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED,zero_Force,zero_Torque,length);
mbd_zero.run(steps);
SECTION("Force Euler") {
CAPTURE(length);
size_t i = 0;
for (auto &c: euler_zero.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("Force Heun") {
CAPTURE(length);
size_t i = 0;
for (auto &c: heun_zero.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("Force Exact") {
CAPTURE(length);
size_t i = 0;
for (auto &c: exact_zero.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("Force BDAS") {
CAPTURE(length);
size_t i = 0;
for (auto &c: bdas_zero.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
SECTION("Force MBD") {
CAPTURE(length);
size_t i = 0;
for (auto &c: mbd_zero.getComputes()) {
CAPTURE(c);
CHECK(c.getDifference() <= delta*c.getAgg().getMean());
++i;
}
}
}
/*
SECTION("Euler") {
Calculation euler(Integratoren2d_forceless::Set1_Euler, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED);
{
euler.run(10000);
for (auto &c: euler.getComputes()) { CHECK(c.getDifference() <= 0.005); }
}
Calculation euler_force(Integratoren2d_force::Set1_Euler, {
{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED, force, torque);
Calculation euler_force(
Integratoren2d_force::Set1_Euler,
{{Compute::Type::msd, 1}, {Compute::Type::oaf, 1}}, 0.01, SEED,
force, torque);
{
euler_force.run(10000);
for (auto &c: euler_force.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : euler_force.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
CHECK(euler.getComputes()[0].getAgg().getMean() == euler_force.getComputes()[0].getAgg().getMean());
CHECK(euler.getComputes()[1].getAgg().getMean() == euler_force.getComputes()[1].getAgg().getMean());
}SECTION("Heun") {
Calculation heun(Integratoren2d_forceless::Set2_Heun, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED);
CHECK(euler.getComputes()[0].getAgg().getMean() ==
euler_force.getComputes()[0].getAgg().getMean());
CHECK(euler.getComputes()[1].getAgg().getMean() ==
euler_force.getComputes()[1].getAgg().getMean());
}
SECTION("Heun") {
Calculation heun(Integratoren2d_forceless::Set2_Heun,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED);
{
heun.run(10000);
for (auto &c: heun.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : heun.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
Calculation heun_force(Integratoren2d_force::Set2_Heun, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED, force,
torque);
Calculation heun_force(Integratoren2d_force::Set2_Heun,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED, force, torque);
{
heun_force.run(10000);
for (auto &c: heun_force.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : heun_force.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
CHECK(heun.getComputes()[0].getAgg().getMean() == heun_force.getComputes()[0].getAgg().getMean());
CHECK(heun.getComputes()[1].getAgg().getMean() == heun_force.getComputes()[1].getAgg().getMean());
}SECTION("Exact") {
Calculation exact(Integratoren2d_forceless::Set3_Exact, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED);
CHECK(heun.getComputes()[0].getAgg().getMean() ==
heun_force.getComputes()[0].getAgg().getMean());
CHECK(heun.getComputes()[1].getAgg().getMean() ==
heun_force.getComputes()[1].getAgg().getMean());
}
SECTION("Exact") {
Calculation exact(Integratoren2d_forceless::Set3_Exact,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED);
{
exact.run(10000);
for (auto &c: exact.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : exact.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
Calculation exact_force(Integratoren2d_force::Set3_Exact, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED, force,
torque);
Calculation exact_force(Integratoren2d_force::Set3_Exact,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED, force, torque);
{
exact_force.run(10000);
for (auto &c: exact_force.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : exact_force.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
CHECK(exact.getComputes()[0].getAgg().getMean() == Approx(exact_force.getComputes()[0].getAgg().getMean()).epsilon(1e-10));
CHECK(exact.getComputes()[1].getAgg().getMean() == exact_force.getComputes()[1].getAgg().getMean());
}SECTION("BDAS") {
Calculation bdas(Integratoren2d_forceless::Set4_BDAS, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED);
CHECK(exact.getComputes()[0].getAgg().getMean() ==
Approx(exact_force.getComputes()[0].getAgg().getMean())
.epsilon(1e-10));
CHECK(exact.getComputes()[1].getAgg().getMean() ==
exact_force.getComputes()[1].getAgg().getMean());
}
SECTION("BDAS") {
Calculation bdas(Integratoren2d_forceless::Set4_BDAS,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED);
{
bdas.run(10000);
for (auto &c: bdas.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : bdas.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
Calculation bdas_force(Integratoren2d_force::Set4_BDAS, {{Compute::Type::msd, 1},
{Compute::Type::oaf, 1}}, 0.01, SEED, force,
torque);
Calculation bdas_force(Integratoren2d_force::Set4_BDAS,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED, force, torque);
{
bdas_force.run(10000);
for (auto &c: bdas_force.getComputes()) { CHECK(c.getDifference() <= 0.005); }
for (auto &c : bdas_force.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
CHECK(bdas.getComputes()[0].getAgg().getMean() == bdas_force.getComputes()[0].getAgg().getMean());
CHECK(bdas.getComputes()[1].getAgg().getMean() == bdas_force.getComputes()[1].getAgg().getMean());
CHECK(bdas.getComputes()[0].getAgg().getMean() ==
Approx(bdas_force.getComputes()[0].getAgg().getMean())
.epsilon(10e-10));
CHECK(bdas.getComputes()[1].getAgg().getMean() ==
Approx(bdas_force.getComputes()[1].getAgg().getMean())
.epsilon(10e-10));
}
SECTION("MBD") {
Calculation mbd(Integratoren2d_forceless::Set5_MBD,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED);
{
mbd.run(10000);
for (auto &c : mbd.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
Calculation mbd_force(Integratoren2d_force::Set5_MBD,
{{Compute::Type::msd, 1},
{Compute::Type::oaf, 1},
{Compute::Type::empxx, 1},
{Compute::Type::empyy, 1}},
0.01, SEED, force, torque);
{
mbd_force.run(10000);
for (auto &c : mbd_force.getComputes()) {
CHECK(c.getDifference() <= 0.005);
}
}
CHECK(mbd.getComputes()[0].getAgg().getMean() ==
Approx(mbd_force.getComputes()[0].getAgg().getMean())
.epsilon(10e-10));
CHECK(mbd.getComputes()[1].getAgg().getMean() ==
Approx(mbd_force.getComputes()[1].getAgg().getMean())
.epsilon(10e-10));
}
}
*/

View File

@ -3,14 +3,15 @@
//
#include <catch2/catch.hpp>
#include "LiveAgg.hpp"
TEST_CASE("LiveAgg") {
auto ag = LiveAgg();
SECTION("Mean of same values"){
SECTION("Mean of same values") {
ag.feed(1.0);
ag.feed(1.0);
REQUIRE(ag.getMean()==1.0);
REQUIRE(ag.getNumPoints()==2);
REQUIRE(ag.getMean() == 1.0);
REQUIRE(ag.getNumPoints() == 2);
}
}

View File

@ -2,10 +2,11 @@
// Created by jholder on 21.10.21.
//
#include "Rod2d.hpp"
#include <catch2/catch.hpp>
#include <Eigen/Dense>
#include <catch2/catch.hpp>
#include "Rod2d.hpp"
#include "vec_trafos.h"
TEST_CASE("Rods") {
Rod2d sphere(1);
Rod2d rod(2);
@ -14,34 +15,19 @@ TEST_CASE("Rods") {
auto newPos = rod.getPos();
REQUIRE(newPos[0] == 1);
REQUIRE(newPos[1] == -1);
REQUIRE(sphere.getDiff_Sqrt()(0,0) == 1.0);
REQUIRE(sphere.getDiff_Sqrt()(0,1) == 0.0);
REQUIRE(sphere.getDiff_Sqrt()(1,0) == 0.0);
REQUIRE(sphere.getDiff_Sqrt()(1,1) == 1.0);
}SECTION("Checking rotation") {
SECTION("Forwards == e 90"){
//
// =====
//
rod.setE({0, 1}); // Lab system is 90 degree rotated
auto test = Eigen::Vector2d ({1,0});
auto erg = (rod.getE_Base_matrix()*test).normalized();
REQUIRE(sphere.getDiff_Sqrt()(0, 0) == 1.0);
REQUIRE(sphere.getDiff_Sqrt()(0, 1) == 0.0);
REQUIRE(sphere.getDiff_Sqrt()(1, 0) == 0.0);
REQUIRE(sphere.getDiff_Sqrt()(1, 1) == 1.0);
}
SECTION("Checking rotation") {
double f1 = GENERATE(take(10, random(-100, 100)));
double f2 = GENERATE(take(10, random(-100, 100)));
rod.setE(Eigen::Vector2d({f1, f2}).normalized());
auto test = Eigen::Vector2d({1, 0});
auto e = rod.getE();
auto erg = (rotation_Matrix(e) * test).normalized();
REQUIRE(erg.isApprox(e));
}
SECTION("Forwards == e 45"){
// o
// o
// o
rod.setE(Eigen::Vector2d ({1,1}).normalized()); // Lab system is 90 degree rotated
auto test = Eigen::Vector2d ({1,0});
auto erg = (rod.getE_Base_matrix()*test).normalized();
auto e = rod.getE();
REQUIRE(erg.isApprox(e));
}
}
}

View File

@ -3,25 +3,26 @@
//
#include <catch2/catch.hpp>
#include "Simulation.h"
TEST_CASE("Simulation") {
auto sim = Simulation(1,0);
REQUIRE(sim.getSTD()==sqrt(1*2.0));
SECTION("Symmetrie"){
auto sim = Simulation(1, 0);
REQUIRE(sim.getSTD() == sqrt(1 * 2.0));
SECTION("Symmetrie") {
constexpr int num = 10000000;
double sum = 0.0;
for (int i = 0; i < num; ++i) {
sum += sim.getNorm(1);
}
CHECK(sum/num == Catch::Detail::Approx(0.0).margin(0.001));
CHECK(sum / num == Catch::Detail::Approx(0.0).margin(0.001));
}
SECTION("STD"){
SECTION("STD") {
constexpr int num = 10000000;
double sum = 0.0;
for (int i = 0; i < num; ++i) {
sum += pow(sim.getNorm(1),2);
sum += pow(sim.getNorm(1), 2);
}
CHECK(sum/num == Catch::Detail::Approx(1.0).margin(0.001));
CHECK(sum / num == Catch::Detail::Approx(1.0).margin(0.001));
}
}