Refactoring
This commit is contained in:
parent
96e63d15a3
commit
ef18646cfd
|
|
@ -427,8 +427,8 @@ SimulationResults DER_leimer::executeSimulation(const std::shared_ptr<Simulation
|
||||||
|
|
||||||
RodParams rodParams;
|
RodParams rodParams;
|
||||||
const double E = pJob->pMesh->getBeamMaterial()[0].youngsModulus;
|
const double E = pJob->pMesh->getBeamMaterial()[0].youngsModulus;
|
||||||
const double w = pJob->pMesh->getBeamDimensions()[0].b;
|
const double w = pJob->pMesh->getBeamDimensions()[0].getDim1();
|
||||||
const double h = pJob->pMesh->getBeamDimensions()[0].h;
|
const double h = pJob->pMesh->getBeamDimensions()[0].getDim2();
|
||||||
rodParams.thickness = h;
|
rodParams.thickness = h;
|
||||||
rodParams.kbending = E;
|
rodParams.kbending = E;
|
||||||
rodParams.kstretching = E;
|
rodParams.kstretching = E;
|
||||||
|
|
@ -455,6 +455,13 @@ SimulationResults DER_leimer::executeSimulation(const std::shared_ptr<Simulation
|
||||||
rodParamsPerRod,
|
rodParamsPerRod,
|
||||||
anchors);
|
anchors);
|
||||||
|
|
||||||
|
// assert(config->numIntersections() == 0);
|
||||||
|
|
||||||
|
// pRod = std::make_unique<ElasticRod>(verts);
|
||||||
|
// const auto cs = CrossSection::construct("rectangle", E, poissonsRatio, {w, h});
|
||||||
|
// RodMaterial mat(*cs);
|
||||||
|
// pRod->setMaterial(mat);
|
||||||
|
|
||||||
bool done = false;
|
bool done = false;
|
||||||
while (!done) {
|
while (!done) {
|
||||||
done = simulateOneStepGrid(config);
|
done = simulateOneStepGrid(config);
|
||||||
|
|
@ -567,6 +574,19 @@ bool DER_leimer::simulateOneStepGrid(RodConfig *config)
|
||||||
forceResidual = lineSearchGrid(*config, updateVec, params, externalForces);
|
forceResidual = lineSearchGrid(*config, updateVec, params, externalForces);
|
||||||
std::cout << "Force residual: " << forceResidual << std::endl;
|
std::cout << "Force residual: " << forceResidual << std::endl;
|
||||||
|
|
||||||
|
//panetta's rod update
|
||||||
|
// assert(config->numIntersections() == 0);
|
||||||
|
std::vector<Eigen::Vector3d> vertexPositions(config->numVertices());
|
||||||
|
for (int vi = 0; vi < config->numVertices(); vi++) {
|
||||||
|
vertexPositions[vi] = config->vertices.row(vi);
|
||||||
|
}
|
||||||
|
std::vector<double> thetas(config->numRods());
|
||||||
|
for (int ri = 0; ri < config->numRods(); ri++) {
|
||||||
|
assert(config->rods[ri]->numSegments() == 1);
|
||||||
|
thetas[ri] = config->rods[ri]->curState.thetas[0];
|
||||||
|
}
|
||||||
|
// pRod->setDeformedConfiguration(vertexPositions, thetas);
|
||||||
|
|
||||||
rAndJGrid(*config, r, &Jr, linE, gravityForces, params, externalForcesPE, externalForces);
|
rAndJGrid(*config, r, &Jr, linE, gravityForces, params, externalForcesPE, externalForces);
|
||||||
|
|
||||||
iter++;
|
iter++;
|
||||||
|
|
@ -4346,7 +4366,7 @@ DER_leimer::RodConfig *DER_leimer::readRodGrid(
|
||||||
}
|
}
|
||||||
|
|
||||||
Eigen::VectorXd segmentWidths_eigen(numSegments_rod);
|
Eigen::VectorXd segmentWidths_eigen(numSegments_rod);
|
||||||
const double rodWidth = pMesh->elements[rodIndex].dimensions.b;
|
const double rodWidth = pMesh->elements[rodIndex].dimensions.getDim1();
|
||||||
for (int si_rod = 0; si_rod < numSegments_rod; si_rod++) {
|
for (int si_rod = 0; si_rod < numSegments_rod; si_rod++) {
|
||||||
segmentWidths_eigen[si_rod] = rodWidth;
|
segmentWidths_eigen[si_rod] = rodWidth;
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -1,6 +1,7 @@
|
||||||
#ifndef DER_LEIMER_HPP
|
#ifndef DER_LEIMER_HPP
|
||||||
#define DER_LEIMER_HPP
|
#define DER_LEIMER_HPP
|
||||||
|
|
||||||
|
//#include "ElasticRod.hh"
|
||||||
#include "simulationmodel.hpp"
|
#include "simulationmodel.hpp"
|
||||||
#include <Eigen/Sparse>
|
#include <Eigen/Sparse>
|
||||||
|
|
||||||
|
|
@ -8,7 +9,7 @@ class DER_leimer : public SimulationModel
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
DER_leimer();
|
DER_leimer();
|
||||||
virtual SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob);
|
virtual SimulationResults executeSimulation(const std::shared_ptr<SimulationJob> &pJob) override;
|
||||||
struct RodParams
|
struct RodParams
|
||||||
{
|
{
|
||||||
double thickness;
|
double thickness;
|
||||||
|
|
@ -175,15 +176,17 @@ private:
|
||||||
const Eigen::VectorXd &update,
|
const Eigen::VectorXd &update,
|
||||||
const SimParams ¶ms,
|
const SimParams ¶ms,
|
||||||
const Eigen::VectorXd &externalForces = Eigen::VectorXd());
|
const Eigen::VectorXd &externalForces = Eigen::VectorXd());
|
||||||
|
SimulationResults constructSimulationResults(const std::shared_ptr<SimulationJob> &pJob,
|
||||||
|
RodConfig *config) const;
|
||||||
|
Eigen::Vector3d getPerpendicularVector(const Eigen::Vector3d &t) const;
|
||||||
|
|
||||||
double energy;
|
double energy;
|
||||||
Eigen::VectorXd updateVec;
|
Eigen::VectorXd updateVec;
|
||||||
double forceResidual;
|
double forceResidual;
|
||||||
int iter{0};
|
int iter{0};
|
||||||
SimulationResults constructSimulationResults(const std::shared_ptr<SimulationJob> &pJob,
|
|
||||||
RodConfig *config) const;
|
|
||||||
std::shared_ptr<SimulationJob> pJob;
|
std::shared_ptr<SimulationJob> pJob;
|
||||||
Eigen::Vector3d getPerpendicularVector(const Eigen::Vector3d &t) const;
|
|
||||||
|
// std::unique_ptr<ElasticRod> pRod;
|
||||||
};
|
};
|
||||||
|
|
||||||
Eigen::Matrix3d eulerRotation(double e0, double e1, double e2, int deriv = -1, int deriv2 = -1);
|
Eigen::Matrix3d eulerRotation(double e0, double e1, double e2, int deriv = -1, int deriv2 = -1);
|
||||||
|
|
|
||||||
|
|
@ -202,7 +202,7 @@ bool VCGEdgeMesh::createSpanGrid(const size_t desiredWidth,
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool VCGEdgeMesh::load(const std::filesystem::__cxx11::path &meshFilePath)
|
bool VCGEdgeMesh::load(const std::filesystem::path &meshFilePath)
|
||||||
{
|
{
|
||||||
std::string usedPath = meshFilePath;
|
std::string usedPath = meshFilePath;
|
||||||
if (std::filesystem::path(meshFilePath).is_relative()) {
|
if (std::filesystem::path(meshFilePath).is_relative()) {
|
||||||
|
|
|
||||||
|
|
@ -7,7 +7,6 @@ property float z { z coordinate, too }
|
||||||
property float nx
|
property float nx
|
||||||
property float ny
|
property float ny
|
||||||
property float nz
|
property float nz
|
||||||
|
|
||||||
element edge 4 { there are 6 "face" elements in the file }
|
element edge 4 { there are 6 "face" elements in the file }
|
||||||
property int vertex1
|
property int vertex1
|
||||||
property int vertex2
|
property int vertex2
|
||||||
|
|
|
||||||
|
|
@ -8,6 +8,9 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
#ifdef POLYSCOPE_DEFINED
|
||||||
|
#include <polyscope/point_cloud.h>
|
||||||
|
#endif
|
||||||
namespace Eigen {
|
namespace Eigen {
|
||||||
template <class Matrix>
|
template <class Matrix>
|
||||||
void write_binary(const std::string &filename, const Matrix &matrix) {
|
void write_binary(const std::string &filename, const Matrix &matrix) {
|
||||||
|
|
@ -157,7 +160,11 @@ class SimulationJob {
|
||||||
// simulation mesh class
|
// simulation mesh class
|
||||||
} jsonLabels;
|
} jsonLabels;
|
||||||
|
|
||||||
public:
|
#ifdef POLYSCOPE_DEFINED
|
||||||
|
const std::string polyscopeLabel_bcAsPointCloud{"BC_spheres"};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
public:
|
||||||
inline static std::string jsonDefaultFileName = "SimulationJob.json";
|
inline static std::string jsonDefaultFileName = "SimulationJob.json";
|
||||||
std::shared_ptr<SimulationMesh> pMesh;
|
std::shared_ptr<SimulationMesh> pMesh;
|
||||||
std::string label{"empty_job"};
|
std::string label{"empty_job"};
|
||||||
|
|
@ -173,7 +180,10 @@ public:
|
||||||
nodalForcedDisplacements(fd)
|
nodalForcedDisplacements(fd)
|
||||||
{}
|
{}
|
||||||
SimulationJob() {}
|
SimulationJob() {}
|
||||||
SimulationJob(const std::string &jsonFilename) { load(jsonFilename); }
|
SimulationJob(const std::string &jsonFilename)
|
||||||
|
{
|
||||||
|
load(jsonFilename);
|
||||||
|
}
|
||||||
|
|
||||||
bool isEmpty()
|
bool isEmpty()
|
||||||
{
|
{
|
||||||
|
|
@ -470,6 +480,7 @@ json[jsonLabels.meshFilename]= std::filesystem::relative(std::filesystem::path(m
|
||||||
->addNodeColorQuantity("Boundary conditions", nodeColors)
|
->addNodeColorQuantity("Boundary conditions", nodeColors)
|
||||||
->setEnabled(shouldEnable);
|
->setEnabled(shouldEnable);
|
||||||
}
|
}
|
||||||
|
drawBcAsSpheres();
|
||||||
|
|
||||||
// per node external forces
|
// per node external forces
|
||||||
std::vector<std::array<double, 3>> externalForces(pMesh->VN());
|
std::vector<std::array<double, 3>> externalForces(pMesh->VN());
|
||||||
|
|
@ -509,7 +520,7 @@ json[jsonLabels.meshFilename]= std::filesystem::relative(std::filesystem::path(m
|
||||||
->setEnabled(shouldEnable);
|
->setEnabled(shouldEnable);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void unregister(const std::string &meshLabel)
|
void unregister(const std::string &meshLabel) const
|
||||||
{
|
{
|
||||||
if (polyscope::getCurveNetwork(meshLabel) == nullptr) {
|
if (polyscope::getCurveNetwork(meshLabel) == nullptr) {
|
||||||
return;
|
return;
|
||||||
|
|
@ -519,6 +530,7 @@ json[jsonLabels.meshFilename]= std::filesystem::relative(std::filesystem::path(m
|
||||||
}
|
}
|
||||||
if (!constrainedVertices.empty()) {
|
if (!constrainedVertices.empty()) {
|
||||||
polyscope::getCurveNetwork(meshLabel)->removeQuantity("Boundary conditions");
|
polyscope::getCurveNetwork(meshLabel)->removeQuantity("Boundary conditions");
|
||||||
|
polyscope::removeStructure(polyscopeLabel_bcAsPointCloud, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
// per node external moments
|
// per node external moments
|
||||||
|
|
@ -534,6 +546,38 @@ json[jsonLabels.meshFilename]= std::filesystem::relative(std::filesystem::path(m
|
||||||
polyscope::getCurveNetwork(meshLabel)->removeQuantity("External moment");
|
polyscope::getCurveNetwork(meshLabel)->removeQuantity("External moment");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void drawBcAsSpheres() const
|
||||||
|
{
|
||||||
|
polyscope::removeStructure(polyscopeLabel_bcAsPointCloud, false);
|
||||||
|
std::vector<glm::vec3> bcPos;
|
||||||
|
std::vector<glm::vec3> bcColors;
|
||||||
|
for (std::pair<VertexIndex, std::unordered_set<int>> bc : constrainedVertices) {
|
||||||
|
bcPos.push_back(glm::vec3(pMesh->vert[bc.first].cP()[0],
|
||||||
|
pMesh->vert[bc.first].cP()[1],
|
||||||
|
pMesh->vert[bc.first].cP()[2]));
|
||||||
|
const bool hasRotationalDoFConstrained = bc.second.contains(3) || bc.second.contains(4)
|
||||||
|
|| bc.second.contains(5);
|
||||||
|
const bool hasTranslationalDoFConstrained = bc.second.contains(0) || bc.second.contains(1)
|
||||||
|
|| bc.second.contains(2);
|
||||||
|
|
||||||
|
std::array<double, 3> color_fixedTranslation{63.0 / 255, 191.0 / 255, 127.0 / 255};
|
||||||
|
std::array<double, 3> color_rigid({1, 0, 0});
|
||||||
|
if (hasTranslationalDoFConstrained && !hasRotationalDoFConstrained) {
|
||||||
|
bcColors.push_back(glm::vec3(color_fixedTranslation[0],
|
||||||
|
color_fixedTranslation[1],
|
||||||
|
color_fixedTranslation[2]));
|
||||||
|
} else if (!hasTranslationalDoFConstrained && hasRotationalDoFConstrained) {
|
||||||
|
bcColors.push_back(glm::vec3(0, 0, 1));
|
||||||
|
} else {
|
||||||
|
bcColors.push_back(glm::vec3(color_rigid[0], color_rigid[1], color_rigid[2]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
auto bcPolyscopePointCloud = polyscope::registerPointCloud(polyscopeLabel_bcAsPointCloud,
|
||||||
|
bcPos);
|
||||||
|
bcPolyscopePointCloud->addColorQuantity("bc_colors", bcColors)->setEnabled(true);
|
||||||
|
}
|
||||||
#endif // POLYSCOPE_DEFINED
|
#endif // POLYSCOPE_DEFINED
|
||||||
};
|
};
|
||||||
struct SimulationResults
|
struct SimulationResults
|
||||||
|
|
@ -554,6 +598,7 @@ struct SimulationResults
|
||||||
double internalPotentialEnergy{0};
|
double internalPotentialEnergy{0};
|
||||||
double executionTime{0};
|
double executionTime{0};
|
||||||
std::vector<std::array<Vector6d, 4>> perVertexInternalForces; //axial,torsion,bending1,bending2
|
std::vector<std::array<Vector6d, 4>> perVertexInternalForces; //axial,torsion,bending1,bending2
|
||||||
|
std::string simulationModelUsed{"empty label"};
|
||||||
std::string labelPrefix{"deformed"};
|
std::string labelPrefix{"deformed"};
|
||||||
inline static char deliminator{' '};
|
inline static char deliminator{' '};
|
||||||
SimulationResults() { pJob = std::make_shared<SimulationJob>(); }
|
SimulationResults() { pJob = std::make_shared<SimulationJob>(); }
|
||||||
|
|
@ -572,7 +617,8 @@ struct SimulationResults
|
||||||
void setLabelPrefix(const std::string &lp) { labelPrefix += deliminator + lp; }
|
void setLabelPrefix(const std::string &lp) { labelPrefix += deliminator + lp; }
|
||||||
std::string getLabel() const
|
std::string getLabel() const
|
||||||
{
|
{
|
||||||
return labelPrefix + deliminator + pJob->pMesh->getLabel() + deliminator + pJob->getLabel();
|
return labelPrefix + deliminator + simulationModelUsed + deliminator
|
||||||
|
+ pJob->pMesh->getLabel() + deliminator + pJob->getLabel();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool saveDeformedModel(const std::string &outputFolder = std::string())
|
bool saveDeformedModel(const std::string &outputFolder = std::string())
|
||||||
|
|
@ -742,46 +788,51 @@ struct SimulationResults
|
||||||
pJob->unregister(getLabel());
|
pJob->unregister(getLabel());
|
||||||
polyscope::removeCurveNetwork(getLabel());
|
polyscope::removeCurveNetwork(getLabel());
|
||||||
}
|
}
|
||||||
|
|
||||||
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 bool &shouldEnable = true,
|
const bool &shouldEnable = true /*,
|
||||||
const double &desiredRadius = 0.001,
|
const bool &shouldShowFrames = false*/) const
|
||||||
// const double &desiredRadius = 0.0001,
|
|
||||||
const bool &shouldShowFrames = false) const
|
|
||||||
{
|
{
|
||||||
|
if (!converged) {
|
||||||
|
std::cerr << "Simulation did not converge. Drawing nothing." << std::endl;
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
PolyscopeInterface::init();
|
PolyscopeInterface::init();
|
||||||
const std::shared_ptr<SimulationMesh> &mesh = pJob->pMesh;
|
const std::shared_ptr<SimulationMesh> &simulationMesh = pJob->pMesh;
|
||||||
polyscope::CurveNetwork *polyscopeHandle_deformedEdmeMesh;
|
polyscope::CurveNetwork *polyscopeHandle_deformedEdmeMesh;
|
||||||
if (!polyscope::hasStructure(getLabel())) {
|
const std::string &meshLabel = getLabel();
|
||||||
const auto verts = mesh->getEigenVertices();
|
if (!polyscope::hasStructure(meshLabel)) {
|
||||||
const auto edges = mesh->getEigenEdges();
|
const auto &verts = simulationMesh->getEigenVertices();
|
||||||
polyscopeHandle_deformedEdmeMesh = polyscope::registerCurveNetwork(getLabel(),
|
const auto &edges = simulationMesh->getEigenEdges();
|
||||||
|
polyscopeHandle_deformedEdmeMesh = polyscope::registerCurveNetwork(meshLabel,
|
||||||
verts,
|
verts,
|
||||||
edges);
|
edges);
|
||||||
} else {
|
} else {
|
||||||
polyscopeHandle_deformedEdmeMesh = polyscope::getCurveNetwork(getLabel());
|
polyscopeHandle_deformedEdmeMesh = polyscope::getCurveNetwork(meshLabel);
|
||||||
}
|
}
|
||||||
polyscopeHandle_deformedEdmeMesh->setEnabled(shouldEnable);
|
polyscopeHandle_deformedEdmeMesh->setEnabled(shouldEnable);
|
||||||
polyscopeHandle_deformedEdmeMesh->setRadius(desiredRadius, true);
|
const double drawingRadius = simulationMesh->getBeamDimensions()[0].getDrawingRadius();
|
||||||
|
polyscopeHandle_deformedEdmeMesh->setRadius(drawingRadius /*0.00025*/, false);
|
||||||
if (desiredColor.has_value()) {
|
if (desiredColor.has_value()) {
|
||||||
const glm::vec3 desiredColor_glm(desiredColor.value()[0],
|
const glm::vec3 desiredColor_glm(desiredColor.value()[0],
|
||||||
desiredColor.value()[1],
|
desiredColor.value()[1],
|
||||||
desiredColor.value()[2]);
|
desiredColor.value()[2]);
|
||||||
polyscopeHandle_deformedEdmeMesh->setColor(/*glm::normalize(*/ desiredColor_glm /*)*/);
|
polyscopeHandle_deformedEdmeMesh->setColor(desiredColor_glm);
|
||||||
}
|
}
|
||||||
Eigen::MatrixX3d nodalDisplacements(mesh->VN(), 3);
|
Eigen::MatrixX3d nodalDisplacements(simulationMesh->VN(), 3);
|
||||||
Eigen::MatrixX3d framesX(mesh->VN(), 3);
|
Eigen::MatrixX3d framesX(simulationMesh->VN(), 3);
|
||||||
Eigen::MatrixX3d framesY(mesh->VN(), 3);
|
Eigen::MatrixX3d framesY(simulationMesh->VN(), 3);
|
||||||
Eigen::MatrixX3d framesZ(mesh->VN(), 3);
|
Eigen::MatrixX3d framesZ(simulationMesh->VN(), 3);
|
||||||
|
|
||||||
Eigen::MatrixX3d framesX_initial(mesh->VN(), 3);
|
Eigen::MatrixX3d framesX_initial(simulationMesh->VN(), 3);
|
||||||
Eigen::MatrixX3d framesY_initial(mesh->VN(), 3);
|
Eigen::MatrixX3d framesY_initial(simulationMesh->VN(), 3);
|
||||||
Eigen::MatrixX3d framesZ_initial(mesh->VN(), 3);
|
Eigen::MatrixX3d framesZ_initial(simulationMesh->VN(), 3);
|
||||||
|
|
||||||
// std::unordered_set<int> interfaceNodes{1, 3, 5, 7, 9, 11};
|
// 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{};
|
// std::unordered_set<int> interfaceNodes{};
|
||||||
for (VertexIndex vi = 0; vi < mesh->VN(); vi++) {
|
for (VertexIndex vi = 0; vi < simulationMesh->VN(); vi++) {
|
||||||
const Vector6d &nodalDisplacement = displacements[vi];
|
const Vector6d &nodalDisplacement = displacements[vi];
|
||||||
nodalDisplacements.row(vi) = Eigen::Vector3d(nodalDisplacement[0],
|
nodalDisplacements.row(vi) = Eigen::Vector3d(nodalDisplacement[0],
|
||||||
nodalDisplacement[1],
|
nodalDisplacement[1],
|
||||||
|
|
@ -790,10 +841,14 @@ struct SimulationResults
|
||||||
// Eigen::Quaternion<double> Ry(Eigen::AngleAxis(nodalDisplacement[4],Eigen::Vector3d(0, 1, 0)));
|
// Eigen::Quaternion<double> Ry(Eigen::AngleAxis(nodalDisplacement[4],Eigen::Vector3d(0, 1, 0)));
|
||||||
// Eigen::Quaternion<double> Rz(Eigen::AngleAxis(nodalDisplacement[5],Eigen::Vector3d(0, 0, 1)));
|
// Eigen::Quaternion<double> Rz(Eigen::AngleAxis(nodalDisplacement[5],Eigen::Vector3d(0, 0, 1)));
|
||||||
// Eigen::Quaternion<double> R=Rx*Ry*Rz;
|
// Eigen::Quaternion<double> R=Rx*Ry*Rz;
|
||||||
// if (interfaceNodes.contains(vi)) {
|
if (interfaceNodes.contains(vi)) {
|
||||||
auto deformedNormal = rotationalDisplacementQuaternion[vi] * Eigen::Vector3d(0, 0, 1);
|
assert(!rotationalDisplacementQuaternion.empty());
|
||||||
auto deformedFrameY = rotationalDisplacementQuaternion[vi] * Eigen::Vector3d(0, 1, 0);
|
auto deformedNormal = rotationalDisplacementQuaternion[vi]
|
||||||
auto deformedFrameX = rotationalDisplacementQuaternion[vi] * Eigen::Vector3d(1, 0, 0);
|
* Eigen::Vector3d(0, 0, 1);
|
||||||
|
auto deformedFrameY = rotationalDisplacementQuaternion[vi]
|
||||||
|
* Eigen::Vector3d(0, 1, 0);
|
||||||
|
auto deformedFrameX = rotationalDisplacementQuaternion[vi]
|
||||||
|
* Eigen::Vector3d(1, 0, 0);
|
||||||
framesX.row(vi) = Eigen::Vector3d(deformedFrameX[0],
|
framesX.row(vi) = Eigen::Vector3d(deformedFrameX[0],
|
||||||
deformedFrameX[1],
|
deformedFrameX[1],
|
||||||
deformedFrameX[2]);
|
deformedFrameX[2]);
|
||||||
|
|
@ -806,16 +861,16 @@ struct SimulationResults
|
||||||
framesX_initial.row(vi) = Eigen::Vector3d(1, 0, 0);
|
framesX_initial.row(vi) = Eigen::Vector3d(1, 0, 0);
|
||||||
framesY_initial.row(vi) = Eigen::Vector3d(0, 1, 0);
|
framesY_initial.row(vi) = Eigen::Vector3d(0, 1, 0);
|
||||||
framesZ_initial.row(vi) = Eigen::Vector3d(0, 0, 1);
|
framesZ_initial.row(vi) = Eigen::Vector3d(0, 0, 1);
|
||||||
// } else {
|
} else {
|
||||||
// framesX.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesX.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// framesY.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesY.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// framesZ.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesZ.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// framesX_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesX_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// framesY_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesY_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// framesZ_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
framesZ_initial.row(vi) = Eigen::Vector3d(0, 0, 0);
|
||||||
// }
|
|
||||||
}
|
}
|
||||||
polyscopeHandle_deformedEdmeMesh->updateNodePositions(mesh->getEigenVertices()
|
}
|
||||||
|
polyscopeHandle_deformedEdmeMesh->updateNodePositions(simulationMesh->getEigenVertices()
|
||||||
+ nodalDisplacements);
|
+ nodalDisplacements);
|
||||||
|
|
||||||
const double frameRadius_default = 0.035;
|
const double frameRadius_default = 0.035;
|
||||||
|
|
|
||||||
|
|
@ -257,9 +257,7 @@ void SimulationMesh::updateElementalFrames() {
|
||||||
polyscope::CurveNetwork *SimulationMesh::registerForDrawing(
|
polyscope::CurveNetwork *SimulationMesh::registerForDrawing(
|
||||||
const std::optional<std::array<double, 3>> &desiredColor, const bool &shouldEnable)
|
const std::optional<std::array<double, 3>> &desiredColor, const bool &shouldEnable)
|
||||||
{
|
{
|
||||||
const double drawingRadius = getBeamDimensions()[0].b
|
const double drawingRadius = getBeamDimensions()[0].getDrawingRadius();
|
||||||
/ (std::sqrt(
|
|
||||||
2.0)); //polyscope can only draw a circular cross section
|
|
||||||
// std::cout << __FUNCTION__ << " revert this" << std::endl;
|
// std::cout << __FUNCTION__ << " revert this" << std::endl;
|
||||||
return VCGEdgeMesh::registerForDrawing(desiredColor, /*0.08*/ drawingRadius, shouldEnable);
|
return VCGEdgeMesh::registerForDrawing(desiredColor, /*0.08*/ drawingRadius, shouldEnable);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue