Skip to content

Commit

Permalink
Optimized Update System Variables for beams
Browse files Browse the repository at this point in the history
  • Loading branch information
ddement committed Feb 19, 2025
1 parent 16abb3f commit 3d439b8
Show file tree
Hide file tree
Showing 51 changed files with 915 additions and 2,180 deletions.
80 changes: 19 additions & 61 deletions src/elements/beams/beams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,46 +40,25 @@ struct Beams {
Kokkos::View<double** [6]> node_FX; // External forces

// Quadrature point data
Kokkos::View<double**> qp_weight; // Integration weights
Kokkos::View<double**> 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** [7]> qp_x; // Current position/orientation
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]> qp_deformation; // Deformation relative to rigid body motion
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_Fe; // External 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**> qp_weight; // Integration weights
Kokkos::View<double**> 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** [7]> qp_x; // Current position/orientation
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]> qp_deformation; // Deformation relative to rigid body motion
Kokkos::View<double** [3][4]> qp_E; // Quaternion derivative
Kokkos::View<double** [6]> qp_Fe; // External force

Kokkos::View<double** [6]> residual_vector_terms;
Kokkos::View<double*** [6][6]> stiffness_matrix_terms;
Expand Down Expand Up @@ -126,28 +105,7 @@ struct Beams {
qp_omega_dot("qp_omega_dot", num_elems, max_elem_qps),
qp_deformation("qp_deformation", num_elems, max_elem_qps),
qp_E("qp_E", num_elems, max_elem_qps),
qp_eta_tilde("R1_3x3", num_elems, max_elem_qps),
qp_omega_tilde("R1_3x3", num_elems, max_elem_qps),
qp_omega_dot_tilde("R1_3x3", num_elems, max_elem_qps),
qp_x0pupss("R1_3x3", num_elems, max_elem_qps),
qp_M_tilde("R1_3x3", num_elems, max_elem_qps),
qp_N_tilde("R1_3x3", num_elems, max_elem_qps),
qp_eta("V_3", num_elems, max_elem_qps),
qp_rho("R1_3x3", num_elems, max_elem_qps),
qp_strain("qp_strain", num_elems, max_elem_qps),
qp_Fc("qp_Fc", num_elems, max_elem_qps),
qp_Fd("qp_Fd", num_elems, max_elem_qps),
qp_Fi("qp_Fi", num_elems, max_elem_qps),
qp_Fe("qp_Fe", num_elems, max_elem_qps),
qp_Fg("qp_Fg", num_elems, max_elem_qps),
qp_RR0("qp_RR0", num_elems, max_elem_qps),
qp_Muu("qp_Muu", num_elems, max_elem_qps),
qp_Cuu("qp_Cuu", num_elems, max_elem_qps),
qp_Ouu("qp_Ouu", num_elems, max_elem_qps),
qp_Puu("qp_Puu", num_elems, max_elem_qps),
qp_Quu("qp_Quu", num_elems, max_elem_qps),
qp_Guu("qp_Guu", num_elems, max_elem_qps),
qp_Kuu("qp_Kuu", num_elems, max_elem_qps),
residual_vector_terms("residual_vector_terms", num_elems, max_elem_nodes),
stiffness_matrix_terms(
"stiffness_matrix_terms", num_elems, max_elem_nodes, max_elem_nodes
Expand Down
1 change: 1 addition & 0 deletions src/elements/beams/create_beams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ inline Beams CreateBeams(const BeamsInput& beams_input, const std::vector<Node>&
beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x
}
);

return beams;
}

Expand Down
2 changes: 2 additions & 0 deletions src/step/assemble_inertia_matrix_beams.hpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
/*
#pragma once
#include <Kokkos_Core.hpp>
Expand Down Expand Up @@ -26,3 +27,4 @@ inline void AssembleInertiaMatrixBeams(const Beams& beams, double beta_prime, do
}
} // namespace openturbine
*/
2 changes: 2 additions & 0 deletions src/step/assemble_residual_vector_beams.hpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
/*
#pragma once
#include <Kokkos_Core.hpp>
Expand Down Expand Up @@ -33,3 +34,4 @@ inline void AssembleResidualVectorBeams(const Beams& beams) {
}
} // namespace openturbine
*/
2 changes: 2 additions & 0 deletions src/step/assemble_stiffness_matrix_beams.hpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
/*
#pragma once
#include <Kokkos_Core.hpp>
Expand Down Expand Up @@ -35,3 +36,4 @@ inline void AssembleStiffnessMatrixBeams(const Beams& beams) {
}
} // namespace openturbine
*/
82 changes: 25 additions & 57 deletions src/step/update_system_variables_beams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,86 +2,54 @@

#include <Kokkos_Core.hpp>

#include "assemble_inertia_matrix_beams.hpp"
#include "assemble_residual_vector_beams.hpp"
#include "assemble_stiffness_matrix_beams.hpp"
#include "elements/beams/beams.hpp"
#include "elements/beams/interpolate_to_quadrature_points.hpp"
#include "state/state.hpp"
#include "step_parameters.hpp"
#include "system/beams/calculate_quadrature_point_values.hpp"
#include "system/beams/update_node_state.hpp"

namespace openturbine {

inline void UpdateSystemVariablesBeams(
StepParameters& parameters, const Beams& beams, State& state
) {
auto range_policy = Kokkos::TeamPolicy<>(static_cast<int>(beams.num_elems), Kokkos::AUTO());
Kokkos::parallel_for(
"UpdateNodeState", range_policy,
UpdateNodeState{
beams.num_nodes_per_element, beams.node_state_indices, beams.node_u, beams.node_u_dot,
beams.node_u_ddot, state.q, state.v, state.vd
}
);

Kokkos::parallel_for(
"InterpolateToQuadraturePoints", range_policy,
InterpolateToQuadraturePoints{
beams.num_nodes_per_element, beams.num_qps_per_element, beams.shape_interp,
beams.shape_deriv, beams.qp_jacobian, beams.node_u, beams.node_u_dot, beams.node_u_ddot,
beams.qp_x0, beams.qp_r0, beams.qp_u, beams.qp_u_prime, beams.qp_r, beams.qp_r_prime,
beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x
}
);
const auto shape_size =
Kokkos::View<double**>::shmem_size(beams.max_elem_nodes, beams.max_elem_qps);
const auto weight_size = Kokkos::View<double*>::shmem_size(beams.max_elem_qps);
const auto node_variable_size = Kokkos::View<double* [7]>::shmem_size(beams.max_elem_nodes);
const auto qp_variable_size = Kokkos::View<double* [6]>::shmem_size(beams.max_elem_qps);
const auto qp_matrix_size = Kokkos::View<double* [6][6]>::shmem_size(beams.max_elem_qps);
auto smem = 2 * shape_size + 2 * weight_size + 4 * node_variable_size + 5 * qp_variable_size +
7 * qp_matrix_size;
range_policy.set_scratch_size(1, Kokkos::PerTeam(smem));

Kokkos::parallel_for(
"CalculateQuadraturePointValues", range_policy,
CalculateQuadraturePointValues{
beams::CalculateQuadraturePointValues{
parameters.beta_prime,
parameters.gamma_prime,
state.q,
state.v,
state.vd,
beams.node_state_indices,
beams.num_nodes_per_element,
beams.num_qps_per_element,
beams.qp_weight,
beams.qp_jacobian,
beams.shape_interp,
beams.shape_deriv,
beams.gravity,
beams.qp_u,
beams.qp_u_prime,
beams.qp_r,
beams.qp_r_prime,
beams.node_FX,
beams.qp_r0,
beams.qp_x0,
beams.qp_x0_prime,
beams.qp_u_ddot,
beams.qp_omega,
beams.qp_omega_dot,
beams.qp_Mstar,
beams.qp_Cstar,
beams.qp_x,
beams.qp_RR0,
beams.qp_strain,
beams.qp_eta,
beams.qp_rho,
beams.qp_eta_tilde,
beams.qp_x0pupss,
beams.qp_M_tilde,
beams.qp_N_tilde,
beams.qp_omega_tilde,
beams.qp_omega_dot_tilde,
beams.qp_Fc,
beams.qp_Fd,
beams.qp_Fi,
beams.qp_Fe,
beams.qp_Fg,
beams.qp_Muu,
beams.qp_Cuu,
beams.qp_Ouu,
beams.qp_Puu,
beams.qp_Quu,
beams.qp_Guu,
beams.qp_Kuu
}
beams.residual_vector_terms,
beams.stiffness_matrix_terms,
beams.inertia_matrix_terms}
);

AssembleResidualVectorBeams(beams);
AssembleStiffnessMatrixBeams(beams);
AssembleInertiaMatrixBeams(beams, parameters.beta_prime, parameters.gamma_prime);
}

} // namespace openturbine
16 changes: 7 additions & 9 deletions src/system/beams/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,23 +1,21 @@
target_sources(openturbine_library PRIVATE)

install(FILES
calculate_force_FC.hpp
calculate_force_FD.hpp
calculate_gravity_force.hpp
calculate_gyroscopic_matrix.hpp
calculate_inertial_force.hpp
calculate_inertia_stiffness_matrix.hpp
calculate_mass_matrix_components.hpp
calculate_Ouu.hpp
calculate_Puu.hpp
calculate_quadrature_point_values.hpp
calculate_Quu.hpp
calculate_RR0.hpp
calculate_force_FC.hpp
calculate_force_FD.hpp
calculate_inertial_quadrature_point_values.hpp
calculate_quadrature_point_values.hpp
calculate_stiffness_quadrature_point_values.hpp
calculate_strain.hpp
calculate_temporary_variables.hpp
integrate_inertia_matrix.hpp
integrate_residual_vector.hpp
integrate_stiffness_matrix.hpp
interpolate_to_quadrature_point_for_inertia.hpp
interpolate_to_quadrature_point_for_stiffness.hpp
rotate_section_matrix.hpp
update_node_state.hpp
DESTINATION include/OpenTurbine/system/beams/
Expand Down
49 changes: 19 additions & 30 deletions src/system/beams/calculate_Ouu.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,37 +5,26 @@
#include <KokkosBlas1_set.hpp>
#include <Kokkos_Core.hpp>

namespace openturbine {
namespace openturbine::beams {

struct CalculateOuu {
KOKKOS_FUNCTION
inline void CalculateOuu(
const Kokkos::View<double[6][6]>::const_type& Cuu,
const Kokkos::View<double[3][3]>::const_type& x0pupSS,
const Kokkos::View<double[3][3]>::const_type& M_tilde,
const Kokkos::View<double[3][3]>::const_type& N_tilde, const Kokkos::View<double[6][6]>& Ouu
) {
using NoTranspose = KokkosBatched::Trans::NoTranspose;
using Default = KokkosBatched::Algo::Gemm::Default;
using Gemm = KokkosBatched::SerialGemm<NoTranspose, NoTranspose, Default>;
size_t i_elem;
Kokkos::View<double** [6][6]>::const_type qp_Cuu_;
Kokkos::View<double** [3][3]>::const_type x0pupSS_;
Kokkos::View<double** [3][3]>::const_type M_tilde_;
Kokkos::View<double** [3][3]>::const_type N_tilde_;
Kokkos::View<double** [6][6]> qp_Ouu_;

KOKKOS_FUNCTION
void operator()(int i_qp) const {
auto Cuu = Kokkos::subview(qp_Cuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto x0pupSS = Kokkos::subview(x0pupSS_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto M_tilde = Kokkos::subview(M_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto N_tilde = Kokkos::subview(N_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto Ouu = Kokkos::subview(qp_Ouu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);

auto C11 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3));
auto C21 = Kokkos::subview(Cuu, Kokkos::make_pair(3, 6), Kokkos::make_pair(0, 3));
KokkosBlas::SerialSet::invoke(0., Ouu);
auto Ouu_12 = Kokkos::subview(Ouu, Kokkos::make_pair(0, 3), Kokkos::make_pair(3, 6));
KokkosBlas::serial_axpy(1., N_tilde, Ouu_12);
Gemm::invoke(1., C11, x0pupSS, -1., Ouu_12);
auto Ouu_22 = Kokkos::subview(Ouu, Kokkos::make_pair(3, 6), Kokkos::make_pair(3, 6));
KokkosBlas::serial_axpy(1., M_tilde, Ouu_22);
Gemm::invoke(1., C21, x0pupSS, -1., Ouu_22);
}
};

} // namespace openturbine
auto C11 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3));
auto C21 = Kokkos::subview(Cuu, Kokkos::make_pair(3, 6), Kokkos::make_pair(0, 3));
KokkosBlas::SerialSet::invoke(0., Ouu);
auto Ouu_12 = Kokkos::subview(Ouu, Kokkos::make_pair(0, 3), Kokkos::make_pair(3, 6));
KokkosBlas::serial_axpy(1., N_tilde, Ouu_12);
Gemm::invoke(1., C11, x0pupSS, -1., Ouu_12);
auto Ouu_22 = Kokkos::subview(Ouu, Kokkos::make_pair(3, 6), Kokkos::make_pair(3, 6));
KokkosBlas::serial_axpy(1., M_tilde, Ouu_22);
Gemm::invoke(1., C21, x0pupSS, -1., Ouu_22);
}
} // namespace openturbine::beams
43 changes: 17 additions & 26 deletions src/system/beams/calculate_Puu.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,35 +5,26 @@
#include <KokkosBlas1_set.hpp>
#include <Kokkos_Core.hpp>

namespace openturbine {
namespace openturbine::beams {

struct CalculatePuu {
KOKKOS_FUNCTION
inline void CalculatePuu(
const Kokkos::View<double[6][6]>::const_type& Cuu,
const Kokkos::View<double[3][3]>::const_type& x0pupSS,
const Kokkos::View<double[3][3]>::const_type& N_tilde, const Kokkos::View<double[6][6]>& Puu
) {
using NoTranspose = KokkosBatched::Trans::NoTranspose;
using Transpose = KokkosBatched::Trans::Transpose;
using Default = KokkosBatched::Algo::Gemm::Default;
using GemmTN = KokkosBatched::SerialGemm<Transpose, NoTranspose, Default>;
size_t i_elem;
Kokkos::View<double** [6][6]>::const_type qp_Cuu_;
Kokkos::View<double** [3][3]>::const_type x0pupSS_;
Kokkos::View<double** [3][3]>::const_type N_tilde_;
Kokkos::View<double** [6][6]> qp_Puu_;
auto C11 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3));
auto C12 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(3, 6));
KokkosBlas::SerialSet::invoke(0., Puu);
auto Puu_21 = Kokkos::subview(Puu, Kokkos::make_pair(3, 6), Kokkos::make_pair(0, 3));
KokkosBlas::serial_axpy(1., N_tilde, Puu_21);
GemmTN::invoke(1., x0pupSS, C11, 1., Puu_21);
auto Puu_22 = Kokkos::subview(Puu, Kokkos::make_pair(3, 6), Kokkos::make_pair(3, 6));
GemmTN::invoke(1., x0pupSS, C12, 0., Puu_22);
}

KOKKOS_FUNCTION
void operator()(int i_qp) const {
auto Cuu = Kokkos::subview(qp_Cuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto x0pupSS = Kokkos::subview(x0pupSS_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto N_tilde = Kokkos::subview(N_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);
auto Puu = Kokkos::subview(qp_Puu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL);

auto C11 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3));
auto C12 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(3, 6));
KokkosBlas::SerialSet::invoke(0., Puu);
auto Puu_21 = Kokkos::subview(Puu, Kokkos::make_pair(3, 6), Kokkos::make_pair(0, 3));
KokkosBlas::serial_axpy(1., N_tilde, Puu_21);
GemmTN::invoke(1., x0pupSS, C11, 1., Puu_21);
auto Puu_22 = Kokkos::subview(Puu, Kokkos::make_pair(3, 6), Kokkos::make_pair(3, 6));
GemmTN::invoke(1., x0pupSS, C12, 0., Puu_22);
}
};

} // namespace openturbine
} // namespace openturbine::beams
Loading

0 comments on commit 3d439b8

Please sign in to comment.