Skip to content

Commit

Permalink
Merge pull request #238 from Exawind/qu_to_elem_integration
Browse files Browse the repository at this point in the history
Changed quadrature point variables in Beams to be per-element
  • Loading branch information
ddement authored Aug 13, 2024
2 parents a1d3a95 + 6efeec5 commit 7e3adb0
Show file tree
Hide file tree
Showing 54 changed files with 1,139 additions and 1,355 deletions.
144 changes: 72 additions & 72 deletions src/restruct_poc/beams/beams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,43 +47,43 @@ struct Beams {
View_Nx6 node_FX; // External forces

// Quadrature point data
View_NxN qp_weight; // Integration weights
View_NxN qp_jacobian; // Jacobian vector
View_Nx6x6 qp_Mstar; // Mass matrix in material frame
View_Nx6x6 qp_Cstar; // Stiffness matrix in material frame
View_Nx3 qp_x0; // Initial position
View_Nx3 qp_x0_prime; // Initial position derivative
View_Nx4 qp_r0; // Initial rotation
View_Nx3 qp_u; // State: translation displacement
View_Nx3 qp_u_prime; // State: translation displacement derivative
View_Nx3 qp_u_dot; // State: translation velocity
View_Nx3 qp_u_ddot; // State: translation acceleration
View_Nx4 qp_r; // State: rotation
View_Nx4 qp_r_prime; // State: rotation derivative
View_Nx3 qp_omega; // State: angular velocity
View_Nx3 qp_omega_dot; // State: position/rotation
View_Nx3x4 qp_E; // Quaternion derivative
View_Nx3x3 qp_eta_tilde; //
View_Nx3x3 qp_omega_tilde; //
View_Nx3x3 qp_omega_dot_tilde; //
View_Nx3x3 qp_x0pupss; //
View_Nx3x3 qp_M_tilde; //
View_Nx3x3 qp_N_tilde; //
View_Nx3 qp_eta; //
View_Nx3x3 qp_rho; //
View_Nx6 qp_strain; // Strain
View_Nx6 qp_Fc; // Elastic force
View_Nx6 qp_Fd; // Elastic force
View_Nx6 qp_Fi; // Inertial force
View_Nx6 qp_Fg; // Gravity force
View_Nx6x6 qp_RR0; // Global rotation
View_Nx6x6 qp_Muu; // Mass in global frame
View_Nx6x6 qp_Cuu; // Stiffness in global frame
View_Nx6x6 qp_Ouu; // Linearization matrices
View_Nx6x6 qp_Puu; // Linearization matrices
View_Nx6x6 qp_Quu; // Linearization matrices
View_Nx6x6 qp_Guu; // Linearization matrices
View_Nx6x6 qp_Kuu; // Linearization matrices
View_NxN qp_weight; // Integration weights
View_NxN qp_jacobian; // Jacobian vector
Kokkos::View<double** [6][6]> qp_Mstar; // Mass matrix in material frame
Kokkos::View<double** [6][6]> qp_Cstar; // Stiffness matrix in material frame
Kokkos::View<double** [3]> qp_x0; // Initial position
Kokkos::View<double** [3]> qp_x0_prime; // Initial position derivative
Kokkos::View<double** [4]> qp_r0; // Initial rotation
Kokkos::View<double** [3]> qp_u; // State: translation displacement
Kokkos::View<double** [3]> qp_u_prime; // State: translation displacement derivative
Kokkos::View<double** [3]> qp_u_dot; // State: translation velocity
Kokkos::View<double** [3]> qp_u_ddot; // State: translation acceleration
Kokkos::View<double** [4]> qp_r; // State: rotation
Kokkos::View<double** [4]> qp_r_prime; // State: rotation derivative
Kokkos::View<double** [3]> qp_omega; // State: angular velocity
Kokkos::View<double** [3]> qp_omega_dot; // State: position/rotation
Kokkos::View<double** [3][4]> qp_E; // Quaternion derivative
Kokkos::View<double** [3][3]> qp_eta_tilde; //
Kokkos::View<double** [3][3]> qp_omega_tilde; //
Kokkos::View<double** [3][3]> qp_omega_dot_tilde; //
Kokkos::View<double** [3][3]> qp_x0pupss; //
Kokkos::View<double** [3][3]> qp_M_tilde; //
Kokkos::View<double** [3][3]> qp_N_tilde; //
Kokkos::View<double** [3]> qp_eta; //
Kokkos::View<double** [3][3]> qp_rho; //
Kokkos::View<double** [6]> qp_strain; // Strain
Kokkos::View<double** [6]> qp_Fc; // Elastic force
Kokkos::View<double** [6]> qp_Fd; // Elastic force
Kokkos::View<double** [6]> qp_Fi; // Inertial force
Kokkos::View<double** [6]> qp_Fg; // Gravity force
Kokkos::View<double** [6][6]> qp_RR0; // Global rotation
Kokkos::View<double** [6][6]> qp_Muu; // Mass in global frame
Kokkos::View<double** [6][6]> qp_Cuu; // Stiffness in global frame
Kokkos::View<double** [6][6]> qp_Ouu; // Linearization matrices
Kokkos::View<double** [6][6]> qp_Puu; // Linearization matrices
Kokkos::View<double** [6][6]> qp_Quu; // Linearization matrices
Kokkos::View<double** [6][6]> qp_Guu; // Linearization matrices
Kokkos::View<double** [6][6]> qp_Kuu; // Linearization matrices

Kokkos::View<double***> shape_interp; // shape function matrix for interpolation [Nodes x QPs]
Kokkos::View<double***>
Expand Down Expand Up @@ -115,41 +115,41 @@ struct Beams {
// Quadrature Point data
qp_weight("qp_weight", n_beams, max_elem_qps),
qp_jacobian("qp_jacobian", n_beams, max_elem_qps),
qp_Mstar("qp_Mstar", n_qps),
qp_Cstar("qp_Cstar", n_qps),
qp_x0("qp_x0", n_qps),
qp_x0_prime("qp_x0_prime", n_qps),
qp_r0("qp_r0", n_qps),
qp_u("qp_u", n_qps),
qp_u_prime("qp_u_prime", n_qps),
qp_u_dot("qp_u_dot", n_qps),
qp_u_ddot("qp_u_ddot", n_qps),
qp_r("qp_r", n_qps),
qp_r_prime("qp_r_prime", n_qps),
qp_omega("qp_omega", n_qps),
qp_omega_dot("qp_omega_dot", n_qps),
qp_E("qp_E", n_qps),
qp_eta_tilde("R1_3x3", n_qps),
qp_omega_tilde("R1_3x3", n_qps),
qp_omega_dot_tilde("R1_3x3", n_qps),
qp_x0pupss("R1_3x3", n_qps),
qp_M_tilde("R1_3x3", n_qps),
qp_N_tilde("R1_3x3", n_qps),
qp_eta("V_3", n_qps),
qp_rho("R1_3x3", n_qps),
qp_strain("qp_strain", n_qps),
qp_Fc("qp_Fc", n_qps),
qp_Fd("qp_Fd", n_qps),
qp_Fi("qp_Fi", n_qps),
qp_Fg("qp_Fg", n_qps),
qp_RR0("qp_RR0", n_qps),
qp_Muu("qp_Muu", n_qps),
qp_Cuu("qp_Cuu", n_qps),
qp_Ouu("qp_Ouu", n_qps),
qp_Puu("qp_Puu", n_qps),
qp_Quu("qp_Quu", n_qps),
qp_Guu("qp_Guu", n_qps),
qp_Kuu("qp_Kuu", n_qps),
qp_Mstar("qp_Mstar", n_beams, max_elem_qps),
qp_Cstar("qp_Cstar", n_beams, max_elem_qps),
qp_x0("qp_x0", n_beams, max_elem_qps),
qp_x0_prime("qp_x0_prime", n_beams, max_elem_qps),
qp_r0("qp_r0", n_beams, max_elem_qps),
qp_u("qp_u", n_beams, max_elem_qps),
qp_u_prime("qp_u_prime", n_beams, max_elem_qps),
qp_u_dot("qp_u_dot", n_beams, max_elem_qps),
qp_u_ddot("qp_u_ddot", n_beams, max_elem_qps),
qp_r("qp_r", n_beams, max_elem_qps),
qp_r_prime("qp_r_prime", n_beams, max_elem_qps),
qp_omega("qp_omega", n_beams, max_elem_qps),
qp_omega_dot("qp_omega_dot", n_beams, max_elem_qps),
qp_E("qp_E", n_beams, max_elem_qps),
qp_eta_tilde("R1_3x3", n_beams, max_elem_qps),
qp_omega_tilde("R1_3x3", n_beams, max_elem_qps),
qp_omega_dot_tilde("R1_3x3", n_beams, max_elem_qps),
qp_x0pupss("R1_3x3", n_beams, max_elem_qps),
qp_M_tilde("R1_3x3", n_beams, max_elem_qps),
qp_N_tilde("R1_3x3", n_beams, max_elem_qps),
qp_eta("V_3", n_beams, max_elem_qps),
qp_rho("R1_3x3", n_beams, max_elem_qps),
qp_strain("qp_strain", n_beams, max_elem_qps),
qp_Fc("qp_Fc", n_beams, max_elem_qps),
qp_Fd("qp_Fd", n_beams, max_elem_qps),
qp_Fi("qp_Fi", n_beams, max_elem_qps),
qp_Fg("qp_Fg", n_beams, max_elem_qps),
qp_RR0("qp_RR0", n_beams, max_elem_qps),
qp_Muu("qp_Muu", n_beams, max_elem_qps),
qp_Cuu("qp_Cuu", n_beams, max_elem_qps),
qp_Ouu("qp_Ouu", n_beams, max_elem_qps),
qp_Puu("qp_Puu", n_beams, max_elem_qps),
qp_Quu("qp_Quu", n_beams, max_elem_qps),
qp_Guu("qp_Guu", n_beams, max_elem_qps),
qp_Kuu("qp_Kuu", n_beams, max_elem_qps),
shape_interp("shape_interp", n_beams, max_elem_nodes, max_elem_qps),
shape_deriv("deriv_interp", n_beams, max_elem_nodes, max_elem_qps) {}
};
Expand Down
10 changes: 6 additions & 4 deletions src/restruct_poc/beams/calculate_jacobian.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@ namespace openturbine {
struct CalculateJacobian {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices; // Element indices
Kokkos::View<double***>::const_type shape_derivative; // Num Nodes x Num Quadrature points
View_Nx7::const_type node_position_rotation; // Node global position/rotation vector
View_Nx3 qp_position_derivative; // quadrature point position derivative
View_NxN qp_jacobian; // Jacobians
View_Nx7::const_type node_position_rotation; // Node global position/rotation vector
Kokkos::View<double** [3]> qp_position_derivative; // quadrature point position derivative
View_NxN qp_jacobian; // Jacobians

KOKKOS_FUNCTION
void operator()(const int i_elem) const {
Expand All @@ -23,7 +23,9 @@ struct CalculateJacobian {
shape_derivative, i_elem, Kokkos::make_pair(size_t{0U}, idx.num_nodes),
idx.qp_shape_range
);
const auto qp_pos_deriv = Kokkos::subview(qp_position_derivative, idx.qp_range, Kokkos::ALL);
const auto qp_pos_deriv = Kokkos::subview(
qp_position_derivative, i_elem, Kokkos::pair(size_t{0U}, idx.num_qps), Kokkos::ALL
);
const auto node_pos =
Kokkos::subview(node_position_rotation, idx.node_range, Kokkos::make_pair(0, 3));
const auto qp_jacob =
Expand Down
8 changes: 6 additions & 2 deletions src/restruct_poc/beams/create_beams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,12 @@ inline Beams CreateBeams(const BeamsInput& beams_input) {
beams_input.elements[i], // Element inputs
Kokkos::subview(host_node_x0, idx.node_range, Kokkos::ALL),
Kokkos::subview(host_qp_weight, i, Kokkos::pair(size_t{0U}, idx.num_qps)),
Kokkos::subview(host_qp_Mstar, idx.qp_range, Kokkos::ALL, Kokkos::ALL),
Kokkos::subview(host_qp_Cstar, idx.qp_range, Kokkos::ALL, Kokkos::ALL),
Kokkos::subview(
host_qp_Mstar, i, Kokkos::pair(size_t{0U}, idx.num_qps), Kokkos::ALL, Kokkos::ALL
),
Kokkos::subview(
host_qp_Cstar, i, Kokkos::pair(size_t{0U}, idx.num_qps), Kokkos::ALL, Kokkos::ALL
),
Kokkos::subview(
host_shape_interp, i, Kokkos::pair(size_t{0U}, idx.num_nodes), idx.qp_shape_range
),
Expand Down
6 changes: 4 additions & 2 deletions src/restruct_poc/beams/interpolate_QP_position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ struct InterpolateQPPosition {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices; // Element indices
Kokkos::View<double***>::const_type shape_interpolation; // Num Nodes x Num Quadrature points
View_Nx7::const_type node_position_rotation; // Node global position vector
View_Nx3 qp_position; // quadrature point position
Kokkos::View<double** [3]> qp_position; // quadrature point position

KOKKOS_FUNCTION
void operator()(const int i_elem) const {
Expand All @@ -23,7 +23,9 @@ struct InterpolateQPPosition {
);
const auto node_pos =
Kokkos::subview(node_position_rotation, idx.node_range, Kokkos::make_pair(0, 3));
const auto qp_pos = Kokkos::subview(qp_position, idx.qp_range, Kokkos::ALL);
const auto qp_pos = Kokkos::subview(
qp_position, i_elem, Kokkos::make_pair(size_t{0U}, idx.num_qps), Kokkos::ALL
);

for (auto j = 0U; j < idx.num_qps; ++j) {
auto local_result = Kokkos::Array<double, 3>{};
Expand Down
6 changes: 4 additions & 2 deletions src/restruct_poc/beams/interpolate_QP_rotation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ struct InterpolateQPRotation {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices; // Element indices
Kokkos::View<double***>::const_type shape_interpolation; // Num Nodes x Num Quadrature points
View_Nx7::const_type node_position_rotation; // Node global position vector
View_Nx4 qp_rotation; // quadrature point rotation
Kokkos::View<double** [4]> qp_rotation; // quadrature point rotation

KOKKOS_FUNCTION
void operator()(const int i_elem) const {
Expand All @@ -24,7 +24,9 @@ struct InterpolateQPRotation {
);
const auto node_rot =
Kokkos::subview(node_position_rotation, idx.node_range, Kokkos::make_pair(3, 7));
const auto qp_rot = Kokkos::subview(qp_rotation, idx.qp_range, Kokkos::ALL);
const auto qp_rot = Kokkos::subview(
qp_rotation, i_elem, Kokkos::make_pair(size_t{0U}, idx.num_qps), Kokkos::ALL
);

InterpQuaternion(shape_interp, node_rot, qp_rot);
}
Expand Down
4 changes: 2 additions & 2 deletions src/restruct_poc/beams/interpolate_QP_rotation_derivative.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@ struct InterpolateQPRotationDerivative {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices; // Element indices
Kokkos::View<double***>::const_type shape_derivative; // Num Nodes x Num Quadrature points
View_N::const_type qp_jacobian; // Jacobians
View_Nx7::const_type node_pos_rot; // Node global position/rotation vector
View_Nx4 qp_rot_deriv; // quadrature point rotation derivative
View_Nx7::const_type node_pos_rot; // Node global position/rotation vector
Kokkos::View<double** [4]> qp_rot_deriv; // quadrature point rotation derivative

KOKKOS_FUNCTION
void operator()(const int i_elem) const {
Expand Down
24 changes: 12 additions & 12 deletions src/restruct_poc/beams/interpolate_QP_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@ struct InterpolateQPState_u {
size_t num_nodes;
Kokkos::View<double***>::const_type shape_interp;
View_Nx7::const_type node_u;
View_Nx3 qp_u;
Kokkos::View<double** [3]> qp_u;

KOKKOS_FUNCTION
void operator()(size_t j_index) const {
const auto j = first_qp + j_index;
// const auto j = first_qp + j_index;
auto local_total = Kokkos::Array<double, 3>{};
for (auto i_index = 0U; i_index < num_nodes; ++i_index) {
const auto i = first_node + i_index;
Expand All @@ -27,7 +27,7 @@ struct InterpolateQPState_u {
}
}
for (auto k = 0U; k < 3U; ++k) {
qp_u(j, k) = local_total[k];
qp_u(i_elem, j_index, k) = local_total[k];
}
}
};
Expand All @@ -40,11 +40,11 @@ struct InterpolateQPState_uprime {
Kokkos::View<double***>::const_type shape_deriv;
View_NxN::const_type qp_jacobian;
View_Nx7::const_type node_u;
View_Nx3 qp_uprime;
Kokkos::View<double** [3]> qp_uprime;

KOKKOS_FUNCTION
void operator()(size_t j_index) const {
const auto j = first_qp + j_index;
// const auto j = first_qp + j_index;
const auto jacobian = qp_jacobian(i_elem, j_index);
auto local_total = Kokkos::Array<double, 3>{};
for (auto i_index = 0U; i_index < num_nodes; ++i_index) {
Expand All @@ -55,7 +55,7 @@ struct InterpolateQPState_uprime {
}
}
for (auto k = 0U; k < 3U; ++k) {
qp_uprime(j, k) = local_total[k];
qp_uprime(i_elem, j_index, k) = local_total[k];
}
}
};
Expand All @@ -67,11 +67,11 @@ struct InterpolateQPState_r {
size_t num_nodes;
Kokkos::View<double***>::const_type shape_interp;
View_Nx7::const_type node_u;
View_Nx4 qp_r;
Kokkos::View<double** [4]> qp_r;

KOKKOS_FUNCTION
void operator()(size_t j_index) const {
const auto j = first_qp + j_index;
// const auto j = first_qp + j_index;
auto local_total = Kokkos::Array<double, 4>{};
for (auto i_index = 0U; i_index < num_nodes; ++i_index) {
const auto i = first_node + i_index;
Expand All @@ -89,7 +89,7 @@ struct InterpolateQPState_r {
local_total = length_zero_result;
}
for (auto k = 0U; k < 4U; ++k) {
qp_r(j, k) = local_total[k];
qp_r(i_elem, j_index, k) = local_total[k];
}
}
};
Expand All @@ -102,11 +102,11 @@ struct InterpolateQPState_rprime {
Kokkos::View<double***>::const_type shape_deriv;
View_NxN::const_type qp_jacobian;
View_Nx7::const_type node_u;
View_Nx4 qp_rprime;
Kokkos::View<double** [4]> qp_rprime;

KOKKOS_FUNCTION
void operator()(size_t j_index) const {
const auto j = first_qp + j_index;
// const auto j = first_qp + j_index;
const auto jacobian = qp_jacobian(i_elem, j_index);
auto local_total = Kokkos::Array<double, 4>{};
for (auto i_index = 0U; i_index < num_nodes; ++i_index) {
Expand All @@ -117,7 +117,7 @@ struct InterpolateQPState_rprime {
}
}
for (auto k = 0U; k < 4U; ++k) {
qp_rprime(j, k) = local_total[k];
qp_rprime(i_elem, j_index, k) = local_total[k];
}
}
};
Expand Down
6 changes: 3 additions & 3 deletions src/restruct_poc/beams/interpolate_QP_vector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@ struct InterpolateQPVector {
size_t num_nodes;
Kokkos::View<double***>::const_type shape_interp;
View_Nx3::const_type node_vector;
View_Nx3 qp_vector;
Kokkos::View<double** [3]> qp_vector;

KOKKOS_FUNCTION
void operator()(size_t j_index) const {
const auto j = first_qp + j_index;
// const auto j = first_qp + j_index;
auto local_total = Kokkos::Array<double, 3>{};
for (auto i_index = 0U; i_index < num_nodes; ++i_index) {
const auto i = first_node + i_index;
Expand All @@ -27,7 +27,7 @@ struct InterpolateQPVector {
}
}
for (auto k = 0U; k < 3U; ++k) {
qp_vector(j, k) = local_total[k];
qp_vector(i_elem, j_index, k) = local_total[k];
}
}
};
Expand Down
16 changes: 8 additions & 8 deletions src/restruct_poc/beams/interpolate_to_quadrature_points.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,14 @@ struct InterpolateToQuadraturePoints {
View_Nx7::const_type node_u;
View_Nx6::const_type node_u_dot;
View_Nx6::const_type node_u_ddot;
View_Nx3 qp_u;
View_Nx3 qp_uprime;
View_Nx4 qp_r;
View_Nx4 qp_rprime;
View_Nx3 qp_u_dot;
View_Nx3 qp_omega;
View_Nx3 qp_u_ddot;
View_Nx3 qp_omega_dot;
Kokkos::View<double** [3]> qp_u;
Kokkos::View<double** [3]> qp_uprime;
Kokkos::View<double** [4]> qp_r;
Kokkos::View<double** [4]> qp_rprime;
Kokkos::View<double** [3]> qp_u_dot;
Kokkos::View<double** [3]> qp_omega;
Kokkos::View<double** [3]> qp_u_ddot;
Kokkos::View<double** [3]> qp_omega_dot;

KOKKOS_FUNCTION
void operator()(Kokkos::TeamPolicy<>::member_type member) const {
Expand Down
Loading

0 comments on commit 7e3adb0

Please sign in to comment.