Refactoring

This commit is contained in:
iasonmanolas 2021-07-28 18:38:05 +03:00
parent 3c879db90f
commit cbb3a9fd26
8 changed files with 352 additions and 3133 deletions

View File

@ -24,6 +24,7 @@ download_project(PROJ vcglib_devel
PREFIX ${EXTERNAL_DEPS_DIR} PREFIX ${EXTERNAL_DEPS_DIR}
${UPDATE_DISCONNECTED_IF_AVAILABLE} ${UPDATE_DISCONNECTED_IF_AVAILABLE}
) )
add_subdirectory(${vcglib_devel_SOURCE_DIR} ${vcglib_devel_BINARY_DIR})
##matplot++ lib ##matplot++ lib
download_project(PROJ MATPLOTPLUSPLUS download_project(PROJ MATPLOTPLUSPLUS
@ -50,6 +51,7 @@ download_project(PROJ TBB
PREFIX ${EXTERNAL_DEPS_DIR} PREFIX ${EXTERNAL_DEPS_DIR}
${UPDATE_DISCONNECTED_IF_AVAILABLE} ${UPDATE_DISCONNECTED_IF_AVAILABLE}
) )
option(TBB_BUILD_TESTS "Build TBB tests and enable testing infrastructure" OFF)
add_subdirectory(${TBB_SOURCE_DIR} ${TBB_BINARY_DIR}) add_subdirectory(${TBB_SOURCE_DIR} ${TBB_BINARY_DIR})
link_directories(${TBB_BINARY_DIR}) link_directories(${TBB_BINARY_DIR})
message(${TBB_BINARY_DIR}) message(${TBB_BINARY_DIR})
@ -64,7 +66,6 @@ endif(MSVC)
#link_directories(${CMAKE_CURRENT_LIST_DIR}/boost_graph/libs) #link_directories(${CMAKE_CURRENT_LIST_DIR}/boost_graph/libs)
file(GLOB MySourcesFiles ${CMAKE_CURRENT_LIST_DIR}/*.hpp ${CMAKE_CURRENT_LIST_DIR}/*.cpp) file(GLOB MySourcesFiles ${CMAKE_CURRENT_LIST_DIR}/*.hpp ${CMAKE_CURRENT_LIST_DIR}/*.cpp)
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ltbb")
add_library(${PROJECT_NAME} ${MySourcesFiles} ${vcglib_devel_SOURCE_DIR}/wrap/ply/plylib.cpp) add_library(${PROJECT_NAME} ${MySourcesFiles} ${vcglib_devel_SOURCE_DIR}/wrap/ply/plylib.cpp)

View File

@ -1,4 +1,5 @@
#include "drmsimulationmodel.hpp" #include "drmsimulationmodel.hpp"
#include "linearsimulationmodel.hpp"
#include "simulationhistoryplotter.hpp" #include "simulationhistoryplotter.hpp"
#include <Eigen/Geometry> #include <Eigen/Geometry>
#include <algorithm> #include <algorithm>
@ -222,7 +223,6 @@ void DRMSimulationModel::reset()
mCurrentSimulationStep = 0; mCurrentSimulationStep = 0;
history.clear(); history.clear();
constrainedVertices.clear(); constrainedVertices.clear();
isRigidSupport.clear();
pMesh.reset(); pMesh.reset();
plotYValues.clear(); plotYValues.clear();
plotHandle.reset(); plotHandle.reset();
@ -810,7 +810,9 @@ void DRMSimulationModel::updateResidualForcesOnTheFly(
//#pragma omp parallel for schedule(static) num_threads(5) //#pragma omp parallel for schedule(static) num_threads(5)
//#endif //#endif
std::for_each( std::for_each(
#ifdef ENABLE_PARALLEL_DRM
std::execution::par_unseq, std::execution::par_unseq,
#endif
pMesh->edge.begin(), pMesh->edge.begin(),
pMesh->edge.end(), pMesh->edge.end(),
[&](const EdgeType &e) [&](const EdgeType &e)
@ -828,7 +830,6 @@ void DRMSimulationModel::updateResidualForcesOnTheFly(
const double theta1_jplus1 = ef.t1.dot(t3CrossN_jplus1); const double theta1_jplus1 = ef.t1.dot(t3CrossN_jplus1);
const double theta2_j = ef.t2.dot(t3CrossN_j); const double theta2_j = ef.t2.dot(t3CrossN_j);
const double theta2_jplus1 = ef.t2.dot(t3CrossN_jplus1); const double theta2_jplus1 = ef.t2.dot(t3CrossN_jplus1);
const bool shouldBreak = mCurrentSimulationStep == 12970;
const double theta3_j = computeTheta3(e, ev_j); const double theta3_j = computeTheta3(e, ev_j);
const double theta3_jplus1 = computeTheta3(e, ev_jplus1); const double theta3_jplus1 = computeTheta3(e, ev_jplus1);
// element.rotationalDisplacements_j.theta1 = theta1_j; // element.rotationalDisplacements_j.theta1 = theta1_j;
@ -856,8 +857,7 @@ void DRMSimulationModel::updateResidualForcesOnTheFly(
// #pragma omp parallel for schedule(static) num_threads(6) // #pragma omp parallel for schedule(static) num_threads(6)
for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) { for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) {
const bool isDofConstrainedFor_ev = isVertexConstrained[edgeNode.vi] const bool isDofConstrainedFor_ev = isVertexConstrained[edgeNode.vi]
&& fixedVertices.at(edgeNode.vi) && fixedVertices.at(edgeNode.vi).contains(dofi);
.contains(dofi);
if (!isDofConstrainedFor_ev) { if (!isDofConstrainedFor_ev) {
DifferentiateWithRespectTo dui{ev, dofi}; DifferentiateWithRespectTo dui{ev, dofi};
// Axial force computation // Axial force computation
@ -927,7 +927,7 @@ void DRMSimulationModel::updateResidualForcesOnTheFly(
const double secondBendingForce_inBracketsTerm_2 = theta3_j_deriv const double secondBendingForce_inBracketsTerm_2 = theta3_j_deriv
* theta3_jplus1; * theta3_jplus1;
////4th in bracket term ////4th in bracket term
const double secondBendingForce_inBracketsTerm_3 = 2 * theta3_jplus1_deriv const double secondBendingForce_inBracketsTerm_3 = theta3_jplus1_deriv * 2
* theta3_jplus1; * theta3_jplus1;
// 3rd term computation // 3rd term computation
const double secondBendingForce_inBracketsTerm const double secondBendingForce_inBracketsTerm
@ -1048,6 +1048,7 @@ void DRMSimulationModel::updateNodalExternalForces(
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices) const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices)
{ {
externalMomentsNorm = 0; externalMomentsNorm = 0;
double totalExternalForcesNorm = 0;
for (const std::pair<VertexIndex, Vector6d> &nodalForce : nodalForces) { for (const std::pair<VertexIndex, Vector6d> &nodalForce : nodalForces) {
const VertexIndex nodeIndex = nodalForce.first; const VertexIndex nodeIndex = nodalForce.first;
const bool isNodeConstrained = fixedVertices.contains(nodeIndex); const bool isNodeConstrained = fixedVertices.contains(nodeIndex);
@ -1085,7 +1086,10 @@ void DRMSimulationModel::updateNodalExternalForces(
} }
node.force.external = nodalExternalForce; node.force.external = nodalExternalForce;
totalExternalForcesNorm += node.force.external.norm();
} }
pMesh->totalExternalForcesNorm = totalExternalForcesNorm;
} }
void DRMSimulationModel::updateResidualForces() void DRMSimulationModel::updateResidualForces()
@ -1248,7 +1252,7 @@ void DRMSimulationModel::updateNodalMasses()
pMesh->nodes[v].mass_6d[DoF::Nx] = pMesh->nodes[v].mass.rotationalJ; pMesh->nodes[v].mass_6d[DoF::Nx] = pMesh->nodes[v].mass.rotationalJ;
pMesh->nodes[v].mass_6d[DoF::Ny] = pMesh->nodes[v].mass.rotationalI3; pMesh->nodes[v].mass_6d[DoF::Ny] = pMesh->nodes[v].mass.rotationalI3;
pMesh->nodes[v].mass_6d[DoF::Nr] = pMesh->nodes[v].mass.rotationalI2; pMesh->nodes[v].mass_6d[DoF::Nr] = pMesh->nodes[v].mass.rotationalI2;
if (mSettings.useViscousDamping) { if (mSettings.viscousDampingFactor.has_value()) {
//fill 6d damping vector //fill 6d damping vector
const double translationalDampingFactor const double translationalDampingFactor
= 2 * std::sqrt(translationalSumSk * pMesh->nodes[v].mass.translational); = 2 * std::sqrt(translationalSumSk * pMesh->nodes[v].mass.translational);
@ -1264,7 +1268,8 @@ void DRMSimulationModel::updateNodalMasses()
pMesh->nodes[v].damping_6d[DoF::Nr] = 2 pMesh->nodes[v].damping_6d[DoF::Nr] = 2
* std::sqrt(rotationalSumSk_I2 * std::sqrt(rotationalSumSk_I2
* pMesh->nodes[v].mass_6d[DoF::Nr]); * pMesh->nodes[v].mass_6d[DoF::Nr]);
pMesh->nodes[v].damping_6d = pMesh->nodes[v].damping_6d * 1e-3; pMesh->nodes[v].damping_6d = pMesh->nodes[v].damping_6d
* mSettings.viscousDampingFactor.value();
} }
assert(std::pow(mSettings.Dtini, 2.0) * translationalSumSk assert(std::pow(mSettings.Dtini, 2.0) * translationalSumSk
/ pMesh->nodes[v].mass.translational / pMesh->nodes[v].mass.translational
@ -1286,6 +1291,7 @@ void DRMSimulationModel::updateNodalAccelerations()
Node &node = pMesh->nodes[v]; Node &node = pMesh->nodes[v];
const VertexIndex vi = pMesh->getIndex(v); const VertexIndex vi = pMesh->getIndex(v);
node.acceleration = node.force.residual / node.mass_6d; node.acceleration = node.force.residual / node.mass_6d;
const bool shouldTrigger = mCurrentSimulationStep > 3500;
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
if (std::isnan(node.acceleration.norm())) { if (std::isnan(node.acceleration.norm())) {
std::cout << "acceleration " << vi << ":" << node.acceleration.toString() << std::endl; std::cout << "acceleration " << vi << ":" << node.acceleration.toString() << std::endl;
@ -1307,7 +1313,7 @@ void DRMSimulationModel::updateNodalVelocities()
for (VertexType &v : pMesh->vert) { for (VertexType &v : pMesh->vert) {
const VertexIndex vi = pMesh->getIndex(v); const VertexIndex vi = pMesh->getIndex(v);
Node &node = pMesh->nodes[v]; Node &node = pMesh->nodes[v];
if (mSettings.useViscousDamping) { if (mSettings.viscousDampingFactor.has_value()) {
const Vector6d massOverDt = node.mass_6d / Dt; const Vector6d massOverDt = node.mass_6d / Dt;
// const Vector6d visciousDampingFactor(viscuousDampingConstant / 2); // const Vector6d visciousDampingFactor(viscuousDampingConstant / 2);
const Vector6d &visciousDampingFactor = node.damping_6d; const Vector6d &visciousDampingFactor = node.damping_6d;
@ -1330,17 +1336,17 @@ void DRMSimulationModel::updateNodalVelocities()
void DRMSimulationModel::updateNodalDisplacements() void DRMSimulationModel::updateNodalDisplacements()
{ {
const bool shouldCapDisplacements = mSettings.displacementCap.has_value(); // const bool shouldCapDisplacements = mSettings.displacementCap.has_value();
for (VertexType &v : pMesh->vert) { for (VertexType &v : pMesh->vert) {
Node &node = pMesh->nodes[v]; Node &node = pMesh->nodes[v];
Vector6d stepDisplacement = node.velocity * Dt; Vector6d stepDisplacement = node.velocity * Dt;
if (shouldCapDisplacements // if (shouldCapDisplacements
&& stepDisplacement.getTranslation().norm() > mSettings.displacementCap) { // && stepDisplacement.getTranslation().norm() > mSettings.displacementCap) {
stepDisplacement = stepDisplacement // stepDisplacement = stepDisplacement
* (*mSettings.displacementCap // * (*mSettings.displacementCap
/ stepDisplacement.getTranslation().norm()); // / stepDisplacement.getTranslation().norm());
std::cout << "Displacement capped" << std::endl; // std::cout << "Displacement capped" << std::endl;
} // }
node.displacements = node.displacements + stepDisplacement; node.displacements = node.displacements + stepDisplacement;
// if (mSettings.isDebugMode && mSettings.beVerbose && pMesh->getIndex(v) == 40) { // if (mSettings.isDebugMode && mSettings.beVerbose && pMesh->getIndex(v) == 40) {
// std::cout << "Node " << node.vi << ":" << endl; // std::cout << "Node " << node.vi << ":" << endl;
@ -1432,7 +1438,7 @@ void DRMSimulationModel::updateNodeNormal(
* */ * */
const bool viHasMoments = node.force.external[3] != 0 || node.force.external[4] != 0; const bool viHasMoments = node.force.external[3] != 0 || node.force.external[4] != 0;
if (!checkedForMaximumMoment && viHasMoments) { if (!checkedForMaximumMoment && viHasMoments) {
mSettings.shouldUseTranslationalKineticEnergyThreshold = true; mSettings.totalTranslationalKineticEnergyThreshold = 1e-8;
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
std::cout << "Maximum moment reached.The Kinetic energy of the system will " std::cout << "Maximum moment reached.The Kinetic energy of the system will "
"be used as a convergence criterion" "be used as a convergence criterion"
@ -1865,9 +1871,16 @@ void DRMSimulationModel::draw(const std::string &screenshotsFolder)
// instead of full width. Must have // instead of full width. Must have
// matching PopItemWidth() below. // matching PopItemWidth() below.
ImGui::InputInt("Simulation debug step", static int debugModeStep = mSettings.debugModeStep.has_value()
&mSettings.debugModeStep); // set a int variable ? mSettings.debugModeStep.value()
mSettings.drawingStep = mSettings.debugModeStep; : 0;
if (ImGui::InputInt("Simulation debug step",
&debugModeStep)) { // set a int variable
if (debugModeStep != 0) {
*mSettings.debugModeStep = debugModeStep;
}
}
// mSettings.drawingStep = mSettings.debugModeStep;
ImGui::Checkbox("Enable drawing", ImGui::Checkbox("Enable drawing",
&mSettings.shouldDraw); // set a int variable &mSettings.shouldDraw); // set a int variable
ImGui::Text("Number of simulation steps: %zu", mCurrentSimulationStep); ImGui::Text("Number of simulation steps: %zu", mCurrentSimulationStep);
@ -2059,6 +2072,43 @@ void DRMSimulationModel::applySolutionGuess(const SimulationResults &solutionGue
// //} // //}
// polyscope::show(); // polyscope::show();
} }
void DRMSimulationModel::applyKineticDamping(const std::shared_ptr<SimulationJob> &pJob)
{
// if (!mSettings.viscousDampingFactor.has_value()) {
// const bool shouldCapDisplacements = mSettings.displacementCap.has_value();
for (VertexType &v : pMesh->vert) {
Node &node = pMesh->nodes[v];
Vector6d stepDisplacement = node.velocity * 0.5 * Dt;
// if (shouldCapDisplacements
// && stepDisplacement.getTranslation().norm() > mSettings.displacementCap) {
// stepDisplacement = stepDisplacement
// * (*mSettings.displacementCap
// / stepDisplacement.getTranslation().norm());
// }
node.displacements = node.displacements - stepDisplacement;
}
applyDisplacements(constrainedVertices);
if (!pJob->nodalForcedDisplacements.empty()) {
applyForcedDisplacements(
pJob->nodalForcedDisplacements);
}
updateElementalLengths();
// }
// const double triggerPercentage = 0.01;
// const double xi_min = 0.55;
// const double xi_init = 0.9969;
// if (mSettings.totalResidualForcesNormThreshold / pMesh->totalResidualForcesNorm
// > triggerPercentage) {
// mSettings.xi = ((xi_min - xi_init)
// * (mSettings.totalResidualForcesNormThreshold
// / pMesh->totalResidualForcesNorm)
// + xi_init - triggerPercentage * xi_min)
// / (1 - triggerPercentage);
// }
resetVelocities();
++numOfDampings;
}
SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<SimulationJob> &pJob, SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<SimulationJob> &pJob,
const Settings &settings, const Settings &settings,
@ -2107,7 +2157,7 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
} }
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
if (mSettings.shouldDraw || mSettings.isDebugMode) { if (mSettings.shouldDraw || mSettings.debugModeStep.has_value()) {
PolyscopeInterface::init(); PolyscopeInterface::init();
polyscope::registerCurveNetwork(meshPolyscopeLabel, polyscope::registerCurveNetwork(meshPolyscopeLabel,
pMesh->getEigenVertices(), pMesh->getEigenVertices(),
@ -2125,35 +2175,44 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
} }
updateElementalFrames(); updateElementalFrames();
if (!solutionGuess.displacements.empty()) { if (!solutionGuess.displacements.empty()) {
//#ifdef POLYSCOPE_DEFINED assert(!mSettings.linearGuessForceScaleFactor.has_value());
// if (mSettings.shouldDraw || mSettings.isDebugMode) {
// solutionGuess.registerForDrawing();
// polyscope::show();
// solutionGuess.unregister();
// }
//#endif
applySolutionGuess(solutionGuess, pJob); applySolutionGuess(solutionGuess, pJob);
shouldTemporarilyDampForces = true; shouldTemporarilyDampForces = true;
// Dt = mSettings.Dtini * 0.9; }
if (mSettings.linearGuessForceScaleFactor.has_value()) {
const double forceScaleFactor = 1;
for (auto &externalForce : pJob->nodalExternalForces) {
externalForce.second = externalForce.second * forceScaleFactor;
}
LinearSimulationModel linearSimulationModel;
SimulationResults simulationResults_fullPatternLinearModel = linearSimulationModel
.executeSimulation(pJob);
// simulationResults_fullPatternLinearModel.save(fullResultsFolderPath);
for (auto &externalForce : pJob->nodalExternalForces) {
externalForce.second = externalForce.second / forceScaleFactor;
}
applySolutionGuess(simulationResults_fullPatternLinearModel, pJob);
shouldTemporarilyDampForces = true;
} }
updateNodalMasses(); updateNodalMasses();
std::unordered_map<VertexIndex, Vector6d> nodalExternalForces = pJob->nodalExternalForces; // std::unordered_map<VertexIndex, Vector6d> nodalExternalForces = pJob->nodalExternalForces;
double totalExternalForcesNorm = 0; // double totalExternalForcesNorm = 0;
// Vector6d sumOfExternalForces(0); // Vector6d sumOfExternalForces(0);
for (auto &nodalForce : nodalExternalForces) { // for (auto &nodalForce : nodalExternalForces) {
const double percentageOfExternalLoads = double(externalLoadStep) // const double percentageOfExternalLoads = double(externalLoadStep)
/ mSettings.desiredGradualExternalLoadsSteps; // / mSettings.desiredGradualExternalLoadsSteps;
nodalForce.second = nodalForce.second * percentageOfExternalLoads; // nodalForce.second = nodalForce.second * percentageOfExternalLoads;
totalExternalForcesNorm += nodalForce.second.norm(); // totalExternalForcesNorm += nodalForce.second.norm();
// sumOfExternalForces = sumOfExternalForces + nodalForce.second; // // sumOfExternalForces = sumOfExternalForces + nodalForce.second;
} // }
pMesh->totalExternalForcesNorm = totalExternalForcesNorm; updateNodalExternalForces(pJob->nodalExternalForces, constrainedVertices);
updateNodalExternalForces(nodalExternalForces, constrainedVertices); if (!pJob->nodalExternalForces.empty()) {
if (!nodalExternalForces.empty()) {
mSettings.totalResidualForcesNormThreshold mSettings.totalResidualForcesNormThreshold
= settings.totalExternalForcesNormPercentageTermination * totalExternalForcesNorm; = settings.totalExternalForcesNormPercentageTermination
* pMesh->totalExternalForcesNorm;
} else { } else {
mSettings.totalResidualForcesNormThreshold = 1e-3; mSettings.totalResidualForcesNormThreshold = 1e-3;
std::cout << "No forces setted default residual forces norm threshold" << std::endl; std::cout << "No forces setted default residual forces norm threshold" << std::endl;
@ -2161,9 +2220,9 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
if (mSettings.beVerbose) { if (mSettings.beVerbose) {
std::cout << "totalResidualForcesNormThreshold:" std::cout << "totalResidualForcesNormThreshold:"
<< mSettings.totalResidualForcesNormThreshold << std::endl; << mSettings.totalResidualForcesNormThreshold << std::endl;
if (mSettings.useAverage) { if (mSettings.averageResidualForcesCriterionThreshold.has_value()) {
std::cout << "average/extNorm threshold:" std::cout << "average/extNorm threshold:"
<< mSettings.averageResidualForcesCriterionThreshold << std::endl; << *mSettings.averageResidualForcesCriterionThreshold << std::endl;
} }
} }
const size_t movingAverageSampleSize = 200; const size_t movingAverageSampleSize = 200;
@ -2171,8 +2230,9 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
std::vector<double> percentageOfConvergence; std::vector<double> percentageOfConvergence;
// double residualForcesMovingAverageDerivativeMax = 0; // double residualForcesMovingAverageDerivativeMax = 0;
while (settings.maxDRMIterations == 0 || mCurrentSimulationStep < settings.maxDRMIterations) { while (!settings.maxDRMIterations.has_value()
if ((mSettings.isDebugMode && mCurrentSimulationStep == 50000)) { || mCurrentSimulationStep < settings.maxDRMIterations.value()) {
if ((mSettings.debugModeStep.has_value() && mCurrentSimulationStep == 50000)) {
// std::filesystem::create_directory("./PatternOptimizationNonConv"); // std::filesystem::create_directory("./PatternOptimizationNonConv");
// pJob->save("./PatternOptimizationNonConv"); // pJob->save("./PatternOptimizationNonConv");
// Dt = mSettings.Dtini; // Dt = mSettings.Dtini;
@ -2256,25 +2316,26 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
// pMesh->currentTotalPotentialEnergykN; // pMesh->currentTotalPotentialEnergykN;
// pMesh->currentTotalPotentialEnergykN = computeTotalPotentialEnergy() / 1000; // pMesh->currentTotalPotentialEnergykN = computeTotalPotentialEnergy() / 1000;
// timePerNodePerIterationHistor.push_back(timePerNodePerIteration); // timePerNodePerIterationHistor.push_back(timePerNodePerIteration);
if (mSettings.beVerbose && mSettings.isDebugMode if (mSettings.beVerbose && mSettings.debugModeStep.has_value()
&& mCurrentSimulationStep % mSettings.debugModeStep == 0) { && mCurrentSimulationStep % mSettings.debugModeStep.value() == 0) {
printCurrentState(); printCurrentState();
// auto t2 = std::chrono::high_resolution_clock::now(); // auto t2 = std::chrono::high_resolution_clock::now();
// const double executionTime_min // const double executionTime_min
// = std::chrono::duration_cast<std::chrono::minutes>(t2 - beginTime).count(); // = std::chrono::duration_cast<std::chrono::minutes>(t2 - beginTime).count();
// std::cout << "Execution time(min):" << executionTime_min << std::endl; // std::cout << "Execution time(min):" << executionTime_min << std::endl;
if (mSettings.useAverage) { if (mSettings.averageResidualForcesCriterionThreshold.has_value()) {
std::cout << "Best percentage of target (average):" std::cout << "Best percentage of target (average):"
<< 100 * mSettings.averageResidualForcesCriterionThreshold << 100 * mSettings.averageResidualForcesCriterionThreshold.value()
* totalExternalForcesNorm * pMesh->totalExternalForcesNorm * pMesh->VN()
/ (minTotalResidualForcesNorm / pMesh->VN()) / minTotalResidualForcesNorm
<< "%" << std::endl; << "%" << std::endl;
} } else {
std::cout << "Best percentage of target:" std::cout << "Best percentage of target:"
<< 100 * mSettings.totalExternalForcesNormPercentageTermination << 100 * mSettings.totalExternalForcesNormPercentageTermination
* totalExternalForcesNorm / minTotalResidualForcesNorm * pMesh->totalExternalForcesNorm / minTotalResidualForcesNorm
<< "%" << std::endl; << "%" << std::endl;
}
// SimulationResultsReporter::createPlot("Number of Steps", // SimulationResultsReporter::createPlot("Number of Steps",
// "Residual Forces mov aver", // "Residual Forces mov aver",
// history.residualForcesMovingAverage); // history.residualForcesMovingAverage);
@ -2287,25 +2348,28 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
// timePerNodePerIterationHistory); // timePerNodePerIterationHistory);
} }
if ((mSettings.shouldCreatePlots || mSettings.isDebugMode) && mCurrentSimulationStep != 0) { if ((mSettings.shouldCreatePlots || mSettings.debugModeStep.has_value())
&& mCurrentSimulationStep != 0) {
history.stepPulse(*pMesh); history.stepPulse(*pMesh);
percentageOfConvergence.push_back(100 * mSettings.totalResidualForcesNormThreshold percentageOfConvergence.push_back(100 * mSettings.totalResidualForcesNormThreshold
/ pMesh->totalResidualForcesNorm); / pMesh->totalResidualForcesNorm);
} }
if (mSettings.shouldCreatePlots && mSettings.isDebugMode if (mSettings.shouldCreatePlots && mSettings.debugModeStep.has_value()
&& mCurrentSimulationStep % mSettings.debugModeStep == 0) { && mCurrentSimulationStep % mSettings.debugModeStep.value() == 0) {
// SimulationResultsReporter::createPlot("Number of Steps", // SimulationResultsReporter::createPlot("Number of Steps",
// "Residual Forces mov aver deriv", // "Residual Forces mov aver deriv",
// movingAveragesDerivatives_norm); // movingAveragesDerivatives_norm);
SimulationResultsReporter::createPlot("Number of Steps",
"Residual Forces mov aver",
history.residualForcesMovingAverage);
// SimulationResultsReporter::createPlot("Number of Steps", // SimulationResultsReporter::createPlot("Number of Steps",
// "Log of Residual Forces", // "Residual Forces mov aver",
// history.logResidualForces, // history.residualForcesMovingAverage,
// {}, // {},
// history.redMarks); // history.redMarks);
SimulationResultsReporter::createPlot("Number of Steps",
"Log of Residual Forces",
history.logResidualForces,
{},
history.redMarks);
// SimulationResultsReporter::createPlot("Number of Steps", // SimulationResultsReporter::createPlot("Number of Steps",
// "Log of Kinetic energy", // "Log of Kinetic energy",
// history.kineticEnergy, // history.kineticEnergy,
@ -2330,8 +2394,8 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
} }
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
if (mSettings.shouldDraw && mSettings.isDebugMode if (mSettings.shouldDraw && mSettings.debugModeStep.has_value()
&& mCurrentSimulationStep % mSettings.drawingStep == 0) /* && && mCurrentSimulationStep % mSettings.debugModeStep.value() == 0) /* &&
currentSimulationStep > maxDRMIterations*/ currentSimulationStep > maxDRMIterations*/
{ {
@ -2355,21 +2419,35 @@ currentSimulationStep > maxDRMIterations*/
// std::cout << "Residual forces norm:" << mesh.totalResidualForcesNorm // std::cout << "Residual forces norm:" << mesh.totalResidualForcesNorm
// << std::endl; // << std::endl;
const bool fullfillsResidualForcesNormTerminationCriterion const bool fullfillsResidualForcesNormTerminationCriterion
= !mSettings.useAverage = !mSettings.averageResidualForcesCriterionThreshold.has_value()
&& pMesh->totalResidualForcesNorm / totalExternalForcesNorm && pMesh->totalResidualForcesNorm / pMesh->totalExternalForcesNorm
< mSettings.totalExternalForcesNormPercentageTermination; < mSettings.totalExternalForcesNormPercentageTermination;
const bool fullfillsAverageResidualForcesNormTerminationCriterion const bool fullfillsAverageResidualForcesNormTerminationCriterion
= mSettings.useAverage = mSettings.averageResidualForcesCriterionThreshold.has_value()
&& (pMesh->totalResidualForcesNorm / pMesh->VN()) / totalExternalForcesNorm && (pMesh->totalResidualForcesNorm / pMesh->VN()) / pMesh->totalExternalForcesNorm
< mSettings.averageResidualForcesCriterionThreshold; < mSettings.averageResidualForcesCriterionThreshold.value();
if ((fullfillsAverageResidualForcesNormTerminationCriterion
// Residual forces norm convergence
if (((pMesh->previousTotalKineticEnergy > pMesh->currentTotalKineticEnergy
|| fullfillsAverageResidualForcesNormTerminationCriterion
|| fullfillsResidualForcesNormTerminationCriterion) || fullfillsResidualForcesNormTerminationCriterion)
// && mCurrentSimulationStep > movingAverageSampleSize && numOfDampings > 0
&& (pJob->nodalForcedDisplacements.empty() && (pJob->nodalForcedDisplacements.empty()
|| mCurrentSimulationStep > mSettings.gradualForcedDisplacementSteps)) || mCurrentSimulationStep > mSettings.gradualForcedDisplacementSteps)) {
if (mSettings.beVerbose /*&& !mSettings.isDebugMode*/) {
std::cout << "Simulation converged." << std::endl;
printCurrentState();
if (fullfillsResidualForcesNormTerminationCriterion) {
std::cout << "Converged using residual forces norm threshold criterion"
<< std::endl;
} else if (fullfillsAverageResidualForcesNormTerminationCriterion) {
std::cout << "Converged using average residual forces norm threshold criterion"
<< std::endl;
}
}
break;
}
// Residual forces norm convergence
if ((pMesh->previousTotalKineticEnergy > pMesh->currentTotalKineticEnergy
// && mCurrentSimulationStep > movingAverageSampleSize
)
/* || (pMesh->totalResidualForcesNorm / mSettings.totalResidualForcesNormThreshold <= 1 /* || (pMesh->totalResidualForcesNorm / mSettings.totalResidualForcesNormThreshold <= 1
&& mCurrentSimulationStep > 1)*/ && mCurrentSimulationStep > 1)*/
/*|| /*||
@ -2378,110 +2456,66 @@ mesh->currentTotalPotentialEnergykN*/
/*|| mesh->currentTotalPotentialEnergykN < minPotentialEnergy*/) { /*|| mesh->currentTotalPotentialEnergykN < minPotentialEnergy*/) {
// if (pMesh->totalResidualForcesNorm < totalResidualForcesNormThreshold) { // if (pMesh->totalResidualForcesNorm < totalResidualForcesNormThreshold) {
const bool fullfillsKineticEnergyTerminationCriterion const bool fullfillsKineticEnergyTerminationCriterion
= mSettings.shouldUseTranslationalKineticEnergyThreshold = mSettings.totalTranslationalKineticEnergyThreshold.has_value()
&& pMesh->currentTotalTranslationalKineticEnergy && pMesh->currentTotalTranslationalKineticEnergy
< mSettings.totalTranslationalKineticEnergyThreshold < mSettings.totalTranslationalKineticEnergyThreshold.value()
&& mCurrentSimulationStep > 20 && numOfDampings > 0; && mCurrentSimulationStep > 20 && numOfDampings > 0;
const bool fullfillsMovingAverageNormTerminationCriterion // const bool fullfillsMovingAverageNormTerminationCriterion
= pMesh->residualForcesMovingAverage // = pMesh->residualForcesMovingAverage
< mSettings.residualForcesMovingAverageNormThreshold; // < mSettings.residualForcesMovingAverageNormThreshold;
/*pMesh->residualForcesMovingAverage < totalResidualForcesNormThreshold*/ /*pMesh->residualForcesMovingAverage < totalResidualForcesNormThreshold*/
const bool fullfillsMovingAverageDerivativeNormTerminationCriterion // const bool fullfillsMovingAverageDerivativeNormTerminationCriterion
= pMesh->residualForcesMovingAverageDerivativeNorm < 1e-4; // = pMesh->residualForcesMovingAverageDerivativeNorm < 1e-4;
const bool shouldTerminate const bool shouldTerminate = fullfillsKineticEnergyTerminationCriterion
= fullfillsKineticEnergyTerminationCriterion
// || fullfillsMovingAverageNormTerminationCriterion // || fullfillsMovingAverageNormTerminationCriterion
// || fullfillsMovingAverageDerivativeNormTerminationCriterion // || fullfillsMovingAverageDerivativeNormTerminationCriterion
|| fullfillsAverageResidualForcesNormTerminationCriterion ;
|| fullfillsResidualForcesNormTerminationCriterion; if (shouldTerminate) {
if (shouldTerminate && mCurrentSimulationStep > 100) {
if (mSettings.beVerbose /*&& !mSettings.isDebugMode*/) { if (mSettings.beVerbose /*&& !mSettings.isDebugMode*/) {
std::cout << "Simulation converged." << std::endl; std::cout << "Simulation converged." << std::endl;
printCurrentState(); printCurrentState();
if (fullfillsResidualForcesNormTerminationCriterion) { if (fullfillsKineticEnergyTerminationCriterion) {
std::cout << "Converged using residual forces norm threshold criterion"
<< std::endl;
} else if (fullfillsKineticEnergyTerminationCriterion) {
std::cout << "The kinetic energy of the system was " std::cout << "The kinetic energy of the system was "
" used as a convergence criterion" " used as a convergence criterion"
<< std::endl; << std::endl;
} else if (fullfillsMovingAverageNormTerminationCriterion) {
std::cout
<< "Converged using residual forces moving average derivative norm "
"threshold criterion"
<< std::endl;
} }
} }
if (mSettings.desiredGradualExternalLoadsSteps == externalLoadStep) { // if (mSettings.desiredGradualExternalLoadsSteps == externalLoadStep) {
break; break;
} else { // } else {
externalLoadStep++; // externalLoadStep++;
std::unordered_map<VertexIndex, Vector6d> nodalExternalForces // std::unordered_map<VertexIndex, Vector6d> nodalExternalForces
= pJob->nodalExternalForces; // = pJob->nodalExternalForces;
double totalExternalForcesNorm = 0; // double totalExternalForcesNorm = 0;
for (auto &nodalForce : nodalExternalForces) { // for (auto &nodalForce : nodalExternalForces) {
const double percentageOfExternalLoads // const double percentageOfExternalLoads
= double(externalLoadStep) / mSettings.desiredGradualExternalLoadsSteps; // = double(externalLoadStep) / mSettings.desiredGradualExternalLoadsSteps;
nodalForce.second = nodalForce.second * percentageOfExternalLoads; // nodalForce.second = nodalForce.second * percentageOfExternalLoads;
totalExternalForcesNorm += nodalForce.second.norm(); // totalExternalForcesNorm += nodalForce.second.norm();
} // }
updateNodalExternalForces(nodalExternalForces, constrainedVertices); // updateNodalExternalForces(nodalExternalForces, constrainedVertices);
if (!nodalExternalForces.empty()) { // if (!nodalExternalForces.empty()) {
mSettings.totalResidualForcesNormThreshold = 1e-2 * totalExternalForcesNorm; // mSettings.totalResidualForcesNormThreshold = 1e-2 * totalExternalForcesNorm;
} // }
if (mSettings.beVerbose) { // if (mSettings.beVerbose) {
std::cout << "totalResidualForcesNormThreshold:" // std::cout << "totalResidualForcesNormThreshold:"
<< mSettings.totalResidualForcesNormThreshold << std::endl; // << mSettings.totalResidualForcesNormThreshold << std::endl;
} // }
} // }
// } // }
} }
if (!mSettings.useViscousDamping) {
const bool shouldCapDisplacements = mSettings.displacementCap.has_value();
for (VertexType &v : pMesh->vert) {
Node &node = pMesh->nodes[v];
Vector6d stepDisplacement = node.velocity * 0.5 * Dt;
if (shouldCapDisplacements
&& stepDisplacement.getTranslation().norm() > mSettings.displacementCap) {
stepDisplacement = stepDisplacement
* (*mSettings.displacementCap
/ stepDisplacement.getTranslation().norm());
}
node.displacements = node.displacements - stepDisplacement;
}
applyDisplacements(constrainedVertices);
if (!pJob->nodalForcedDisplacements.empty()) {
applyForcedDisplacements(
pJob->nodalForcedDisplacements);
}
updateElementalLengths();
}
// const double triggerPercentage = 0.01;
// const double xi_min = 0.55;
// const double xi_init = 0.9969;
// if (mSettings.totalResidualForcesNormThreshold / pMesh->totalResidualForcesNorm
// > triggerPercentage) {
// mSettings.xi = ((xi_min - xi_init)
// * (mSettings.totalResidualForcesNormThreshold
// / pMesh->totalResidualForcesNorm)
// + xi_init - triggerPercentage * xi_min)
// / (1 - triggerPercentage);
// }
if (mSettings.useKineticDamping) { if (mSettings.useKineticDamping) {
resetVelocities(); applyKineticDamping(pJob);
}
Dt *= mSettings.xi; Dt *= mSettings.xi;
// if (mSettings.isDebugMode) {
// std::cout << Dt << std::endl;
// }
++numOfDampings;
if (mSettings.shouldCreatePlots) { if (mSettings.shouldCreatePlots) {
history.redMarks.push_back(mCurrentSimulationStep); history.redMarks.push_back(mCurrentSimulationStep);
} }
}
// if (mSettings.isDebugMode) {
// std::cout << Dt << std::endl;
// }
// std::cout << "Number of dampings:" << numOfDampings << endl; // std::cout << "Number of dampings:" << numOfDampings << endl;
// draw(); // draw();
} }
@ -2492,11 +2526,12 @@ mesh->currentTotalPotentialEnergykN*/
results.executionTime = std::chrono::duration_cast<std::chrono::seconds>(endTime - beginTime) results.executionTime = std::chrono::duration_cast<std::chrono::seconds>(endTime - beginTime)
.count(); .count();
if (mCurrentSimulationStep == settings.maxDRMIterations && mCurrentSimulationStep != 0) { if (settings.maxDRMIterations.has_value() && mCurrentSimulationStep == settings.maxDRMIterations
&& mCurrentSimulationStep != 0) {
if (mSettings.beVerbose) { if (mSettings.beVerbose) {
std::cout << "Did not reach equilibrium before reaching the maximum number " std::cout << "Did not reach equilibrium before reaching the maximum number "
"of DRM steps (" "of DRM steps ("
<< settings.maxDRMIterations << "). Breaking simulation" << std::endl; << settings.maxDRMIterations.value() << "). Breaking simulation" << std::endl;
} }
results.converged = false; results.converged = false;
} else if (std::isnan(pMesh->currentTotalKineticEnergy)) { } else if (std::isnan(pMesh->currentTotalKineticEnergy)) {
@ -2507,7 +2542,7 @@ mesh->currentTotalPotentialEnergykN*/
} }
// mesh.printVertexCoordinates(mesh.VN() / 2); // mesh.printVertexCoordinates(mesh.VN() / 2);
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
if (mSettings.shouldDraw && !mSettings.isDebugMode) { if (mSettings.shouldDraw && !mSettings.debugModeStep.has_value()) {
draw(); draw();
} }
#endif #endif
@ -2608,13 +2643,13 @@ mesh->currentTotalPotentialEnergykN*/
} }
} }
if (!mSettings.isDebugMode && mSettings.shouldCreatePlots) { if (!mSettings.debugModeStep.has_value() && mSettings.shouldCreatePlots) {
SimulationResultsReporter reporter; SimulationResultsReporter reporter;
reporter.reportResults({results}, "Results", pJob->pMesh->getLabel()); reporter.reportResults({results}, "Results", pJob->pMesh->getLabel());
} }
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
if (mSettings.shouldDraw || mSettings.isDebugMode) { if (mSettings.shouldDraw || mSettings.debugModeStep.has_value()) {
polyscope::removeCurveNetwork(meshPolyscopeLabel); polyscope::removeCurveNetwork(meshPolyscopeLabel);
polyscope::removeCurveNetwork("Initial_" + meshPolyscopeLabel); polyscope::removeCurveNetwork("Initial_" + meshPolyscopeLabel);
} }
@ -2623,18 +2658,103 @@ mesh->currentTotalPotentialEnergykN*/
return results; return results;
} }
bool DRMSimulationModel::Settings::save(const filesystem::__cxx11::path &folderPath) const void DRMSimulationModel::Settings::save(const std::filesystem::path &folderPath) const
{ {
bool returnValue = true;
std::filesystem::create_directories(folderPath); std::filesystem::create_directories(folderPath);
nlohmann::json json; nlohmann::json json;
json[jsonLabels.meshFilename]
= std::filesystem::relative(std::filesystem::path(meshFilename), json[jsonLabels.gamma] = gamma;
std::filesystem::path(jsonFilename).parent_path()) json[jsonLabels.shouldDraw] = shouldDraw ? "true" : "false";
.string(); json[jsonLabels.shouldCreatePlots] = shouldCreatePlots ? "true" : "false";
json[jsonLabels.beVerbose] = beVerbose ? "true" : "false";
json[jsonLabels.Dtini] = Dtini;
json[jsonLabels.xi] = xi;
if (maxDRMIterations.has_value()) {
json[jsonLabels.maxDRMIterations] = maxDRMIterations.value();
}
if (debugModeStep.has_value()) {
json[jsonLabels.debugModeStep] = debugModeStep.value();
}
if (totalTranslationalKineticEnergyThreshold.has_value()) {
json[jsonLabels.totalTranslationalKineticEnergyThreshold]
= totalTranslationalKineticEnergyThreshold.value();
}
if (averageResidualForcesCriterionThreshold.has_value()) {
json[jsonLabels.averageResidualForcesCriterionThreshold]
= averageResidualForcesCriterionThreshold.value();
}
if (averageResidualForcesCriterionThreshold.has_value()) {
json[jsonLabels.averageResidualForcesCriterionThreshold]
= averageResidualForcesCriterionThreshold.value();
}
if (linearGuessForceScaleFactor.has_value()) {
json[jsonLabels.linearGuessForceScaleFactor] = linearGuessForceScaleFactor.value();
}
const std::string jsonFilename = "drmSettings.json"; const std::string jsonFilename = "drmSettings.json";
std::ofstream jsonFile(std::filesystem::path(folderPath).append(jsonFilename)); std::ofstream jsonFile(std::filesystem::path(folderPath).append(jsonFilename));
jsonFile << json; jsonFile << json;
} }
bool DRMSimulationModel::Settings::load(const filesystem::__cxx11::path &filePath) const {} bool DRMSimulationModel::Settings::load(const std::filesystem::path &jsonFilePath)
{
if (!std::filesystem::exists(std::filesystem::path(jsonFilePath))) {
std::cerr << "The json file does not exist. Json file provided:" << jsonFilePath.string()
<< std::endl;
assert(false);
return false;
}
if (std::filesystem::path(jsonFilePath).extension() != ".json") {
std::cerr << "A json file is expected as input. The given file has the "
"following extension:"
<< std::filesystem::path(jsonFilePath).extension() << std::endl;
assert(false);
return false;
}
nlohmann::json json;
std::ifstream ifs(jsonFilePath.string());
ifs >> json;
if (json.contains(jsonLabels.shouldDraw)) {
shouldDraw = json.at(jsonLabels.shouldDraw) == "true" ? true : false;
}
if (json.contains(jsonLabels.beVerbose)) {
beVerbose = json.at(jsonLabels.beVerbose) == "true" ? true : false;
}
if (json.contains(jsonLabels.shouldCreatePlots)) {
shouldCreatePlots = json.at(jsonLabels.shouldCreatePlots) == "true" ? true : false;
}
if (json.contains(jsonLabels.Dtini)) {
Dtini = json.at(jsonLabels.Dtini);
}
if (json.contains(jsonLabels.xi)) {
xi = json.at(jsonLabels.xi);
}
if (json.contains(jsonLabels.maxDRMIterations)) {
maxDRMIterations = json.at(jsonLabels.maxDRMIterations);
}
if (json.contains(jsonLabels.debugModeStep)) {
debugModeStep = json.at(jsonLabels.debugModeStep);
}
if (json.contains(jsonLabels.totalTranslationalKineticEnergyThreshold)) {
totalTranslationalKineticEnergyThreshold = json.at(
jsonLabels.totalTranslationalKineticEnergyThreshold);
}
if (json.contains(jsonLabels.gamma)) {
gamma = json.at(jsonLabels.gamma);
}
if (json.contains(jsonLabels.averageResidualForcesCriterionThreshold)) {
averageResidualForcesCriterionThreshold = json.at(
jsonLabels.averageResidualForcesCriterionThreshold);
}
if (json.contains(jsonLabels.linearGuessForceScaleFactor)) {
linearGuessForceScaleFactor = json.at(jsonLabels.linearGuessForceScaleFactor);
}
return true;
}

File diff suppressed because it is too large Load Diff

View File

@ -26,7 +26,6 @@ public:
struct Settings struct Settings
{ {
// bool isDebugMode{false}; // bool isDebugMode{false};
std::optional<int> debugModeStep{0};
bool shouldDraw{false}; bool shouldDraw{false};
bool beVerbose{false}; bool beVerbose{false};
bool shouldCreatePlots{false}; bool shouldCreatePlots{false};
@ -35,22 +34,39 @@ public:
// double residualForcesMovingAverageNormThreshold{1e-8}; // double residualForcesMovingAverageNormThreshold{1e-8};
double Dtini{0.1}; double Dtini{0.1};
double xi{0.9969}; double xi{0.9969};
int maxDRMIterations{0};
std::optional<double> shouldUseTranslationalKineticEnergyThreshold; std::optional<double> shouldUseTranslationalKineticEnergyThreshold;
// int gradualForcedDisplacementSteps{50}; int gradualForcedDisplacementSteps{50};
// int desiredGradualExternalLoadsSteps{1}; // int desiredGradualExternalLoadsSteps{1};
double gamma{0.8}; double gamma{0.8};
std::optional<double> displacementCap;
double totalResidualForcesNormThreshold{1e-3}; double totalResidualForcesNormThreshold{1e-3};
double totalExternalForcesNormPercentageTermination{1e-3}; double totalExternalForcesNormPercentageTermination{1e-3};
std::optional<double> averageResidualForcesCriterionThreshold{1e-5}; std::optional<int> maxDRMIterations;
std::optional<int> debugModeStep;
std::optional<double> totalTranslationalKineticEnergyThreshold;
std::optional<double> averageResidualForcesCriterionThreshold;
std::optional<double> linearGuessForceScaleFactor;
Settings() {} Settings() {}
bool save(const std::filesystem::path &folderPath) const; void save(const std::filesystem::path &folderPath) const;
bool load(const std::filesystem::path &filePath) const; bool load(const std::filesystem::path &filePath);
bool useViscousDamping{false}; std::optional<double> viscousDampingFactor;
bool useKineticDamping{true}; bool useKineticDamping{true};
struct JsonLabels struct JsonLabels
{}; {
const std::string shouldDraw{"shouldDraw"};
const std::string beVerbose{"beVerbose"};
const std::string shouldCreatePlots{"shouldCreatePlots"};
const std::string Dtini{"DtIni"};
const std::string xi{"xi"};
const std::string maxDRMIterations{"maxIterations"};
const std::string debugModeStep{"debugModeStep"};
const std::string totalTranslationalKineticEnergyThreshold{
"totalTranslationaKineticEnergyThreshold"};
const std::string gamma{"gamma"};
const std::string averageResidualForcesCriterionThreshold{
"averageResidualForcesThreshold"};
const std::string linearGuessForceScaleFactor{"linearGuessForceScaleFactor"};
};
static JsonLabels jsonLabels;
}; };
private: private:
@ -65,7 +81,6 @@ private:
std::vector<double> plotYValues; std::vector<double> plotYValues;
size_t numOfDampings{0}; size_t numOfDampings{0};
int externalLoadStep{1}; int externalLoadStep{1};
const double viscuousDampingConstant{100};
std::vector<bool> isVertexConstrained; std::vector<bool> isVertexConstrained;
std::vector<bool> isRigidSupport; std::vector<bool> isRigidSupport;
double minTotalResidualForcesNorm{std::numeric_limits<double>::max()}; double minTotalResidualForcesNorm{std::numeric_limits<double>::max()};
@ -220,6 +235,8 @@ private:
void updateNodeNr(VertexType &v); void updateNodeNr(VertexType &v);
void applyKineticDamping(const std::shared_ptr<SimulationJob> &pJob);
public: public:
DRMSimulationModel(); DRMSimulationModel();
SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob, SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob,
@ -229,6 +246,8 @@ private:
static void runUnitTests(); static void runUnitTests();
}; };
inline DRMSimulationModel::Settings::JsonLabels DRMSimulationModel::Settings::jsonLabels;
template <typename PointType> PointType Cross(PointType p1, PointType p2) { template <typename PointType> PointType Cross(PointType p1, PointType p2) {
return p1 ^ p2; return p1 ^ p2;
} }

View File

@ -1,254 +0,0 @@
#ifndef BEAMFORMFINDER_HPP
#define BEAMFORMFINDER_HPP
#include "simulationmesh.hpp"
#include "matplot/matplot.h"
#include "simulation_structs.hpp"
#include <Eigen/Dense>
#include <filesystem>
#include <unordered_set>
struct SimulationJob;
enum DoF { Ux = 0, Uy, Uz, Nx, Ny, Nr, NumDoF };
using DoFType = int;
using EdgeType = VCGEdgeMesh::EdgeType;
using VertexType = VCGEdgeMesh::VertexType;
struct DifferentiateWithRespectTo {
const VertexType &v;
const DoFType &dofi;
};
class DRMSimulationModel
{
public:
struct Settings
{
bool isDebugMode{false};
int debugModeStep{100000};
bool shouldDraw{false};
bool beVerbose{false};
bool shouldCreatePlots{false};
int drawingStep{1};
double totalTranslationalKineticEnergyThreshold{1e-8};
double residualForcesMovingAverageDerivativeNormThreshold{1e-8};
double residualForcesMovingAverageNormThreshold{1e-8};
double Dtini{0.1};
double xi{0.9969};
int maxDRMIterations{0};
bool shouldUseTranslationalKineticEnergyThreshold{false};
int gradualForcedDisplacementSteps{50};
int desiredGradualExternalLoadsSteps{1};
double gamma{0.8};
std::optional<double> displacementCap;
double totalResidualForcesNormThreshold{1e-3};
double totalExternalForcesNormPercentageTermination{1e-3};
bool useAverage{false};
double averageResidualForcesCriterionThreshold{1e-5};
Settings() {}
bool useViscousDamping{false};
bool useKineticDamping{true};
};
private:
Settings mSettings;
double Dt{mSettings.Dtini};
bool checkedForMaximumMoment{false};
bool shouldTemporarilyDampForces{false};
bool shouldTemporarilyAmplifyForces{true};
double externalMomentsNorm{0};
size_t mCurrentSimulationStep{0};
matplot::line_handle plotHandle;
std::vector<double> plotYValues;
size_t numOfDampings{0};
int externalLoadStep{1};
<<<<<<< HEAD
const double viscuousDampingConstant{100};
=======
>>>>>>> master
std::vector<bool> isVertexConstrained;
std::vector<bool> isRigidSupport;
double minTotalResidualForcesNorm{std::numeric_limits<double>::max()};
const std::string meshPolyscopeLabel{"Simulation mesh"};
std::unique_ptr<SimulationMesh> pMesh;
std::unordered_map<VertexIndex, std::unordered_set<DoFType>> constrainedVertices;
SimulationHistory history;
// Eigen::Tensor<double, 4> theta3Derivatives;
// std::unordered_map<MyKeyType, double, key_hash> theta3Derivatives;
bool shouldApplyInitialDistortion = false;
void reset();
void updateNodalInternalForces(
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices);
void updateNodalExternalForces(
const std::unordered_map<VertexIndex, Vector6d> &nodalForces,
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices);
void updateResidualForces();
void updateRotationalDisplacements();
void updateElementalLengths();
void updateNodalMasses();
void updateNodalAccelerations();
void updateNodalVelocities();
void updateNodalDisplacements();
void applyForcedDisplacements(
const std::unordered_map<VertexIndex, Eigen::Vector3d> &nodalForcedDisplacements);
Vector6d computeElementTorsionalForce(const Element &element,
const Vector6d &displacementDifference,
const std::unordered_set<DoFType> &constrainedDof);
// BeamFormFinder::Vector6d computeElementFirstBendingForce(
// const Element &element, const Vector6d &displacementDifference,
// const std::unordered_set<gsl::index> &constrainedDof);
// BeamFormFinder::Vector6d computeElementSecondBendingForce(
// const Element &element, const Vector6d &displacementDifference,
// const std::unordered_set<gsl::index> &constrainedDof);
void updateKineticEnergy();
void resetVelocities();
SimulationResults computeResults(const std::shared_ptr<SimulationJob> &pJob);
void updateNodePosition(
VertexType &v,
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices);
void applyDisplacements(
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices);
#ifdef POLYSCOPE_DEFINED
void draw(const string &screenshotsFolder= {});
#endif
void
updateNodalInternalForce(Vector6d &nodalInternalForce,
const Vector6d &elementInternalForce,
const std::unordered_set<DoFType> &nodalFixedDof);
Vector6d computeElementInternalForce(
const Element &elem, const Node &n0, const Node &n1,
const std::unordered_set<DoFType> &n0ConstrainedDof,
const std::unordered_set<DoFType> &n1ConstrainedDof);
Vector6d computeElementAxialForce(const ::EdgeType &e) const;
VectorType computeDisplacementDifferenceDerivative(
const EdgeType &e, const DifferentiateWithRespectTo &dui) const;
double
computeDerivativeElementLength(const EdgeType &e,
const DifferentiateWithRespectTo &dui) const;
VectorType computeDerivativeT1(const EdgeType &e,
const DifferentiateWithRespectTo &dui) const;
VectorType
computeDerivativeOfNormal(const VertexType &v,
const DifferentiateWithRespectTo &dui) const;
VectorType computeDerivativeT3(const EdgeType &e,
const DifferentiateWithRespectTo &dui) const;
VectorType computeDerivativeT2(const EdgeType &e,
const DifferentiateWithRespectTo &dui) const;
double computeDerivativeTheta2(const EdgeType &e, const VertexIndex &evi,
const VertexIndex &dwrt_evi,
const DoFType &dwrt_dofi) const;
void updateElementalFrames();
VectorType computeDerivativeOfR(const EdgeType &e, const DifferentiateWithRespectTo &dui) const;
// bool isRigidSupport(const VertexType &v) const;
static double computeDerivativeOfNorm(const VectorType &x,
const VectorType &derivativeOfX);
static VectorType computeDerivativeOfCrossProduct(
const VectorType &a, const VectorType &derivativeOfA, const VectorType &b,
const VectorType &derivativeOfB);
double computeTheta3(const EdgeType &e, const VertexType &v);
double computeDerivativeTheta3(const EdgeType &e, const VertexType &v,
const DifferentiateWithRespectTo &dui) const;
double computeTotalPotentialEnergy();
void computeRigidSupports();
void updateNormalDerivatives();
void updateT1Derivatives();
void updateT2Derivatives();
void updateT3Derivatives();
void updateRDerivatives();
double computeDerivativeTheta1(const EdgeType &e, const VertexIndex &evi,
const VertexIndex &dwrt_evi,
const DoFType &dwrt_dofi) const;
// void updatePositionsOnTheFly(
// const std::unordered_map<VertexIndex,
// std::unordered_set<gsl::index>>
// &fixedVertices);
void updateResidualForcesOnTheFly(
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>>
&fixedVertices);
void updatePositionsOnTheFly(
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>>
&fixedVertices);
void updateNodeNormal(
VertexType &v,
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>>
&fixedVertices);
void applyForcedNormals(
const std::unordered_map<VertexIndex, VectorType> nodalForcedRotations);
void printCurrentState() const;
void printDebugInfo() const;
double computeTotalInternalPotentialEnergy();
void applySolutionGuess(const SimulationResults &solutionGuess,
const std::shared_ptr<SimulationJob> &pJob);
void updateNodeNr(VertexType &v);
public:
DRMSimulationModel();
SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob,
const Settings &settings = Settings(),
const SimulationResults &solutionGuess = SimulationResults());
static void runUnitTests();
};
template <typename PointType> PointType Cross(PointType p1, PointType p2) {
return p1 ^ p2;
}
inline size_t currentStep{0};
inline bool TriggerBreakpoint(const VertexIndex &vi, const EdgeIndex &ei,
const DoFType &dofi) {
const size_t numberOfVertices = 10;
const VertexIndex middleNodeIndex = numberOfVertices / 2;
// return vi == middleNodeIndex && dofi == 1;
return dofi == 1 && ((vi == 1 && ei == 0) || (vi == 9 && ei == 9));
}
inline bool TriggerBreakpoint(const VertexIndex &vi, const EdgeIndex &ei) {
const size_t numberOfVertices = 10;
const VertexIndex middleNodeIndex = numberOfVertices / 2;
return (vi == middleNodeIndex);
// return (vi == 0 || vi == numberOfVertices - 1) && currentStep == 1;
return (vi == 1 && ei == 0) || (vi == 9 && ei == 9);
}
#endif // BEAMFORMFINDER_HPP

View File

@ -377,10 +377,12 @@ void VCGEdgeMesh::printVertexCoordinates(const size_t &vi) const {
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
//TODO: make const getEigenVertices is not //TODO: make const getEigenVertices is not
polyscope::CurveNetwork *VCGEdgeMesh::registerForDrawing( polyscope::CurveNetwork *VCGEdgeMesh::registerForDrawing(
const std::optional<std::array<double, 3>> &desiredColor, const bool &shouldEnable) const std::optional<std::array<double, 3>> &desiredColor,
const double &desiredRadius,
const bool &shouldEnable)
{ {
PolyscopeInterface::init(); PolyscopeInterface::init();
const double drawingRadius = 0.002; const double drawingRadius = desiredRadius;
polyscope::CurveNetwork *polyscopeHandle_edgeMesh polyscope::CurveNetwork *polyscopeHandle_edgeMesh
= polyscope::registerCurveNetwork(label, getEigenVertices(), getEigenEdges()); = polyscope::registerCurveNetwork(label, getEigenVertices(), getEigenEdges());

View File

@ -84,6 +84,7 @@ public:
#ifdef POLYSCOPE_DEFINED #ifdef POLYSCOPE_DEFINED
polyscope::CurveNetwork *registerForDrawing( polyscope::CurveNetwork *registerForDrawing(
const std::optional<std::array<double, 3>> &desiredColor = std::nullopt, const std::optional<std::array<double, 3>> &desiredColor = std::nullopt,
const double &desiredRadius = 0.002,
const bool &shouldEnable = true); const bool &shouldEnable = true);
void unregister() const; void unregister() const;
void drawInitialFrames(polyscope::CurveNetwork *polyscopeHandle_initialMesh) const; void drawInitialFrames(polyscope::CurveNetwork *polyscopeHandle_initialMesh) const;

View File

@ -30,6 +30,7 @@ class PEdge : public vcg::Edge<PUsedTypes,
vcg::edge::VertexRef, vcg::edge::VertexRef,
vcg::edge::BitFlags, vcg::edge::BitFlags,
vcg::edge::EEAdj, vcg::edge::EEAdj,
vcg::edge::EFAdj,
vcg::edge::VEAdj, vcg::edge::VEAdj,
vcg::edge::EVAdj> vcg::edge::EVAdj>
{}; {};
@ -192,10 +193,10 @@ public:
// getVertices(); // getVertices();
// } // }
vcg::tri::UpdateTopology<VCGPolyMesh>::VertexEdge(*this); vcg::tri::UpdateTopology<VCGPolyMesh>::VertexEdge(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::EdgeEdge(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::FaceFace(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::VertexFace(*this); vcg::tri::UpdateTopology<VCGPolyMesh>::VertexFace(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::FaceFace(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::AllocateEdge(*this); vcg::tri::UpdateTopology<VCGPolyMesh>::AllocateEdge(*this);
vcg::tri::UpdateTopology<VCGPolyMesh>::EdgeEdge(*this);
// vcg::tri::UpdateTopology<VCGPolyMesh>::VertexFace(*this); // vcg::tri::UpdateTopology<VCGPolyMesh>::VertexFace(*this);
return true; return true;