Refactoring. Refactored Threed_beam such that it does not recompute the stiffenss matrix for each scenario during the optimization
This commit is contained in:
parent
66eb05b694
commit
1966207b4c
150
CMakeLists.txt
150
CMakeLists.txt
|
@ -1,4 +1,4 @@
|
|||
cmake_minimum_required(VERSION 2.8)
|
||||
cmake_minimum_required(VERSION 3.0)
|
||||
project(MySources)
|
||||
set(CMAKE_CXX_STANDARD 20)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
@ -19,27 +19,27 @@ file(MAKE_DIRECTORY ${EXTERNAL_DEPS_DIR})
|
|||
#message(${POLYSCOPE_ALREADY_COMPILED})
|
||||
|
||||
if(${USE_POLYSCOPE})
|
||||
download_project(PROJ POLYSCOPE
|
||||
GIT_REPOSITORY https://github.com/nmwsharp/polyscope.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${POLYSCOPE_SOURCE_DIR} ${POLYSCOPE_BINARY_DIR})
|
||||
add_compile_definitions(POLYSCOPE_DEFINED)
|
||||
download_project(PROJ POLYSCOPE
|
||||
GIT_REPOSITORY https://github.com/nmwsharp/polyscope.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${POLYSCOPE_SOURCE_DIR} ${POLYSCOPE_BINARY_DIR})
|
||||
endif()
|
||||
|
||||
#dlib
|
||||
set(DLIB_BIN_DIR ${CMAKE_CURRENT_BINARY_DIR}/dlib_bin)
|
||||
file(MAKE_DIRECTORY ${DLIB_BIN_DIR})
|
||||
download_project(PROJ DLIB
|
||||
GIT_REPOSITORY https://github.com/davisking/dlib.git
|
||||
GIT_TAG master
|
||||
BINARY_DIR ${DLIB_BIN_DIR}
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${DLIB_SOURCE_DIR} ${DLIB_BINARY_DIR})
|
||||
|
||||
##dlib
|
||||
#set(DLIB_BIN_DIR ${CMAKE_CURRENT_BINARY_DIR}/dlib_bin)
|
||||
#file(MAKE_DIRECTORY ${DLIB_BIN_DIR})
|
||||
#download_project(PROJ DLIB
|
||||
# GIT_REPOSITORY https://github.com/davisking/dlib.git
|
||||
# GIT_TAG master
|
||||
# BINARY_DIR ${DLIB_BIN_DIR}
|
||||
# PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
# ${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
#)
|
||||
#add_subdirectory(${DLIB_SOURCE_DIR} ${DLIB_BINARY_DIR})
|
||||
|
||||
##vcglib devel branch
|
||||
download_project(PROJ vcglib_devel
|
||||
|
@ -50,15 +50,6 @@ download_project(PROJ vcglib_devel
|
|||
)
|
||||
add_subdirectory(${vcglib_devel_SOURCE_DIR} ${vcglib_devel_BINARY_DIR})
|
||||
|
||||
##matplot++ lib
|
||||
download_project(PROJ MATPLOTPLUSPLUS
|
||||
GIT_REPOSITORY https://github.com/alandefreitas/matplotplusplus
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${MATPLOTPLUSPLUS_SOURCE_DIR} ${MATPLOTPLUSPLUS_BINARY_DIR})
|
||||
|
||||
##threed-beam-fea
|
||||
download_project(PROJ threed-beam-fea
|
||||
GIT_REPOSITORY https://github.com/IasonManolas/threed-beam-fea.git
|
||||
|
@ -68,17 +59,6 @@ download_project(PROJ threed-beam-fea
|
|||
)
|
||||
add_subdirectory(${threed-beam-fea_SOURCE_DIR} ${threed-beam-fea_BINARY_DIR})
|
||||
|
||||
##TBB
|
||||
download_project(PROJ TBB
|
||||
GIT_REPOSITORY https://github.com/wjakob/tbb.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
option(TBB_BUILD_TESTS "Build TBB tests and enable testing infrastructure" OFF)
|
||||
add_subdirectory(${TBB_SOURCE_DIR} ${TBB_BINARY_DIR})
|
||||
link_directories(${TBB_BINARY_DIR})
|
||||
|
||||
###Eigen 3 NOTE: Eigen is required on the system the code is ran
|
||||
find_package(Eigen3 3.3 REQUIRED)
|
||||
|
||||
|
@ -90,22 +70,100 @@ endif(MSVC)
|
|||
file(GLOB MySourcesFiles ${CMAKE_CURRENT_LIST_DIR}/*.hpp ${CMAKE_CURRENT_LIST_DIR}/*.cpp)
|
||||
add_library(${PROJECT_NAME} ${MySourcesFiles} ${vcglib_devel_SOURCE_DIR}/wrap/ply/plylib.cpp)
|
||||
|
||||
set(USE_TBB true)
|
||||
if(${USE_TBB})
|
||||
##TBB
|
||||
download_project(PROJ TBB
|
||||
GIT_REPOSITORY https://github.com/wjakob/tbb.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
option(TBB_BUILD_TESTS "Build TBB tests and enable testing infrastructure" OFF)
|
||||
option(TBB_BUILD_STATIC "Build TBB static library" ON)
|
||||
add_subdirectory(${TBB_SOURCE_DIR} ${TBB_BINARY_DIR})
|
||||
link_directories(${TBB_BINARY_DIR})
|
||||
if(${MYSOURCES_STATIC_LINK})
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC -static tbb_static)
|
||||
else()
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC tbb)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(USE_ENSMALLEN)
|
||||
##ENSMALLEN
|
||||
download_project(PROJ ENSMALLEN
|
||||
GIT_REPOSITORY https://github.com/mlpack/ensmallen.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${ENSMALLEN_SOURCE_DIR} ${ENSMALLEN_BINARY_DIR})
|
||||
|
||||
|
||||
set(ARMADILLO_SOURCE_DIR "/home/iason/Coding/Libraries/armadillo")
|
||||
add_subdirectory(${ARMADILLO_SOURCE_DIR} ${EXTERNAL_DEPS_DIR}/armadillo_build)
|
||||
if(${MYSOURCES_STATIC_LINK})
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC "-static" ensmallen ${EXTERNAL_DEPS_DIR}/armadillo_build/libarmadillo.a)
|
||||
else()
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC)
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC armadillo ensmallen)
|
||||
endif()
|
||||
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC ${ARMADILLO_SOURCE_DIR}/include)
|
||||
endif()
|
||||
|
||||
target_include_directories(${PROJECT_NAME}
|
||||
PUBLIC ${CMAKE_CURRENT_LIST_DIR}/boost_graph
|
||||
PUBLIC ${vcglib_devel_SOURCE_DIR}
|
||||
PUBLIC ${threed-beam-fea_SOURCE_DIR}
|
||||
PUBLIC ${MySourcesFiles}
|
||||
# PUBLIC ${MySourcesFiles}
|
||||
)
|
||||
|
||||
if(${MYSOURCES_STATIC_LINK})
|
||||
|
||||
if(${MYSOURCES_STATIC_LINK} AND NOT ${USE_POLYSCOPE})
|
||||
message("Linking statically")
|
||||
target_link_libraries(${PROJECT_NAME} -static Eigen3::Eigen matplot dlib::dlib ThreedBeamFEA ${TBB_BINARY_DIR}/libtbb_static.a pthread)
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE -static lapack blas gfortran quadmath pthread)
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC -static Eigen3::Eigen #[[dlib::dlib]] ThreedBeamFEA #[[${TBB_BINARY_DIR}/libtbb_static.a]])
|
||||
else()
|
||||
target_link_libraries(${PROJECT_NAME} Eigen3::Eigen matplot dlib::dlib ThreedBeamFEA tbb pthread)
|
||||
if(${USE_POLYSCOPE})
|
||||
target_link_libraries(${PROJECT_NAME} polyscope)
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE lapack blas gfortran quadmath pthread)
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC polyscope xcb Xau)
|
||||
target_include_directories(${PROJECT_NAME}
|
||||
PUBLIC ${POLYSCOPE_SOURCE_DIR}
|
||||
)
|
||||
endif()
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE pthread)
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC Eigen3::Eigen #[[dlib::dlib]] ThreedBeamFEA matplot)
|
||||
endif()
|
||||
|
||||
target_link_directories(MySources PUBLIC ${CMAKE_CURRENT_LIST_DIR}/boost_graph/libs)
|
||||
target_link_directories(${PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_LIST_DIR}/boost_graph/libs)
|
||||
|
||||
#set(USE_MATPLOT FALSE)
|
||||
#if(USE_MATPLOT)
|
||||
##matplot++ lib
|
||||
download_project(PROJ MATPLOTPLUSPLUS
|
||||
GIT_REPOSITORY https://github.com/alandefreitas/matplotplusplus
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${MATPLOTPLUSPLUS_SOURCE_DIR} ${MATPLOTPLUSPLUS_BINARY_DIR})
|
||||
# add_compile_definitions(MATPLOT_DEFINED)
|
||||
if(${MYSOURCES_STATIC_LINK})
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC "-static" matplot)
|
||||
else()
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC matplot)
|
||||
endif()
|
||||
#endif()
|
||||
|
||||
download_project(PROJ GSL
|
||||
GIT_REPOSITORY https://github.com/microsoft/GSL.git
|
||||
GIT_TAG master
|
||||
PREFIX ${EXTERNAL_DEPS_DIR}
|
||||
${UPDATE_DISCONNECTED_IF_AVAILABLE}
|
||||
)
|
||||
add_subdirectory(${GSL_SOURCE_DIR} ${GSL_BINARY_DIR})
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC GSL)
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC GSL)
|
||||
|
||||
|
|
33
csvfile.hpp
33
csvfile.hpp
|
@ -21,23 +21,24 @@ class csvFile {
|
|||
const std::string escape_seq_;
|
||||
const std::string special_chars_;
|
||||
|
||||
public:
|
||||
csvFile(const std::string filename, const bool &overwrite,
|
||||
public:
|
||||
csvFile(const std::filesystem::path &filename,
|
||||
const bool &overwrite,
|
||||
const std::string separator = ",")
|
||||
: fs_(), is_first_(true), separator_(separator), escape_seq_("\""),
|
||||
special_chars_("\"") {
|
||||
fs_.exceptions(std::ios::failbit | std::ios::badbit);
|
||||
if (filename.empty()) {
|
||||
fs_.copyfmt(std::cout);
|
||||
fs_.clear(std::cout.rdstate());
|
||||
fs_.basic_ios<char>::rdbuf(std::cout.rdbuf());
|
||||
} else {
|
||||
if (!std::filesystem::exists(std::filesystem::path(filename))) {
|
||||
std::ofstream outfile(filename);
|
||||
outfile.close();
|
||||
}
|
||||
overwrite ? fs_.open(filename, std::ios::trunc) : fs_.open(filename, std::ios::app);
|
||||
}
|
||||
: fs_(), is_first_(true), separator_(separator), escape_seq_("\""), special_chars_("\"")
|
||||
{
|
||||
fs_.exceptions(std::ios::failbit | std::ios::badbit);
|
||||
if (filename.empty()) {
|
||||
fs_.copyfmt(std::cout);
|
||||
fs_.clear(std::cout.rdstate());
|
||||
fs_.basic_ios<char>::rdbuf(std::cout.rdbuf());
|
||||
} else {
|
||||
if (!std::filesystem::exists(filename)) {
|
||||
std::ofstream outfile(filename);
|
||||
outfile.close();
|
||||
}
|
||||
overwrite ? fs_.open(filename, std::ios::trunc) : fs_.open(filename, std::ios::app);
|
||||
}
|
||||
}
|
||||
|
||||
~csvFile() {
|
||||
|
|
|
@ -217,28 +217,16 @@ void DRMSimulationModel::runUnitTests()
|
|||
|
||||
// polyscope::show();
|
||||
}
|
||||
|
||||
void DRMSimulationModel::reset(const std::shared_ptr<SimulationJob> &pJob, const Settings &settings)
|
||||
void DRMSimulationModel::reset(const std::shared_ptr<SimulationJob> &pJob)
|
||||
{
|
||||
mSettings = settings;
|
||||
mCurrentSimulationStep = 0;
|
||||
history.clear();
|
||||
history.label = pJob->pMesh->getLabel() + "_" + pJob->getLabel();
|
||||
constrainedVertices.clear();
|
||||
//#ifdef USE_ENSMALLEN
|
||||
// this->pJob = pJob;
|
||||
//#endif
|
||||
pMesh.reset();
|
||||
pMesh = std::make_unique<SimulationMesh>(*pJob->pMesh);
|
||||
vcg::tri::UpdateBounding<SimulationMesh>::Box(*pMesh);
|
||||
plotYValues.clear();
|
||||
plotHandle.reset();
|
||||
checkedForMaximumMoment = false;
|
||||
externalMomentsNorm = 0;
|
||||
Dt = settings.Dtini;
|
||||
numOfDampings = 0;
|
||||
shouldTemporarilyDampForces = false;
|
||||
externalLoadStep = 1;
|
||||
isVertexConstrained.clear();
|
||||
minTotalResidualForcesNorm = std::numeric_limits<double>::max();
|
||||
|
||||
constrainedVertices.clear();
|
||||
constrainedVertices = pJob->constrainedVertices;
|
||||
if (!pJob->nodalForcedDisplacements.empty()) {
|
||||
for (std::pair<VertexIndex, Eigen::Vector3d> viDisplPair : pJob->nodalForcedDisplacements) {
|
||||
|
@ -251,6 +239,26 @@ void DRMSimulationModel::reset(const std::shared_ptr<SimulationJob> &pJob, const
|
|||
for (auto fixedVertex : constrainedVertices) {
|
||||
isVertexConstrained[fixedVertex.first] = true;
|
||||
}
|
||||
}
|
||||
|
||||
void DRMSimulationModel::reset(const std::shared_ptr<SimulationJob> &pJob, const Settings &settings)
|
||||
{
|
||||
mSettings = settings;
|
||||
mCurrentSimulationStep = 0;
|
||||
history.clear();
|
||||
history.label = pJob->pMesh->getLabel() + "_" + pJob->getLabel();
|
||||
plotYValues.clear();
|
||||
plotHandle.reset();
|
||||
checkedForMaximumMoment = false;
|
||||
externalMomentsNorm = 0;
|
||||
Dt = settings.Dtini;
|
||||
numOfDampings = 0;
|
||||
shouldTemporarilyDampForces = false;
|
||||
externalLoadStep = 1;
|
||||
isVertexConstrained.clear();
|
||||
minTotalResidualForcesNorm = std::numeric_limits<double>::max();
|
||||
|
||||
reset(pJob);
|
||||
|
||||
#ifdef POLYSCOPE_DEFINED
|
||||
if (mSettings.shouldDraw || mSettings.debugModeStep.has_value()) {
|
||||
|
@ -2656,6 +2664,73 @@ SimulationResults DRMSimulationModel::executeSimulation(const std::shared_ptr<Si
|
|||
return results;
|
||||
}
|
||||
|
||||
//#ifdef USE_ENSMALLEN
|
||||
|
||||
//void DRMSimulationModel::setJob(const std::shared_ptr<SimulationJob> &pJob)
|
||||
//{
|
||||
// reset(pJob);
|
||||
|
||||
// updateNodalExternalForces(pJob->nodalExternalForces, constrainedVertices);
|
||||
// // arma::mat externalForces(pMesh->VN() * NumDoF);
|
||||
// // for (int vi = 0; vi < pMesh->VN(); vi++) {
|
||||
// // const Vector6d &nodeExternalForce = pMesh.vert[vi].node.externalForce;
|
||||
// // for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) {
|
||||
// // externalForces(vi * NumDoF + dofi) = nodeExternalForce[dofi];
|
||||
// // }
|
||||
// // }
|
||||
//}
|
||||
|
||||
//SimulationMesh *DRMSimulationModel::getDeformedMesh(const arma::mat &x)
|
||||
//{
|
||||
// for (int vi = 0; vi < pMesh->VN(); vi++) {
|
||||
// Node &node = pMesh->nodes[vi];
|
||||
// for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) {
|
||||
// node.displacements[dofi] = x(vi * DoF::NumDoF + dofi);
|
||||
// }
|
||||
// }
|
||||
|
||||
// applyDisplacements(constrainedVertices);
|
||||
// if (!pJob->nodalForcedDisplacements.empty()) {
|
||||
// applyForcedDisplacements(pJob->nodalForcedDisplacements);
|
||||
// }
|
||||
|
||||
// return pMesh.get();
|
||||
//}
|
||||
|
||||
//double DRMSimulationModel::EvaluateWithGradient(const arma::mat &x, arma::mat &g)
|
||||
//{
|
||||
// for (int vi = 0; vi < pMesh->VN(); vi++) {
|
||||
// Node &node = pMesh->nodes[vi];
|
||||
// for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) {
|
||||
// node.displacements[dofi] = x(vi * DoF::NumDoF + dofi);
|
||||
// }
|
||||
// }
|
||||
|
||||
// applyDisplacements(constrainedVertices);
|
||||
// if (!pJob->nodalForcedDisplacements.empty()) {
|
||||
// applyForcedDisplacements(pJob->nodalForcedDisplacements);
|
||||
// }
|
||||
// updateElementalLengths();
|
||||
// updateNormalDerivatives();
|
||||
// updateT1Derivatives();
|
||||
// updateRDerivatives();
|
||||
// updateT2Derivatives();
|
||||
// updateT3Derivatives();
|
||||
// updateResidualForcesOnTheFly(constrainedVertices);
|
||||
// for (int vi = 0; vi < pMesh->VN(); vi++) {
|
||||
// Node &node = pMesh->nodes[vi];
|
||||
// for (DoFType dofi = DoF::Ux; dofi < DoF::NumDoF; dofi++) {
|
||||
// g(vi * NumDoF + dofi) = node.force.residual[dofi];
|
||||
// }
|
||||
// }
|
||||
// mCurrentSimulationStep++;
|
||||
// const double PE = computeTotalPotentialEnergy();
|
||||
// std::cout << "PE:" << PE << std::endl;
|
||||
// return PE;
|
||||
//}
|
||||
|
||||
//#endif
|
||||
|
||||
void DRMSimulationModel::Settings::save(const std::filesystem::path &folderPath) const
|
||||
{
|
||||
std::filesystem::create_directories(folderPath);
|
||||
|
|
|
@ -1,13 +1,20 @@
|
|||
#ifndef BEAMFORMFINDER_HPP
|
||||
#define BEAMFORMFINDER_HPP
|
||||
|
||||
//#ifdef USE_MATPLOT
|
||||
#include "matplot/matplot.h"
|
||||
//#endif
|
||||
#include "simulationmesh.hpp"
|
||||
#include "simulationmodel.hpp"
|
||||
#include <Eigen/Dense>
|
||||
#include <filesystem>
|
||||
#include <unordered_set>
|
||||
|
||||
#ifdef USE_ENSMALLEN
|
||||
#include <armadillo>
|
||||
#include <ensmallen.hpp>
|
||||
#endif
|
||||
|
||||
struct SimulationJob;
|
||||
|
||||
enum DoF { Ux = 0, Uy, Uz, Nx, Ny, Nr, NumDoF };
|
||||
|
@ -94,7 +101,9 @@ private:
|
|||
// Eigen::Tensor<double, 4> theta3Derivatives;
|
||||
// std::unordered_map<MyKeyType, double, key_hash> theta3Derivatives;
|
||||
bool shouldApplyInitialDistortion = false;
|
||||
|
||||
//#ifdef USE_ENSMALLEN
|
||||
// std::shared_ptr<SimulationJob> pJob;
|
||||
//#endif
|
||||
void reset(const std::shared_ptr<SimulationJob> &pJob, const Settings &settings);
|
||||
void updateNodalInternalForces(
|
||||
const std::unordered_map<VertexIndex, std::unordered_set<DoFType>> &fixedVertices);
|
||||
|
@ -241,11 +250,19 @@ private:
|
|||
|
||||
virtual SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob);
|
||||
|
||||
void reset(const std::shared_ptr<SimulationJob> &pJob);
|
||||
|
||||
public:
|
||||
DRMSimulationModel();
|
||||
SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob,
|
||||
const Settings &settings,
|
||||
const SimulationResults &solutionGuess = SimulationResults());
|
||||
#ifdef USE_ENSMALLEN
|
||||
double EvaluateWithGradient(const arma::mat &x, arma::mat &g);
|
||||
void setJob(const std::shared_ptr<SimulationJob> &pJob);
|
||||
SimulationMesh *getDeformedMesh(const arma::mat &x);
|
||||
|
||||
#endif
|
||||
|
||||
static void runUnitTests();
|
||||
};
|
||||
|
|
33
edgemesh.cpp
33
edgemesh.cpp
|
@ -204,7 +204,7 @@ bool VCGEdgeMesh::load(const string &plyFilename) {
|
|||
usedPath = std::filesystem::absolute(plyFilename).string();
|
||||
}
|
||||
assert(std::filesystem::exists(usedPath));
|
||||
this->Clear();
|
||||
Clear();
|
||||
// if (!loadUsingNanoply(usedPath)) {
|
||||
// std::cerr << "Error: Unable to open " + usedPath << std::endl;
|
||||
// return false;
|
||||
|
@ -248,7 +248,7 @@ bool VCGEdgeMesh::load(const string &plyFilename) {
|
|||
|
||||
bool VCGEdgeMesh::loadUsingDefaultLoader(const std::string &plyFilename)
|
||||
{
|
||||
this->Clear();
|
||||
Clear();
|
||||
// assert(plyFileHasAllRequiredFields(plyFilename));
|
||||
// Load the ply file
|
||||
int mask = 0;
|
||||
|
@ -337,10 +337,35 @@ bool VCGEdgeMesh::copy(VCGEdgeMesh &mesh) {
|
|||
return true;
|
||||
}
|
||||
|
||||
void VCGEdgeMesh::set(const std::vector<double> &vertexPositions, const std::vector<int> &edges)
|
||||
{
|
||||
Clear();
|
||||
for (int ei = 0; ei < edges.size(); ei += 2) {
|
||||
const int vi0 = edges[ei];
|
||||
const int vi1 = edges[ei + 1];
|
||||
const int vi0_offset = 3 * vi0;
|
||||
const int vi1_offset = 3 * vi1;
|
||||
const CoordType p0(vertexPositions[vi0_offset],
|
||||
vertexPositions[vi0_offset + 1],
|
||||
vertexPositions[vi0_offset + 2]);
|
||||
const CoordType p1(vertexPositions[vi1_offset],
|
||||
vertexPositions[vi1_offset + 1],
|
||||
vertexPositions[vi1_offset + 2]);
|
||||
auto eIt = vcg::tri::Allocator<VCGEdgeMesh>::AddEdge(*this, p0, p1);
|
||||
CoordType n(0, 0, 1);
|
||||
eIt->cV(0)->N() = n;
|
||||
eIt->cV(1)->N() = n;
|
||||
}
|
||||
removeDuplicateVertices();
|
||||
|
||||
updateEigenEdgeAndVertices();
|
||||
}
|
||||
|
||||
void VCGEdgeMesh::removeDuplicateVertices()
|
||||
{
|
||||
vcg::tri::Clean<VCGEdgeMesh>::MergeCloseVertex(*this, 0.000061524);
|
||||
vcg::tri::Allocator<VCGEdgeMesh>::CompactVertexVector(*this);
|
||||
vcg::tri::Allocator<VCGEdgeMesh>::CompactEdgeVector(*this);
|
||||
vcg::tri::UpdateTopology<VCGEdgeMesh>::VertexEdge(*this);
|
||||
}
|
||||
|
||||
|
@ -418,8 +443,12 @@ polyscope::CurveNetwork *VCGEdgeMesh::registerForDrawing(
|
|||
{
|
||||
PolyscopeInterface::init();
|
||||
const double drawingRadius = desiredRadius;
|
||||
updateEigenEdgeAndVertices();
|
||||
polyscope::CurveNetwork *polyscopeHandle_edgeMesh
|
||||
= polyscope::registerCurveNetwork(label, getEigenVertices(), getEigenEdges());
|
||||
// std::cout << "EDGES:" << polyscopeHandle_edgeMesh->nEdges() << std::endl;
|
||||
assert(polyscopeHandle_edgeMesh->nEdges() == getEigenEdges().rows()
|
||||
&& polyscopeHandle_edgeMesh->nNodes() == getEigenVertices().rows());
|
||||
|
||||
polyscopeHandle_edgeMesh->setEnabled(shouldEnable);
|
||||
polyscopeHandle_edgeMesh->setRadius(drawingRadius, true);
|
||||
|
|
|
@ -58,6 +58,8 @@ public:
|
|||
* */
|
||||
bool copy(VCGEdgeMesh &mesh);
|
||||
|
||||
void set(const std::vector<double> &vertexPositions, const std::vector<int> &edges);
|
||||
|
||||
void removeDuplicateVertices();
|
||||
void deleteDanglingVertices();
|
||||
void deleteDanglingVertices(vcg::tri::Allocator<VCGEdgeMesh>::PointerUpdater<VertexPointer> &pu);
|
||||
|
|
|
@ -0,0 +1,266 @@
|
|||
#include "linearsimulationmodel.hpp"
|
||||
#include "gsl/gsl"
|
||||
|
||||
std::vector<fea::Elem> LinearSimulationModel::getFeaElements(
|
||||
const std::shared_ptr<SimulationMesh> &pMesh)
|
||||
{
|
||||
const int numberOfEdges = pMesh->EN();
|
||||
std::vector<fea::Elem> elements(numberOfEdges);
|
||||
for (int edgeIndex = 0; edgeIndex < numberOfEdges; edgeIndex++) {
|
||||
const SimulationMesh::CoordType &evn0 = pMesh->edge[edgeIndex].cV(0)->cN();
|
||||
const SimulationMesh::CoordType &evn1 = pMesh->edge[edgeIndex].cV(1)->cN();
|
||||
const std::vector<double> nAverageVector{(evn0[0] + evn1[0]) / 2,
|
||||
(evn0[1] + evn1[1]) / 2,
|
||||
(evn0[2] + evn1[2]) / 2};
|
||||
const Element &element = pMesh->elements[edgeIndex];
|
||||
const double E = element.material.youngsModulus;
|
||||
fea::Props feaProperties(E * element.A,
|
||||
E * element.inertia.I3,
|
||||
E * element.inertia.I2,
|
||||
element.G * element.inertia.J,
|
||||
nAverageVector);
|
||||
const int vi0 = pMesh->getIndex(pMesh->edge[edgeIndex].cV(0));
|
||||
const int vi1 = pMesh->getIndex(pMesh->edge[edgeIndex].cV(1));
|
||||
elements[edgeIndex] = fea::Elem(vi0, vi1, feaProperties);
|
||||
}
|
||||
|
||||
return elements;
|
||||
}
|
||||
|
||||
std::vector<fea::Node> LinearSimulationModel::getFeaNodes(
|
||||
const std::shared_ptr<SimulationMesh> &pMesh)
|
||||
{
|
||||
const int numberOfNodes = pMesh->VN();
|
||||
std::vector<fea::Node> feaNodes(numberOfNodes);
|
||||
for (int vi = 0; vi < numberOfNodes; vi++) {
|
||||
const CoordType &p = pMesh->vert[vi].cP();
|
||||
feaNodes[vi] = fea::Node(p[0], p[1], p[2]);
|
||||
}
|
||||
|
||||
return feaNodes;
|
||||
}
|
||||
|
||||
std::vector<fea::BC> LinearSimulationModel::getFeaFixedNodes(
|
||||
const std::shared_ptr<SimulationJob> &job)
|
||||
{
|
||||
std::vector<fea::BC> boundaryConditions;
|
||||
// boundaryConditions.reserve(job->constrainedVertices.size() * 6
|
||||
// + job->nodalForcedDisplacements.size() * 3);
|
||||
for (auto fixedVertex : job->constrainedVertices) {
|
||||
const int vertexIndex = fixedVertex.first;
|
||||
for (int dofIndex : fixedVertex.second) {
|
||||
boundaryConditions.emplace_back(
|
||||
fea::BC(vertexIndex, static_cast<fea::DOF>(dofIndex), 0));
|
||||
}
|
||||
}
|
||||
|
||||
for (auto forcedDisplacement : job->nodalForcedDisplacements) {
|
||||
const int vi = forcedDisplacement.first;
|
||||
for (int dofIndex = 0; dofIndex < 3; dofIndex++) {
|
||||
boundaryConditions.emplace_back(
|
||||
fea::BC(vi, static_cast<fea::DOF>(dofIndex), forcedDisplacement.second[dofIndex]));
|
||||
}
|
||||
}
|
||||
|
||||
return boundaryConditions;
|
||||
}
|
||||
|
||||
std::vector<fea::Force> LinearSimulationModel::getFeaNodalForces(
|
||||
const std::shared_ptr<SimulationJob> &job)
|
||||
{
|
||||
std::vector<fea::Force> nodalForces;
|
||||
nodalForces.reserve(job->nodalExternalForces.size() * 6);
|
||||
|
||||
for (auto nodalForce : job->nodalExternalForces) {
|
||||
for (int dofIndex = 0; dofIndex < 6; dofIndex++) {
|
||||
if (nodalForce.second[dofIndex] == 0) {
|
||||
continue;
|
||||
}
|
||||
fea::Force f(nodalForce.first, dofIndex, nodalForce.second[dofIndex]);
|
||||
nodalForces.emplace_back(f);
|
||||
}
|
||||
}
|
||||
|
||||
return nodalForces;
|
||||
}
|
||||
|
||||
SimulationResults LinearSimulationModel::getResults(
|
||||
const fea::Summary &feaSummary, const std::shared_ptr<SimulationJob> &simulationJob)
|
||||
{
|
||||
SimulationResults results;
|
||||
results.converged = feaSummary.converged;
|
||||
if (!results.converged) {
|
||||
return results;
|
||||
}
|
||||
|
||||
results.executionTime = feaSummary.total_time_in_ms * 1000;
|
||||
// displacements
|
||||
results.displacements.resize(feaSummary.num_nodes);
|
||||
results.rotationalDisplacementQuaternion.resize(feaSummary.num_nodes);
|
||||
for (int vi = 0; vi < feaSummary.num_nodes; vi++) {
|
||||
results.displacements[vi] = Vector6d(feaSummary.nodal_displacements[vi]);
|
||||
|
||||
const Vector6d &nodalDisplacement = results.displacements[vi];
|
||||
Eigen::Quaternion<double> q_nx;
|
||||
q_nx = Eigen::AngleAxis<double>(nodalDisplacement[3], Eigen::Vector3d(1, 0, 0));
|
||||
Eigen::Quaternion<double> q_ny;
|
||||
q_ny = Eigen::AngleAxis<double>(nodalDisplacement[4], Eigen::Vector3d(0, 1, 0));
|
||||
Eigen::Quaternion<double> q_nz;
|
||||
q_nz = Eigen::AngleAxis<double>(nodalDisplacement[5], Eigen::Vector3d(0, 0, 1));
|
||||
results.rotationalDisplacementQuaternion[vi] = q_nx * q_ny * q_nz;
|
||||
// results.rotationalDisplacementQuaternion[vi] = q_nz * q_ny * q_nx;
|
||||
// results.rotationalDisplacementQuaternion[vi] = q_nz * q_nx * q_ny;
|
||||
}
|
||||
results.setLabelPrefix("Linear");
|
||||
|
||||
// // Convert forces
|
||||
// // Convert to vector of eigen matrices of the form force component-> per
|
||||
// // Edge
|
||||
// const int numDof = 6;
|
||||
// const size_t numberOfEdges = feaSummary.element_forces.size();
|
||||
// edgeForces =
|
||||
// std::vector<Eigen::VectorXd>(numDof, Eigen::VectorXd(2 *
|
||||
// numberOfEdges));
|
||||
// for (gsl::index edgeIndex = 0; edgeIndex < numberOfEdges; edgeIndex++) {
|
||||
// for (gsl::index forceComponentIndex = 0; forceComponentIndex < numDof;
|
||||
// forceComponentIndex++) {
|
||||
// (edgeForces[forceComponentIndex])(2 * edgeIndex) =
|
||||
// feaSummary.element_forces[edgeIndex][forceComponentIndex];
|
||||
// (edgeForces[forceComponentIndex])(2 * edgeIndex + 1) =
|
||||
// feaSummary.element_forces[edgeIndex][numDof +
|
||||
// forceComponentIndex];
|
||||
// }
|
||||
// }
|
||||
|
||||
for (int ei = 0; ei < feaSummary.num_elems; ei++) {
|
||||
const std::vector<double> &elementForces = feaSummary.element_forces[ei];
|
||||
const Element &element = simulationJob->pMesh->elements[ei];
|
||||
//Axial
|
||||
const double elementPotentialEnergy_axial_v0 = std::pow(elementForces[0], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.A);
|
||||
const double elementPotentialEnergy_axial_v1 = std::pow(elementForces[6], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.A);
|
||||
const double elementPotentialEnergy_axial = elementPotentialEnergy_axial_v0
|
||||
+ elementPotentialEnergy_axial_v1;
|
||||
//Shear
|
||||
const double elementPotentialEnergy_shearY_v0 = std::pow(elementForces[1], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearZ_v0 = std::pow(elementForces[2], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearY_v1 = std::pow(elementForces[7], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearZ_v1 = std::pow(elementForces[8], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shear = elementPotentialEnergy_shearY_v0
|
||||
+ elementPotentialEnergy_shearZ_v0
|
||||
+ elementPotentialEnergy_shearY_v1
|
||||
+ elementPotentialEnergy_shearZ_v1;
|
||||
//Bending
|
||||
const double elementPotentialEnergy_bendingY_v0 = std::pow(elementForces[4], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I2);
|
||||
const double elementPotentialEnergy_bendingZ_v0 = std::pow(elementForces[5], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I3);
|
||||
const double elementPotentialEnergy_bendingY_v1 = std::pow(elementForces[10], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I2);
|
||||
const double elementPotentialEnergy_bendingZ_v1 = std::pow(elementForces[11], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I3);
|
||||
const double elementPotentialEnergy_bending = elementPotentialEnergy_bendingY_v0
|
||||
+ elementPotentialEnergy_bendingZ_v0
|
||||
+ elementPotentialEnergy_bendingY_v1
|
||||
+ elementPotentialEnergy_bendingZ_v1;
|
||||
//Torsion
|
||||
const double elementPotentialEnergy_torsion_v0 = std::pow(elementForces[3], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.inertia.J * element.G);
|
||||
const double elementPotentialEnergy_torsion_v1 = std::pow(elementForces[9], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.inertia.J * element.G);
|
||||
const double elementPotentialEnergy_torsion = elementPotentialEnergy_torsion_v0
|
||||
+ elementPotentialEnergy_torsion_v1;
|
||||
const double elementInternalPotentialEnergy = elementPotentialEnergy_axial
|
||||
+ elementPotentialEnergy_shear
|
||||
+ elementPotentialEnergy_bending
|
||||
+ elementPotentialEnergy_torsion;
|
||||
results.internalPotentialEnergy += elementInternalPotentialEnergy;
|
||||
}
|
||||
results.pJob = simulationJob;
|
||||
|
||||
return results;
|
||||
}
|
||||
|
||||
SimulationResults LinearSimulationModel::executeSimulation(
|
||||
const std::shared_ptr<SimulationJob> &pSimulationJob)
|
||||
{
|
||||
assert(pSimulationJob->pMesh->VN() != 0);
|
||||
if (!simulator.wasInitialized()) {
|
||||
setStructure(pSimulationJob->pMesh);
|
||||
}
|
||||
// printInfo(job);
|
||||
|
||||
// create the default options
|
||||
fea::Options opts;
|
||||
opts.save_elemental_forces = false;
|
||||
opts.save_nodal_displacements = false;
|
||||
opts.save_nodal_forces = false;
|
||||
opts.save_report = false;
|
||||
opts.save_tie_forces = false;
|
||||
// if (!elementalForcesOutputFilepath.empty()) {
|
||||
// opts.save_elemental_forces = true;
|
||||
// opts.elemental_forces_filename = elementalForcesOutputFilepath;
|
||||
// }
|
||||
// if (!nodalDisplacementsOutputFilepath.empty()) {
|
||||
// opts.save_nodal_displacements = true;
|
||||
// opts.nodal_displacements_filename = nodalDisplacementsOutputFilepath;
|
||||
// }
|
||||
|
||||
// have the program output status updates
|
||||
opts.verbose = false;
|
||||
|
||||
// form an empty vector of ties
|
||||
std::vector<fea::Tie> ties;
|
||||
|
||||
// also create an empty list of equations
|
||||
std::vector<fea::Equation> equations;
|
||||
auto fixedVertices = getFeaFixedNodes(pSimulationJob);
|
||||
auto nodalForces = getFeaNodalForces(pSimulationJob);
|
||||
fea::Summary feaResults = simulator.solve(fixedVertices, nodalForces, ties, equations, opts);
|
||||
|
||||
SimulationResults results = getResults(feaResults, pSimulationJob);
|
||||
results.pJob = pSimulationJob;
|
||||
return results;
|
||||
}
|
||||
|
||||
void LinearSimulationModel::setStructure(const std::shared_ptr<SimulationMesh> &pMesh)
|
||||
{
|
||||
fea::BeamStructure structure(getFeaNodes(pMesh), getFeaElements(pMesh));
|
||||
simulator.initialize(structure);
|
||||
}
|
||||
|
||||
void LinearSimulationModel::printInfo(const fea::BeamStructure &job)
|
||||
{
|
||||
std::cout << "Details regarding the fea::Job:" << std::endl;
|
||||
std::cout << "Nodes:" << std::endl;
|
||||
for (fea::Node n : job.nodes) {
|
||||
std::cout << n << std::endl;
|
||||
}
|
||||
std::cout << "Elements:" << std::endl;
|
||||
for (Eigen::Vector2i e : job.elems) {
|
||||
std::cout << e << std::endl;
|
||||
}
|
||||
}
|
|
@ -12,265 +12,21 @@ public:
|
|||
LinearSimulationModel(){
|
||||
|
||||
}
|
||||
static std::vector<fea::Elem>
|
||||
getFeaElements(const std::shared_ptr<SimulationJob> &job) {
|
||||
const int numberOfEdges = job->pMesh->EN();
|
||||
std::vector<fea::Elem> elements(numberOfEdges);
|
||||
for (int edgeIndex = 0; edgeIndex < numberOfEdges; edgeIndex++) {
|
||||
const SimulationMesh::CoordType &evn0 =
|
||||
job->pMesh->edge[edgeIndex].cV(0)->cN();
|
||||
const SimulationMesh::CoordType &evn1 = job->pMesh->edge[edgeIndex].cV(1)->cN();
|
||||
const std::vector<double> nAverageVector{(evn0[0] + evn1[0]) / 2,
|
||||
(evn0[1] + evn1[1]) / 2,
|
||||
(evn0[2] + evn1[2]) / 2};
|
||||
const Element &element = job->pMesh->elements[edgeIndex];
|
||||
const double E = element.material.youngsModulus;
|
||||
fea::Props feaProperties(E * element.A,
|
||||
E * element.inertia.I3,
|
||||
E * element.inertia.I2,
|
||||
element.G * element.inertia.J,
|
||||
nAverageVector);
|
||||
const int vi0 = job->pMesh->getIndex(job->pMesh->edge[edgeIndex].cV(0));
|
||||
const int vi1 = job->pMesh->getIndex(job->pMesh->edge[edgeIndex].cV(1));
|
||||
elements[edgeIndex] = fea::Elem(vi0, vi1, feaProperties);
|
||||
}
|
||||
static std::vector<fea::Elem> getFeaElements(const std::shared_ptr<SimulationMesh> &pMesh);
|
||||
|
||||
return elements;
|
||||
}
|
||||
static std::vector<fea::Node> getFeaNodes(const std::shared_ptr<SimulationMesh> &pMesh);
|
||||
static std::vector<fea::BC> getFeaFixedNodes(const std::shared_ptr<SimulationJob> &job);
|
||||
|
||||
static std::vector<fea::Node>
|
||||
getFeaNodes(const std::shared_ptr<SimulationJob> &job) {
|
||||
const int numberOfNodes = job->pMesh->VN();
|
||||
std::vector<fea::Node> feaNodes(numberOfNodes);
|
||||
for (int vi = 0; vi < numberOfNodes; vi++) {
|
||||
const CoordType &p = job->pMesh->vert[vi].cP();
|
||||
feaNodes[vi] = fea::Node(p[0], p[1], p[2]);
|
||||
}
|
||||
|
||||
return feaNodes;
|
||||
}
|
||||
static std::vector<fea::BC>
|
||||
getFeaFixedNodes(const std::shared_ptr<SimulationJob> &job) {
|
||||
std::vector<fea::BC> boundaryConditions;
|
||||
// boundaryConditions.reserve(job->constrainedVertices.size() * 6
|
||||
// + job->nodalForcedDisplacements.size() * 3);
|
||||
for (auto fixedVertex : job->constrainedVertices) {
|
||||
const int vertexIndex = fixedVertex.first;
|
||||
for (int dofIndex : fixedVertex.second) {
|
||||
boundaryConditions.emplace_back(
|
||||
fea::BC(vertexIndex, static_cast<fea::DOF>(dofIndex), 0));
|
||||
}
|
||||
}
|
||||
|
||||
for (auto forcedDisplacement : job->nodalForcedDisplacements) {
|
||||
const int vi = forcedDisplacement.first;
|
||||
for (int dofIndex = 0; dofIndex < 3; dofIndex++) {
|
||||
boundaryConditions.emplace_back(fea::BC(vi,
|
||||
static_cast<fea::DOF>(dofIndex),
|
||||
forcedDisplacement.second[dofIndex]));
|
||||
}
|
||||
}
|
||||
|
||||
return boundaryConditions;
|
||||
}
|
||||
|
||||
static std::vector<fea::Force>
|
||||
getFeaNodalForces(const std::shared_ptr<SimulationJob> &job) {
|
||||
std::vector<fea::Force> nodalForces;
|
||||
nodalForces.reserve(job->nodalExternalForces.size() * 6);
|
||||
|
||||
for (auto nodalForce : job->nodalExternalForces) {
|
||||
for (int dofIndex = 0; dofIndex < 6; dofIndex++) {
|
||||
if (nodalForce.second[dofIndex] == 0) {
|
||||
continue;
|
||||
}
|
||||
fea::Force f(nodalForce.first, dofIndex, nodalForce.second[dofIndex]);
|
||||
nodalForces.emplace_back(f);
|
||||
}
|
||||
}
|
||||
|
||||
return nodalForces;
|
||||
}
|
||||
static std::vector<fea::Force> getFeaNodalForces(const std::shared_ptr<SimulationJob> &job);
|
||||
static SimulationResults getResults(const fea::Summary &feaSummary,
|
||||
const std::shared_ptr<SimulationJob> &simulationJob)
|
||||
{
|
||||
SimulationResults results;
|
||||
results.converged = feaSummary.converged;
|
||||
if (!results.converged) {
|
||||
return results;
|
||||
}
|
||||
const std::shared_ptr<SimulationJob> &simulationJob);
|
||||
|
||||
results.executionTime = feaSummary.total_time_in_ms * 1000;
|
||||
// displacements
|
||||
results.displacements.resize(feaSummary.num_nodes);
|
||||
results.rotationalDisplacementQuaternion.resize(feaSummary.num_nodes);
|
||||
for (int vi = 0; vi < feaSummary.num_nodes; vi++) {
|
||||
results.displacements[vi] = Vector6d(feaSummary.nodal_displacements[vi]);
|
||||
|
||||
const Vector6d &nodalDisplacement = results.displacements[vi];
|
||||
Eigen::Quaternion<double> q_nx;
|
||||
q_nx = Eigen::AngleAxis<double>(nodalDisplacement[3], Eigen::Vector3d(1, 0, 0));
|
||||
Eigen::Quaternion<double> q_ny;
|
||||
q_ny = Eigen::AngleAxis<double>(nodalDisplacement[4], Eigen::Vector3d(0, 1, 0));
|
||||
Eigen::Quaternion<double> q_nz;
|
||||
q_nz = Eigen::AngleAxis<double>(nodalDisplacement[5], Eigen::Vector3d(0, 0, 1));
|
||||
results.rotationalDisplacementQuaternion[vi] = q_nx * q_ny * q_nz;
|
||||
// results.rotationalDisplacementQuaternion[vi] = q_nz * q_ny * q_nx;
|
||||
// results.rotationalDisplacementQuaternion[vi] = q_nz * q_nx * q_ny;
|
||||
}
|
||||
results.setLabelPrefix("Linear");
|
||||
|
||||
// // Convert forces
|
||||
// // Convert to vector of eigen matrices of the form force component-> per
|
||||
// // Edge
|
||||
// const int numDof = 6;
|
||||
// const size_t numberOfEdges = feaSummary.element_forces.size();
|
||||
// edgeForces =
|
||||
// std::vector<Eigen::VectorXd>(numDof, Eigen::VectorXd(2 *
|
||||
// numberOfEdges));
|
||||
// for (gsl::index edgeIndex = 0; edgeIndex < numberOfEdges; edgeIndex++) {
|
||||
// for (gsl::index forceComponentIndex = 0; forceComponentIndex < numDof;
|
||||
// forceComponentIndex++) {
|
||||
// (edgeForces[forceComponentIndex])(2 * edgeIndex) =
|
||||
// feaSummary.element_forces[edgeIndex][forceComponentIndex];
|
||||
// (edgeForces[forceComponentIndex])(2 * edgeIndex + 1) =
|
||||
// feaSummary.element_forces[edgeIndex][numDof +
|
||||
// forceComponentIndex];
|
||||
// }
|
||||
// }
|
||||
|
||||
for (int ei = 0; ei < feaSummary.num_elems; ei++) {
|
||||
const std::vector<double> &elementForces = feaSummary.element_forces[ei];
|
||||
const Element &element = simulationJob->pMesh->elements[ei];
|
||||
//Axial
|
||||
const double elementPotentialEnergy_axial_v0 = std::pow(elementForces[0], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.A);
|
||||
const double elementPotentialEnergy_axial_v1 = std::pow(elementForces[6], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.A);
|
||||
const double elementPotentialEnergy_axial = elementPotentialEnergy_axial_v0
|
||||
+ elementPotentialEnergy_axial_v1;
|
||||
//Shear
|
||||
const double elementPotentialEnergy_shearY_v0 = std::pow(elementForces[1], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearZ_v0 = std::pow(elementForces[2], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearY_v1 = std::pow(elementForces[7], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shearZ_v1 = std::pow(elementForces[8], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.A * element.G);
|
||||
const double elementPotentialEnergy_shear = elementPotentialEnergy_shearY_v0
|
||||
+ elementPotentialEnergy_shearZ_v0
|
||||
+ elementPotentialEnergy_shearY_v1
|
||||
+ elementPotentialEnergy_shearZ_v1;
|
||||
//Bending
|
||||
const double elementPotentialEnergy_bendingY_v0 = std::pow(elementForces[4], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I2);
|
||||
const double elementPotentialEnergy_bendingZ_v0 = std::pow(elementForces[5], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I3);
|
||||
const double elementPotentialEnergy_bendingY_v1 = std::pow(elementForces[10], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I2);
|
||||
const double elementPotentialEnergy_bendingZ_v1 = std::pow(elementForces[11], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.material.youngsModulus
|
||||
* element.inertia.I3);
|
||||
const double elementPotentialEnergy_bending = elementPotentialEnergy_bendingY_v0
|
||||
+ elementPotentialEnergy_bendingZ_v0
|
||||
+ elementPotentialEnergy_bendingY_v1
|
||||
+ elementPotentialEnergy_bendingZ_v1;
|
||||
//Torsion
|
||||
const double elementPotentialEnergy_torsion_v0 = std::pow(elementForces[3], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.inertia.J * element.G);
|
||||
const double elementPotentialEnergy_torsion_v1 = std::pow(elementForces[9], 2)
|
||||
* element.initialLength
|
||||
/ (4 * element.inertia.J * element.G);
|
||||
const double elementPotentialEnergy_torsion = elementPotentialEnergy_torsion_v0
|
||||
+ elementPotentialEnergy_torsion_v1;
|
||||
const double elementInternalPotentialEnergy = elementPotentialEnergy_axial
|
||||
+ elementPotentialEnergy_shear
|
||||
+ elementPotentialEnergy_bending
|
||||
+ elementPotentialEnergy_torsion;
|
||||
results.internalPotentialEnergy += elementInternalPotentialEnergy;
|
||||
}
|
||||
results.pJob = simulationJob;
|
||||
|
||||
return results;
|
||||
}
|
||||
|
||||
SimulationResults
|
||||
executeSimulation(const std::shared_ptr<SimulationJob> &simulationJob) {
|
||||
assert(simulationJob->pMesh->VN() != 0);
|
||||
fea::Job job(getFeaNodes(simulationJob), getFeaElements(simulationJob));
|
||||
// printInfo(job);
|
||||
|
||||
// create the default options
|
||||
fea::Options opts;
|
||||
opts.save_elemental_forces = false;
|
||||
opts.save_nodal_displacements = false;
|
||||
opts.save_nodal_forces = false;
|
||||
opts.save_report = false;
|
||||
opts.save_tie_forces = false;
|
||||
// if (!elementalForcesOutputFilepath.empty()) {
|
||||
// opts.save_elemental_forces = true;
|
||||
// opts.elemental_forces_filename = elementalForcesOutputFilepath;
|
||||
// }
|
||||
// if (!nodalDisplacementsOutputFilepath.empty()) {
|
||||
// opts.save_nodal_displacements = true;
|
||||
// opts.nodal_displacements_filename = nodalDisplacementsOutputFilepath;
|
||||
// }
|
||||
|
||||
// have the program output status updates
|
||||
opts.verbose = false;
|
||||
|
||||
// form an empty vector of ties
|
||||
std::vector<fea::Tie> ties;
|
||||
|
||||
// also create an empty list of equations
|
||||
std::vector<fea::Equation> equations;
|
||||
auto fixedVertices = getFeaFixedNodes(simulationJob);
|
||||
auto nodalForces = getFeaNodalForces(simulationJob);
|
||||
fea::Summary feaResults =
|
||||
fea::solve(job, fixedVertices, nodalForces, ties, equations, opts);
|
||||
|
||||
SimulationResults results = getResults(feaResults, simulationJob);
|
||||
results.pJob = simulationJob;
|
||||
return results;
|
||||
}
|
||||
// SimulationResults getResults() const;
|
||||
// void setResultsNodalDisplacementCSVFilepath(const std::string
|
||||
// &outputPath); void setResultsElementalForcesCSVFilepath(const std::string
|
||||
// &outputPath);
|
||||
SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &simulationJob);
|
||||
void setStructure(const std::shared_ptr<SimulationMesh> &pMesh);
|
||||
|
||||
private:
|
||||
// std::string nodalDisplacementsOutputFilepath{"nodal_displacement.csv"};
|
||||
// std::string elementalForcesOutputFilepath{"elemental_forces.csv"};
|
||||
// SimulationResults results;
|
||||
|
||||
static void printInfo(const fea::Job &job) {
|
||||
std::cout << "Details regarding the fea::Job:" << std::endl;
|
||||
std::cout << "Nodes:" << std::endl;
|
||||
for (fea::Node n : job.nodes) {
|
||||
std::cout << n << std::endl;
|
||||
}
|
||||
std::cout << "Elements:" << std::endl;
|
||||
for (Eigen::Vector2i e : job.elems) {
|
||||
std::cout << e << std::endl;
|
||||
}
|
||||
}
|
||||
fea::ThreedBeamFEA simulator;
|
||||
static void printInfo(const fea::BeamStructure &job);
|
||||
};
|
||||
|
||||
#endif // LINEARSIMULATIONMODEL_HPP
|
||||
|
|
|
@ -65,7 +65,7 @@ struct xRange
|
|||
struct Settings
|
||||
{
|
||||
enum NormalizationStrategy { NonNormalized, Epsilon };
|
||||
std::vector<xRange> xRanges;
|
||||
std::vector<xRange> parameterRanges;
|
||||
inline static vector<std::string> normalizationStrategyStrings{"NonNormalized", "Epsilon"};
|
||||
int numberOfFunctionCalls{100000};
|
||||
double solverAccuracy{1e-2};
|
||||
|
@ -94,8 +94,8 @@ struct xRange
|
|||
|
||||
nlohmann::json json;
|
||||
//write x ranges
|
||||
for (size_t xRangeIndex = 0; xRangeIndex < xRanges.size(); xRangeIndex++) {
|
||||
const auto &xRange = xRanges[xRangeIndex];
|
||||
for (size_t xRangeIndex = 0; xRangeIndex < parameterRanges.size(); xRangeIndex++) {
|
||||
const auto &xRange = parameterRanges[xRangeIndex];
|
||||
json[JsonKeys::OptimizationVariables + "_" + std::to_string(xRangeIndex)]
|
||||
= xRange.toString();
|
||||
}
|
||||
|
@ -133,7 +133,7 @@ struct xRange
|
|||
}
|
||||
xRange x;
|
||||
x.fromString(json.at(jsonXRangeKey));
|
||||
xRanges.push_back(x);
|
||||
parameterRanges.push_back(x);
|
||||
xRangeIndex++;
|
||||
}
|
||||
|
||||
|
@ -147,9 +147,9 @@ struct xRange
|
|||
std::string toString() const
|
||||
{
|
||||
std::string settingsString;
|
||||
if (!xRanges.empty()) {
|
||||
if (!parameterRanges.empty()) {
|
||||
std::string xRangesString;
|
||||
for (const xRange &range : xRanges) {
|
||||
for (const xRange &range : parameterRanges) {
|
||||
xRangesString += range.toString() + " ";
|
||||
}
|
||||
settingsString += xRangesString;
|
||||
|
@ -164,8 +164,8 @@ struct xRange
|
|||
|
||||
void writeHeaderTo(csvFile &os) const
|
||||
{
|
||||
if (!xRanges.empty()) {
|
||||
for (const xRange &range : xRanges) {
|
||||
if (!parameterRanges.empty()) {
|
||||
for (const xRange &range : parameterRanges) {
|
||||
os << range.label + " max";
|
||||
os << range.label + " min";
|
||||
}
|
||||
|
@ -181,8 +181,8 @@ struct xRange
|
|||
|
||||
void writeSettingsTo(csvFile &os) const
|
||||
{
|
||||
if (!xRanges.empty()) {
|
||||
for (const xRange &range : xRanges) {
|
||||
if (!parameterRanges.empty()) {
|
||||
for (const xRange &range : parameterRanges) {
|
||||
os << range.max;
|
||||
os << range.min;
|
||||
}
|
||||
|
@ -200,7 +200,7 @@ struct xRange
|
|||
inline bool operator==(const Settings &settings1, const Settings &settings2) noexcept
|
||||
{
|
||||
return settings1.numberOfFunctionCalls == settings2.numberOfFunctionCalls
|
||||
&& settings1.xRanges == settings2.xRanges
|
||||
&& settings1.parameterRanges == settings2.parameterRanges
|
||||
&& settings1.solverAccuracy == settings2.solverAccuracy
|
||||
&& settings1.objectiveWeights.translational == settings2.objectiveWeights.translational
|
||||
&& settings1.translationNormalizationParameter
|
||||
|
@ -271,6 +271,7 @@ struct xRange
|
|||
std::vector<std::pair<std::string, double>> optimalXNameValuePairs;
|
||||
std::vector<std::shared_ptr<SimulationJob>> fullPatternSimulationJobs;
|
||||
std::vector<std::shared_ptr<SimulationJob>> reducedPatternSimulationJobs;
|
||||
double fullPatternYoungsModulus;
|
||||
|
||||
PatternGeometry baseTriangleFullPattern; //non-fanned,non-tiled full pattern
|
||||
vcg::Triangle3<double> baseTriangle;
|
||||
|
@ -294,8 +295,8 @@ struct xRange
|
|||
struct CSVExportingSettings
|
||||
{
|
||||
bool exportPE{false};
|
||||
bool exportIterationOfMinima{true};
|
||||
bool exportRawObjectiveValue{false};
|
||||
bool exportIterationOfMinima{false};
|
||||
bool exportRawObjectiveValue{true};
|
||||
CSVExportingSettings() {}
|
||||
};
|
||||
|
||||
|
@ -309,6 +310,7 @@ struct xRange
|
|||
inline static std::string FullPatternLabel{"FullPatternLabel"};
|
||||
inline static std::string Settings{"OptimizationSettings"};
|
||||
inline static std::string FullPatternPotentialEnergies{"PE"};
|
||||
inline static std::string fullPatternYoungsModulus{"youngsModulus"};
|
||||
};
|
||||
|
||||
void save(const string &saveToPath, const bool shouldExportDebugFiles = false)
|
||||
|
@ -362,6 +364,7 @@ struct xRange
|
|||
= perScenario_fullPatternPotentialEnergy[simulationScenarioIndex];
|
||||
}
|
||||
json_optimizationResults[JsonKeys::FullPatternPotentialEnergies] = fullPatternPE;
|
||||
json_optimizationResults[JsonKeys::fullPatternYoungsModulus] = fullPatternYoungsModulus;
|
||||
////Save to json file
|
||||
std::filesystem::path jsonFilePath(
|
||||
std::filesystem::path(saveToPath).append(JsonKeys::filename));
|
||||
|
@ -408,7 +411,7 @@ struct xRange
|
|||
|
||||
settings.save(saveToPath);
|
||||
|
||||
#ifdef POLYSCOPE_DEFINED
|
||||
#ifdef POLYSCOPE_DEFINED12
|
||||
std::cout << "Saved optimization results to:" << saveToPath << std::endl;
|
||||
#endif
|
||||
}
|
||||
|
@ -465,6 +468,12 @@ struct xRange
|
|||
baseTriangle.P2(0) = CoordType(baseTriangleVertices[6],
|
||||
baseTriangleVertices[7],
|
||||
baseTriangleVertices[8]);
|
||||
if (json_optimizationResults.contains(JsonKeys::fullPatternYoungsModulus)) {
|
||||
fullPatternYoungsModulus = json_optimizationResults.at(
|
||||
JsonKeys::fullPatternYoungsModulus);
|
||||
} else {
|
||||
fullPatternYoungsModulus = 1 * 1e9;
|
||||
}
|
||||
if (shouldLoadDebugFiles) {
|
||||
const std::filesystem::path simulationJobsFolderPath(
|
||||
std::filesystem::path(loadFromPath).append("SimulationJobs"));
|
||||
|
@ -480,8 +489,8 @@ struct xRange
|
|||
const auto filepath = fileEntry.path();
|
||||
if (filepath.extension() == ".json") {
|
||||
SimulationJob job;
|
||||
|
||||
job.load(filepath.string());
|
||||
job.pMesh->setBeamMaterial(0.3, fullPatternYoungsModulus);
|
||||
fullPatternSimulationJobs.push_back(std::make_shared<SimulationJob>(job));
|
||||
}
|
||||
}
|
||||
|
@ -715,7 +724,7 @@ struct xRange
|
|||
}
|
||||
}
|
||||
|
||||
void writeHeaderTo(csvFile &os)
|
||||
void writeHeaderTo(csvFile &os) const
|
||||
{
|
||||
if (exportSettings.exportRawObjectiveValue) {
|
||||
os << "Total raw Obj value";
|
||||
|
@ -751,13 +760,20 @@ struct xRange
|
|||
// os << "notes";
|
||||
}
|
||||
|
||||
void writeHeaderTo(std::vector<csvFile *> &vectorOfPointersToOutputStreams) const
|
||||
{
|
||||
for (csvFile *outputStream : vectorOfPointersToOutputStreams) {
|
||||
writeHeaderTo(*outputStream);
|
||||
}
|
||||
}
|
||||
|
||||
void writeResultsTo(csvFile &os) const
|
||||
{
|
||||
if (exportSettings.exportRawObjectiveValue) {
|
||||
os << objectiveValue.totalRaw;
|
||||
}
|
||||
os << objectiveValue.total;
|
||||
if (exportSettings.exportIterationOfMinima) {
|
||||
if (exportSettings.exportIterationOfMinima && !objectiveValueHistory_iteration.empty()) {
|
||||
os << objectiveValueHistory_iteration.back();
|
||||
}
|
||||
for (int simulationScenarioIndex = 0;
|
||||
|
@ -787,6 +803,13 @@ struct xRange
|
|||
// os << notes;
|
||||
}
|
||||
|
||||
void writeResultsTo(std::vector<csvFile *> &vectorOfPointersToOutputStreams) const
|
||||
{
|
||||
for (csvFile *&outputStream : vectorOfPointersToOutputStreams) {
|
||||
writeResultsTo(*outputStream);
|
||||
}
|
||||
}
|
||||
|
||||
void writeMinimaInfoTo(csvFile &outputCsv)
|
||||
{
|
||||
outputCsv << "Iteration";
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
#ifndef SIMULATIONSTRUCTS_HPP
|
||||
#define SIMULATIONSTRUCTS_HPP
|
||||
#include <fstream>
|
||||
|
||||
namespace Eigen {
|
||||
template <class Matrix>
|
||||
|
@ -23,13 +24,13 @@ void read_binary(const std::string &filename, Matrix &matrix) {
|
|||
in.read((char *)matrix.data(), rows * cols * sizeof(typename Matrix::Scalar));
|
||||
in.close();
|
||||
}
|
||||
const static IOFormat CSVFormat(StreamPrecision, DontAlignCols, ", ", "\n");
|
||||
template<class Matrix>
|
||||
void writeToCSV(const std::string &filename, Matrix &matrix)
|
||||
{
|
||||
ofstream file(filename.c_str());
|
||||
file << matrix.format(CSVFormat);
|
||||
}
|
||||
//const static IOFormat CSVFormat(StreamPrecision, DontAlignCols, ", ", "\n");
|
||||
//template<class Matrix>
|
||||
//void writeToCSV(const std::string &filename, Matrix &matrix)
|
||||
//{
|
||||
// ofstream file(filename.c_str());
|
||||
// file << matrix.format(CSVFormat);
|
||||
//}
|
||||
} // namespace Eigen
|
||||
|
||||
#include "simulationmesh.hpp"
|
||||
|
@ -613,9 +614,13 @@ struct SimulationResults
|
|||
const std::shared_ptr<SimulationMesh> &mesh = pJob->pMesh;
|
||||
polyscope::CurveNetwork *polyscopeHandle_deformedEdmeMesh;
|
||||
if (!polyscope::hasStructure(getLabel())) {
|
||||
const auto verts = mesh->getEigenVertices();
|
||||
const auto edges = mesh->getEigenEdges();
|
||||
polyscopeHandle_deformedEdmeMesh = polyscope::registerCurveNetwork(getLabel(),
|
||||
mesh->getEigenVertices(),
|
||||
mesh->getEigenEdges());
|
||||
verts,
|
||||
edges);
|
||||
} else {
|
||||
polyscopeHandle_deformedEdmeMesh = polyscope::getCurveNetwork(getLabel());
|
||||
}
|
||||
polyscopeHandle_deformedEdmeMesh->setEnabled(shouldEnable);
|
||||
polyscopeHandle_deformedEdmeMesh->setRadius(desiredRadius, true);
|
||||
|
@ -635,7 +640,8 @@ struct SimulationResults
|
|||
Eigen::MatrixX3d framesZ_initial(mesh->VN(), 3);
|
||||
|
||||
// std::unordered_set<int> interfaceNodes{1, 3, 5, 7, 9, 11};
|
||||
std::unordered_set<int> interfaceNodes{3, 7, 11, 15, 19, 23};
|
||||
// std::unordered_set<int> interfaceNodes{3, 7, 11, 15, 19, 23};
|
||||
std::unordered_set<int> interfaceNodes{};
|
||||
for (VertexIndex vi = 0; vi < mesh->VN(); vi++) {
|
||||
const Vector6d &nodalDisplacement = displacements[vi];
|
||||
nodalDisplacements.row(vi) = Eigen::Vector3d(nodalDisplacement[0],
|
||||
|
@ -692,10 +698,10 @@ struct SimulationResults
|
|||
polyscopeHandle_frameZ->setVectorColor(
|
||||
/*polyscope::getNextUniqueColor()*/ glm::vec3(0, 0, 1));
|
||||
|
||||
// auto polyscopeHandle_initialMesh = polyscope::getCurveNetwork(mesh->getLabel());
|
||||
// if (!polyscopeHandle_initialMesh) {
|
||||
// polyscopeHandle_initialMesh = mesh->registerForDrawing();
|
||||
// }
|
||||
auto polyscopeHandle_initialMesh = polyscope::getCurveNetwork(mesh->getLabel());
|
||||
if (!polyscopeHandle_initialMesh) {
|
||||
polyscopeHandle_initialMesh = mesh->registerForDrawing();
|
||||
}
|
||||
|
||||
// auto polyscopeHandle_frameX_initial = polyscopeHandle_initialMesh
|
||||
// ->addNodeVectorQuantity("FrameX", framesX_initial);
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#ifndef SIMULATIONHISTORYPLOTTER_HPP
|
||||
#define SIMULATIONHISTORYPLOTTER_HPP
|
||||
|
||||
#include "simulationmesh.hpp"
|
||||
#include "simulation_structs.hpp"
|
||||
#include "simulationmesh.hpp"
|
||||
#include "utilities.hpp"
|
||||
#include <algorithm>
|
||||
#include <matplot/matplot.h>
|
||||
|
|
|
@ -15,8 +15,8 @@ SimulationMesh::SimulationMesh(VCGEdgeMesh &mesh) {
|
|||
|
||||
elements = vcg::tri::Allocator<SimulationMesh>::GetPerEdgeAttribute<Element>(
|
||||
*this, std::string("Elements"));
|
||||
nodes = vcg::tri::Allocator<SimulationMesh>::GetPerVertexAttribute<Node>(
|
||||
*this, std::string("Nodes"));
|
||||
nodes = vcg::tri::Allocator<SimulationMesh>::GetPerVertexAttribute<Node>(*this,
|
||||
std::string("Nodes"));
|
||||
initializeNodes();
|
||||
initializeElements();
|
||||
}
|
||||
|
@ -243,8 +243,6 @@ void SimulationMesh::updateElementalLengths() {
|
|||
const vcg::Segment3<double> s(p0, p1);
|
||||
const double elementLength = s.Length();
|
||||
elements[e].length = elementLength;
|
||||
int i = 0;
|
||||
i++;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -328,7 +326,7 @@ bool SimulationMesh::load(const string &plyFilename) {
|
|||
// mask |= nanoply::NanoPlyWrapper<VCGEdgeMesh>::IO_EDGEINDEX;
|
||||
// mask |= nanoply::NanoPlyWrapper<VCGEdgeMesh>::IO_EDGEATTRIB;
|
||||
// mask |= nanoply::NanoPlyWrapper<VCGEdgeMesh>::IO_MESHATTRIB;
|
||||
if (!load(plyFilename)) {
|
||||
if (!VCGEdgeMesh::load(plyFilename)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -339,6 +337,7 @@ bool SimulationMesh::load(const string &plyFilename) {
|
|||
vcg::tri::UpdateTopology<SimulationMesh>::VertexEdge(*this);
|
||||
initializeNodes();
|
||||
initializeElements();
|
||||
setBeamMaterial(0.3, 1 * 1e9);
|
||||
updateEigenEdgeAndVertices();
|
||||
|
||||
// if (!handleBeamProperties._handle->data.empty()) {
|
||||
|
@ -398,7 +397,7 @@ bool SimulationMesh::save(const std::string &plyFilename)
|
|||
// != 1) {
|
||||
// return false;
|
||||
// }
|
||||
if (!save(plyFilename)) {
|
||||
if (!VCGEdgeMesh::save(plyFilename)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
|
|
@ -257,7 +257,8 @@ inline void init()
|
|||
polyscope::view::upDir = polyscope::view::UpDir::ZUp;
|
||||
|
||||
polyscope::state::userCallback = &mainCallback;
|
||||
// polyscope::options::autocenterStructures = true;
|
||||
polyscope::options::autocenterStructures = false;
|
||||
polyscope::options::autoscaleStructures = false;
|
||||
}
|
||||
using PolyscopeLabel = std::string;
|
||||
inline std::pair<PolyscopeLabel, size_t> getSelection()
|
||||
|
@ -275,9 +276,12 @@ inline void registerWorldAxes()
|
|||
|
||||
Eigen::MatrixX3d axesPositions(4, 3);
|
||||
axesPositions.row(0) = Eigen::Vector3d(0, 0, 0);
|
||||
axesPositions.row(1) = Eigen::Vector3d(polyscope::state::lengthScale, 0, 0);
|
||||
axesPositions.row(2) = Eigen::Vector3d(0, polyscope::state::lengthScale, 0);
|
||||
axesPositions.row(3) = Eigen::Vector3d(0, 0, polyscope::state::lengthScale);
|
||||
// axesPositions.row(1) = Eigen::Vector3d(polyscope::state::lengthScale, 0, 0);
|
||||
// axesPositions.row(2) = Eigen::Vector3d(0, polyscope::state::lengthScale, 0);
|
||||
// axesPositions.row(3) = Eigen::Vector3d(0, 0, polyscope::state::lengthScale);
|
||||
axesPositions.row(1) = Eigen::Vector3d(1, 0, 0);
|
||||
axesPositions.row(2) = Eigen::Vector3d(0, 1, 0);
|
||||
axesPositions.row(3) = Eigen::Vector3d(0, 0, 1);
|
||||
|
||||
Eigen::MatrixX2i axesEdges(3, 2);
|
||||
axesEdges.row(0) = Eigen::Vector2i(0, 1);
|
||||
|
|
Loading…
Reference in New Issue