Skip to content

Commit

Permalink
Revert "Revert "Multipop pressure anisotropy""
Browse files Browse the repository at this point in the history
This reverts commit 10e5207.
  • Loading branch information
lkotipal committed Nov 12, 2024
1 parent fda23d9 commit f132ec6
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 58 deletions.
54 changes: 36 additions & 18 deletions fieldsolver/derivatives.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -740,6 +740,32 @@ static Real calculateU(SpatialCell* cell)
(rho > EPS ? (pow(p[0], 2) + pow(p[1], 2) + pow(p[2], 2)) / (2.0 * cell->parameters[CellParams::RHOM]) : 0.0); // Kinetic energy
}

/*! \brief Calculates pressure anistotropy from B and P
* \param P elements of pressure order in order: P_11, P_22, P_33, P_23, P_13, P_12
*/
static Real calculateAnistropy(const std::array<Real, 3>& B, const std::array<Real, 6>& P)
{
// Now, rotation matrix to get parallel and perpendicular pressure
// Eigen::Quaterniond q {Quaterniond::FromTwoVectors(Eigen::vector3d{0, 0, 1}, Eigen::vector3d{myB[0], myB[1], myB[2]})};
// Eigen::Matrix3d rot = q.toRotationMatrix();
Eigen::Matrix3d rot = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d{B[0], B[1], B[2]}, Eigen::Vector3d{0, 0, 1}).normalized().toRotationMatrix();
Eigen::Matrix3d Ptensor {
{P[0], P[5], P[4]},
{P[5], P[1], P[3]},
{P[4], P[3], P[2]},
};

Eigen::Matrix3d transposerot = rot.transpose();
Eigen::Matrix3d Pprime = rot * Ptensor * transposerot;

Real Panisotropy {0.0};
if (Pprime(2, 2) > EPS) {
Panisotropy = (Pprime(0, 0) + Pprime(1, 1)) / (2 * Pprime(2, 2));
}

return Panisotropy;
}

/*! \brief Low-level scaled gradients calculation
*
* For the SpatialCell* cell and its neighbors, calculate scaled gradients and their maximum alpha
Expand Down Expand Up @@ -828,24 +854,6 @@ void calculateScaledDeltas(
Bperp = std::sqrt(Bperp);
}

// Now, rotation matrix to get parallel and perpendicular pressure
//Eigen::Quaterniond q {Quaterniond::FromTwoVectors(Eigen::vector3d{0, 0, 1}, Eigen::vector3d{myB[0], myB[1], myB[2]})};
//Eigen::Matrix3d rot = q.toRotationMatrix();
Eigen::Matrix3d rot = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d{myB[0], myB[1], myB[2]}, Eigen::Vector3d{0, 0, 1}).normalized().toRotationMatrix();
Eigen::Matrix3d P {
{cell->parameters[CellParams::P_11], cell->parameters[CellParams::P_12], cell->parameters[CellParams::P_13]},
{cell->parameters[CellParams::P_12], cell->parameters[CellParams::P_22], cell->parameters[CellParams::P_23]},
{cell->parameters[CellParams::P_13], cell->parameters[CellParams::P_23], cell->parameters[CellParams::P_33]},
};

Eigen::Matrix3d transposerot = rot.transpose();
Eigen::Matrix3d Pprime = rot * P * transposerot;

Real Panisotropy {0.0};
if (Pprime(2, 2) > EPS) {
Panisotropy = (Pprime(0, 0) + Pprime(1, 1)) / (2 * Pprime(2, 2));
}

// Vorticity
Real dVxdy {cell->derivativesV[vderivatives::dVxdy]};
Real dVxdz {cell->derivativesV[vderivatives::dVxdz]};
Expand All @@ -860,6 +868,16 @@ void calculateScaledDeltas(
amr_vorticity = vorticity * cell->parameters[CellParams::DX] / maxV;
}

std::array<Real, 6> myPressure {cell->parameters[CellParams::P_11], cell->parameters[CellParams::P_22], cell->parameters[CellParams::P_33], cell->parameters[CellParams::P_23], cell->parameters[CellParams::P_13], cell->parameters[CellParams::P_12]};
Real Panisotropy {calculateAnistropy(myB, myPressure)};
for (const auto& pop : cell->get_populations()) {
// TODO I hate this. Change all this crap to std::vectors?
std::array<Real, 6> popP {pop.P[0], pop.P[1], pop.P[2], pop.P[3], pop.P[4], pop.P[5]};
Real popPanisotropy {calculateAnistropy(myB, popP)};
// low value refines
Panisotropy = std::min(Panisotropy, popPanisotropy);
}

cell->parameters[CellParams::AMR_DRHO] = dRho;
cell->parameters[CellParams::AMR_DU] = dU;
cell->parameters[CellParams::AMR_DPSQ] = dPsq;
Expand Down
17 changes: 14 additions & 3 deletions spatial_cell_cpu.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,9 +156,9 @@ namespace spatial_cell {
Real V_R[3];
Real RHO_V;
Real V_V[3];
Real P[3];
Real P_R[3];
Real P_V[3];
Real P[6];
Real P_R[6];
Real P_V[6];
Real RHOLOSSADJUST = 0.0; /*!< Counter for particle number loss from the destroying blocks in blockadjustment*/
Real max_dt[2]; /**< Element[0] is max_r_dt, element[1] max_v_dt.*/
Real velocityBlockMinValue;
Expand Down Expand Up @@ -206,6 +206,9 @@ namespace spatial_cell {
const Population & get_population(const uint popID) const;
void set_population(const Population& pop, cuint popID);

std::vector<Population>& get_populations();
const std::vector<Population>& get_populations() const;

uint8_t get_maximum_refinement_level(const uint popID);
const Real& get_max_r_dt(const uint popID) const;
const Real& get_max_v_dt(const uint popID) const;
Expand Down Expand Up @@ -929,6 +932,14 @@ namespace spatial_cell {
this->populations[popID] = pop;
}

inline std::vector<Population>& SpatialCell::get_populations() {
return populations;
}

inline const std::vector<Population>& SpatialCell::get_populations() const {
return populations;
}

inline const vmesh::LocalID* SpatialCell::get_velocity_grid_length(const uint popID,const uint8_t& refLevel) {
return populations[popID].vmesh.getGridLength(refLevel);
}
Expand Down
73 changes: 38 additions & 35 deletions vlasovsolver/cpu_moments.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,17 +142,17 @@ void calculateCellMoments(spatial_cell::SpatialCell* cell,
}

// Store species' contribution to bulk velocity moments
pop.P[0] = mass*array[0];
pop.P[1] = mass*array[1];
pop.P[2] = mass*array[2];
for (size_t i = 0; i < array.size(); ++i) {
pop.P[i] = mass * array[i];
}

if (!computePopulationMomentsOnly) {
cell->parameters[CellParams::P_11] += mass * array[0];
cell->parameters[CellParams::P_22] += mass * array[1];
cell->parameters[CellParams::P_33] += mass * array[2];
cell->parameters[CellParams::P_23] += mass * array[3];
cell->parameters[CellParams::P_13] += mass * array[4];
cell->parameters[CellParams::P_12] += mass * array[5];
cell->parameters[CellParams::P_11] += pop.P[0];
cell->parameters[CellParams::P_22] += pop.P[1];
cell->parameters[CellParams::P_33] += pop.P[2];
cell->parameters[CellParams::P_23] += pop.P[3];
cell->parameters[CellParams::P_13] += pop.P[4];
cell->parameters[CellParams::P_12] += pop.P[5];
}
} // for-loop over particle species
}
Expand Down Expand Up @@ -199,9 +199,11 @@ void calculateMoments_R(
Population & pop = cell->get_population(popID);
if (blockContainer.size() == 0) {
pop.RHO_R = 0;
for (int i=0; i<3; ++i) {
pop.V_R[i]=0;
pop.P_R[i]=0;
for (int i = 0; i < 3; ++i) {
pop.V_R[i] = 0;
}
for (int i = 0; i < 6; ++i) {
pop.P_R[i] = 0;
}
continue;
}
Expand Down Expand Up @@ -297,16 +299,16 @@ void calculateMoments_R(
} // for-loop over velocity blocks

// Store species' contribution to 2nd bulk velocity moments
pop.P_R[0] = mass*array[0];
pop.P_R[1] = mass*array[1];
pop.P_R[2] = mass*array[2];

cell->parameters[CellParams::P_11_R] += mass * array[0];
cell->parameters[CellParams::P_22_R] += mass * array[1];
cell->parameters[CellParams::P_33_R] += mass * array[2];
cell->parameters[CellParams::P_23_R] += mass * array[3];
cell->parameters[CellParams::P_13_R] += mass * array[4];
cell->parameters[CellParams::P_12_R] += mass * array[5];
for (size_t i = 0; i < array.size(); ++i) {
pop.P_R[i] = mass * array[i];
}

cell->parameters[CellParams::P_11_R] += pop.P_R[0];
cell->parameters[CellParams::P_22_R] += pop.P_R[1];
cell->parameters[CellParams::P_33_R] += pop.P_R[2];
cell->parameters[CellParams::P_23_R] += pop.P_R[3];
cell->parameters[CellParams::P_13_R] += pop.P_R[4];
cell->parameters[CellParams::P_12_R] += pop.P_R[5];
} // for-loop over spatial cells
} // for-loop over particle species

Expand Down Expand Up @@ -356,9 +358,11 @@ void calculateMoments_V(
Population & pop = cell->get_population(popID);
if (blockContainer.size() == 0) {
pop.RHO_V = 0;
for (int i=0; i<3; ++i) {
pop.V_V[i]=0;
pop.P_V[i]=0;
for (int i = 0; i < 3; ++i) {
pop.V_V [i] = 0;
}
for (int i = 0; i < 6; ++i) {
pop.P_V [i] = 0;
}
continue;
}
Expand Down Expand Up @@ -441,17 +445,16 @@ void calculateMoments_V(
} // for-loop over velocity blocks

// Store species' contribution to 2nd bulk velocity moments
pop.P_V[0] = mass*array[0];
pop.P_V[1] = mass*array[1];
pop.P_V[2] = mass*array[2];

cell->parameters[CellParams::P_11_V] += mass * array[0];
cell->parameters[CellParams::P_22_V] += mass * array[1];
cell->parameters[CellParams::P_33_V] += mass * array[2];
cell->parameters[CellParams::P_23_V] += mass * array[3];
cell->parameters[CellParams::P_13_V] += mass * array[4];
cell->parameters[CellParams::P_12_V] += mass * array[5];
for (size_t i = 0; i < array.size(); ++i) {
pop.P_V[i] = mass * array[i];
}

cell->parameters[CellParams::P_11_V] += pop.P_V[0];
cell->parameters[CellParams::P_22_V] += pop.P_V[1];
cell->parameters[CellParams::P_33_V] += pop.P_V[2];
cell->parameters[CellParams::P_23_V] += pop.P_V[3];
cell->parameters[CellParams::P_13_V] += pop.P_V[4];
cell->parameters[CellParams::P_12_V] += pop.P_V[5];
} // for-loop over spatial cells
} // for-loop over particle species
}
6 changes: 4 additions & 2 deletions vlasovsolver/vlasovmover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -547,9 +547,11 @@ void calculateInterpolatedVelocityMoments(
for (uint popID=0; popID<getObjectWrapper().particleSpecies.size(); ++popID) {
spatial_cell::Population& pop = SC->get_population(popID);
pop.RHO = 0.5 * ( pop.RHO_R + pop.RHO_V );
for(int i=0; i<3; i++) {
for (int i = 0; i < 3; i++) {
pop.V[i] = 0.5 * ( pop.V_R[i] + pop.V_V[i] );
pop.P[i] = 0.5 * ( pop.P_R[i] + pop.P_V[i] );
}
for (int i = 0; i < 6; i++) {
pop.P[i] = 0.5 * ( pop.P_R[i] + pop.P_V[i] );
}
}
}
Expand Down

0 comments on commit f132ec6

Please sign in to comment.