diff --git a/src/restruct_poc/beams/beams.hpp b/src/restruct_poc/beams/beams.hpp index 766b2cea..0ae574a5 100644 --- a/src/restruct_poc/beams/beams.hpp +++ b/src/restruct_poc/beams/beams.hpp @@ -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 qp_Mstar; // Mass matrix in material frame + Kokkos::View qp_Cstar; // Stiffness matrix in material frame + Kokkos::View qp_x0; // Initial position + Kokkos::View qp_x0_prime; // Initial position derivative + Kokkos::View qp_r0; // Initial rotation + Kokkos::View qp_u; // State: translation displacement + Kokkos::View qp_u_prime; // State: translation displacement derivative + Kokkos::View qp_u_dot; // State: translation velocity + Kokkos::View qp_u_ddot; // State: translation acceleration + Kokkos::View qp_r; // State: rotation + Kokkos::View qp_r_prime; // State: rotation derivative + Kokkos::View qp_omega; // State: angular velocity + Kokkos::View qp_omega_dot; // State: position/rotation + Kokkos::View qp_E; // Quaternion derivative + Kokkos::View qp_eta_tilde; // + Kokkos::View qp_omega_tilde; // + Kokkos::View qp_omega_dot_tilde; // + Kokkos::View qp_x0pupss; // + Kokkos::View qp_M_tilde; // + Kokkos::View qp_N_tilde; // + Kokkos::View qp_eta; // + Kokkos::View qp_rho; // + Kokkos::View qp_strain; // Strain + Kokkos::View qp_Fc; // Elastic force + Kokkos::View qp_Fd; // Elastic force + Kokkos::View qp_Fi; // Inertial force + Kokkos::View qp_Fg; // Gravity force + Kokkos::View qp_RR0; // Global rotation + Kokkos::View qp_Muu; // Mass in global frame + Kokkos::View qp_Cuu; // Stiffness in global frame + Kokkos::View qp_Ouu; // Linearization matrices + Kokkos::View qp_Puu; // Linearization matrices + Kokkos::View qp_Quu; // Linearization matrices + Kokkos::View qp_Guu; // Linearization matrices + Kokkos::View qp_Kuu; // Linearization matrices Kokkos::View shape_interp; // shape function matrix for interpolation [Nodes x QPs] Kokkos::View @@ -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) {} }; diff --git a/src/restruct_poc/beams/calculate_jacobian.hpp b/src/restruct_poc/beams/calculate_jacobian.hpp index 9c6106bc..df5e74ca 100644 --- a/src/restruct_poc/beams/calculate_jacobian.hpp +++ b/src/restruct_poc/beams/calculate_jacobian.hpp @@ -12,9 +12,9 @@ namespace openturbine { struct CalculateJacobian { Kokkos::View::const_type elem_indices; // Element indices Kokkos::View::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 qp_position_derivative; // quadrature point position derivative + View_NxN qp_jacobian; // Jacobians KOKKOS_FUNCTION void operator()(const int i_elem) const { @@ -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 = diff --git a/src/restruct_poc/beams/create_beams.hpp b/src/restruct_poc/beams/create_beams.hpp index 239720e1..99c48bbe 100644 --- a/src/restruct_poc/beams/create_beams.hpp +++ b/src/restruct_poc/beams/create_beams.hpp @@ -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 ), diff --git a/src/restruct_poc/beams/interpolate_QP_position.hpp b/src/restruct_poc/beams/interpolate_QP_position.hpp index 23a915d3..782331bd 100644 --- a/src/restruct_poc/beams/interpolate_QP_position.hpp +++ b/src/restruct_poc/beams/interpolate_QP_position.hpp @@ -12,7 +12,7 @@ struct InterpolateQPPosition { Kokkos::View::const_type elem_indices; // Element indices Kokkos::View::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 qp_position; // quadrature point position KOKKOS_FUNCTION void operator()(const int i_elem) const { @@ -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{}; diff --git a/src/restruct_poc/beams/interpolate_QP_rotation.hpp b/src/restruct_poc/beams/interpolate_QP_rotation.hpp index 659dc539..0c2b91a0 100644 --- a/src/restruct_poc/beams/interpolate_QP_rotation.hpp +++ b/src/restruct_poc/beams/interpolate_QP_rotation.hpp @@ -13,7 +13,7 @@ struct InterpolateQPRotation { Kokkos::View::const_type elem_indices; // Element indices Kokkos::View::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 qp_rotation; // quadrature point rotation KOKKOS_FUNCTION void operator()(const int i_elem) const { @@ -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); } diff --git a/src/restruct_poc/beams/interpolate_QP_rotation_derivative.hpp b/src/restruct_poc/beams/interpolate_QP_rotation_derivative.hpp index 6001d891..9a4360eb 100644 --- a/src/restruct_poc/beams/interpolate_QP_rotation_derivative.hpp +++ b/src/restruct_poc/beams/interpolate_QP_rotation_derivative.hpp @@ -12,8 +12,8 @@ struct InterpolateQPRotationDerivative { Kokkos::View::const_type elem_indices; // Element indices Kokkos::View::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 qp_rot_deriv; // quadrature point rotation derivative KOKKOS_FUNCTION void operator()(const int i_elem) const { diff --git a/src/restruct_poc/beams/interpolate_QP_state.hpp b/src/restruct_poc/beams/interpolate_QP_state.hpp index 91833cc4..6d2aa4eb 100644 --- a/src/restruct_poc/beams/interpolate_QP_state.hpp +++ b/src/restruct_poc/beams/interpolate_QP_state.hpp @@ -13,11 +13,11 @@ struct InterpolateQPState_u { size_t num_nodes; Kokkos::View::const_type shape_interp; View_Nx7::const_type node_u; - View_Nx3 qp_u; + Kokkos::View 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{}; for (auto i_index = 0U; i_index < num_nodes; ++i_index) { const auto i = first_node + i_index; @@ -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]; } } }; @@ -40,11 +40,11 @@ struct InterpolateQPState_uprime { Kokkos::View::const_type shape_deriv; View_NxN::const_type qp_jacobian; View_Nx7::const_type node_u; - View_Nx3 qp_uprime; + Kokkos::View 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{}; for (auto i_index = 0U; i_index < num_nodes; ++i_index) { @@ -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]; } } }; @@ -67,11 +67,11 @@ struct InterpolateQPState_r { size_t num_nodes; Kokkos::View::const_type shape_interp; View_Nx7::const_type node_u; - View_Nx4 qp_r; + Kokkos::View 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{}; for (auto i_index = 0U; i_index < num_nodes; ++i_index) { const auto i = first_node + i_index; @@ -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]; } } }; @@ -102,11 +102,11 @@ struct InterpolateQPState_rprime { Kokkos::View::const_type shape_deriv; View_NxN::const_type qp_jacobian; View_Nx7::const_type node_u; - View_Nx4 qp_rprime; + Kokkos::View 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{}; for (auto i_index = 0U; i_index < num_nodes; ++i_index) { @@ -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]; } } }; diff --git a/src/restruct_poc/beams/interpolate_QP_vector.hpp b/src/restruct_poc/beams/interpolate_QP_vector.hpp index 7b7d34eb..b89aeb6a 100644 --- a/src/restruct_poc/beams/interpolate_QP_vector.hpp +++ b/src/restruct_poc/beams/interpolate_QP_vector.hpp @@ -13,11 +13,11 @@ struct InterpolateQPVector { size_t num_nodes; Kokkos::View::const_type shape_interp; View_Nx3::const_type node_vector; - View_Nx3 qp_vector; + Kokkos::View 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{}; for (auto i_index = 0U; i_index < num_nodes; ++i_index) { const auto i = first_node + i_index; @@ -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]; } } }; diff --git a/src/restruct_poc/beams/interpolate_to_quadrature_points.hpp b/src/restruct_poc/beams/interpolate_to_quadrature_points.hpp index 202d1e19..f6c8c4c0 100644 --- a/src/restruct_poc/beams/interpolate_to_quadrature_points.hpp +++ b/src/restruct_poc/beams/interpolate_to_quadrature_points.hpp @@ -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 qp_u; + Kokkos::View qp_uprime; + Kokkos::View qp_r; + Kokkos::View qp_rprime; + Kokkos::View qp_u_dot; + Kokkos::View qp_omega; + Kokkos::View qp_u_ddot; + Kokkos::View qp_omega_dot; KOKKOS_FUNCTION void operator()(Kokkos::TeamPolicy<>::member_type member) const { diff --git a/src/restruct_poc/beams/interpolation_operations.hpp b/src/restruct_poc/beams/interpolation_operations.hpp index 692ff4e3..bf44b324 100644 --- a/src/restruct_poc/beams/interpolation_operations.hpp +++ b/src/restruct_poc/beams/interpolation_operations.hpp @@ -6,9 +6,9 @@ namespace openturbine { -template +template KOKKOS_INLINE_FUNCTION void InterpVector3( - const shape_matrix_type& shape_matrix, const View_Nx3::const_type& node_v, const View_Nx3& qp_v + const shape_matrix_type& shape_matrix, const View_Nx3::const_type& node_v, const qp_type& qp_v ) { for (int j = 0; j < qp_v.extent_int(0); ++j) { auto local_total = Kokkos::Array{}; @@ -24,9 +24,9 @@ KOKKOS_INLINE_FUNCTION void InterpVector3( } } -template +template KOKKOS_INLINE_FUNCTION void InterpVector4( - const shape_matrix_type& shape_matrix, const View_Nx4::const_type& node_v, const View_Nx4& qp_v + const shape_matrix_type& shape_matrix, const View_Nx4::const_type& node_v, const qp_type& qp_v ) { for (int j = 0; j < qp_v.extent_int(0); ++j) { auto local_total = Kokkos::Array{}; @@ -42,9 +42,9 @@ KOKKOS_INLINE_FUNCTION void InterpVector4( } } -template +template KOKKOS_INLINE_FUNCTION void InterpQuaternion( - const shape_matrix_type& shape_matrix, const View_Nx4::const_type& node_v, const View_Nx4& qp_v + const shape_matrix_type& shape_matrix, const View_Nx4::const_type& node_v, const qp_type& qp_v ) { InterpVector4(shape_matrix, node_v, qp_v); static constexpr auto length_zero_result = Kokkos::Array{1., 0., 0., 0.}; @@ -65,10 +65,10 @@ KOKKOS_INLINE_FUNCTION void InterpQuaternion( } } -template +template KOKKOS_INLINE_FUNCTION void InterpVector3Deriv( const shape_matrix_type& shape_matrix_deriv, const jacobian_type& jacobian, - const View_Nx3::const_type& node_v, const View_Nx3& qp_v + const View_Nx3::const_type& node_v, const qp_type& qp_v ) { InterpVector3(shape_matrix_deriv, node_v, qp_v); for (int j = 0; j < qp_v.extent_int(0); ++j) { @@ -79,10 +79,10 @@ KOKKOS_INLINE_FUNCTION void InterpVector3Deriv( } } -template +template KOKKOS_INLINE_FUNCTION void InterpVector4Deriv( const shape_matrix_type& shape_matrix_deriv, const jacobian_type& jacobian, - const View_Nx4::const_type& node_v, const View_Nx4& qp_v + const View_Nx4::const_type& node_v, const qp_type& qp_v ) { InterpVector4(shape_matrix_deriv, node_v, qp_v); for (int j = 0; j < qp_v.extent_int(0); ++j) { diff --git a/src/restruct_poc/system/assemble_inertia_matrix.hpp b/src/restruct_poc/system/assemble_inertia_matrix.hpp index 12811372..fedbcc79 100644 --- a/src/restruct_poc/system/assemble_inertia_matrix.hpp +++ b/src/restruct_poc/system/assemble_inertia_matrix.hpp @@ -14,7 +14,10 @@ inline void AssembleInertiaMatrix( ) { auto region = Kokkos::Profiling::ScopedRegion("Assemble Inertia Matrix"); auto range_policy = Kokkos::TeamPolicy<>(static_cast(beams.num_elems), Kokkos::AUTO()); - + auto smem = 2 * Kokkos::View::shmem_size(beams.max_elem_qps) + + 2 * Kokkos::View::shmem_size(beams.max_elem_qps) + + Kokkos::View::shmem_size(beams.max_elem_nodes, beams.max_elem_qps); + range_policy.set_scratch_size(1, Kokkos::PerTeam(smem)); Kokkos::parallel_for( "IntegrateInertiaMatrix", range_policy, IntegrateInertiaMatrix{ diff --git a/src/restruct_poc/system/assemble_stiffness_matrix.hpp b/src/restruct_poc/system/assemble_stiffness_matrix.hpp index af086d0f..bc83ef77 100644 --- a/src/restruct_poc/system/assemble_stiffness_matrix.hpp +++ b/src/restruct_poc/system/assemble_stiffness_matrix.hpp @@ -13,6 +13,10 @@ namespace openturbine { inline void AssembleStiffnessMatrix(const Beams& beams, const Kokkos::View& K) { auto region = Kokkos::Profiling::ScopedRegion("Assemble Stiffness Matrix"); auto range_policy = Kokkos::TeamPolicy<>(static_cast(beams.num_elems), Kokkos::AUTO()); + auto smem = 5 * Kokkos::View::shmem_size(beams.max_elem_qps) + + 2 * Kokkos::View::shmem_size(beams.max_elem_qps) + + 2 * Kokkos::View::shmem_size(beams.max_elem_qps, beams.max_elem_qps); + range_policy.set_scratch_size(1, Kokkos::PerTeam(smem)); Kokkos::parallel_for( "IntegrateStiffnessMatrix", range_policy, IntegrateStiffnessMatrix{ diff --git a/src/restruct_poc/system/calculate_Ouu.hpp b/src/restruct_poc/system/calculate_Ouu.hpp index abaee503..8b1b2b46 100644 --- a/src/restruct_poc/system/calculate_Ouu.hpp +++ b/src/restruct_poc/system/calculate_Ouu.hpp @@ -13,19 +13,20 @@ struct CalculateOuu { using NoTranspose = KokkosBatched::Trans::NoTranspose; using Default = KokkosBatched::Algo::Gemm::Default; using Gemm = KokkosBatched::SerialGemm; - View_Nx6x6::const_type qp_Cuu_; - View_Nx3x3::const_type x0pupSS_; - View_Nx3x3::const_type M_tilde_; - View_Nx3x3::const_type N_tilde_; - View_Nx6x6 qp_Ouu_; + size_t i_elem; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type x0pupSS_; + Kokkos::View::const_type M_tilde_; + Kokkos::View::const_type N_tilde_; + Kokkos::View qp_Ouu_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Cuu = Kokkos::subview(qp_Cuu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto x0pupSS = Kokkos::subview(x0pupSS_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto M_tilde = Kokkos::subview(M_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto N_tilde = Kokkos::subview(N_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto Ouu = Kokkos::subview(qp_Ouu_, i_qp, Kokkos::ALL, Kokkos::ALL); + 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)); diff --git a/src/restruct_poc/system/calculate_Puu.hpp b/src/restruct_poc/system/calculate_Puu.hpp index ca47512b..f60c1f79 100644 --- a/src/restruct_poc/system/calculate_Puu.hpp +++ b/src/restruct_poc/system/calculate_Puu.hpp @@ -14,17 +14,18 @@ struct CalculatePuu { using Transpose = KokkosBatched::Trans::Transpose; using Default = KokkosBatched::Algo::Gemm::Default; using GemmTN = KokkosBatched::SerialGemm; - View_Nx6x6::const_type qp_Cuu_; - View_Nx3x3::const_type x0pupSS_; - View_Nx3x3::const_type N_tilde_; - View_Nx6x6 qp_Puu_; + size_t i_elem; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type x0pupSS_; + Kokkos::View::const_type N_tilde_; + Kokkos::View qp_Puu_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Cuu = Kokkos::subview(qp_Cuu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto x0pupSS = Kokkos::subview(x0pupSS_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto N_tilde = Kokkos::subview(N_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto Puu = Kokkos::subview(qp_Puu_, i_qp, Kokkos::ALL, Kokkos::ALL); + 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)); diff --git a/src/restruct_poc/system/calculate_Quu.hpp b/src/restruct_poc/system/calculate_Quu.hpp index ce588631..9491c377 100644 --- a/src/restruct_poc/system/calculate_Quu.hpp +++ b/src/restruct_poc/system/calculate_Quu.hpp @@ -15,19 +15,20 @@ struct CalculateQuu { using Default = KokkosBatched::Algo::Gemm::Default; using GemmNN = KokkosBatched::SerialGemm; using GemmTN = KokkosBatched::SerialGemm; - View_Nx6x6::const_type qp_Cuu_; - View_Nx3x3::const_type x0pupSS_; - View_Nx3x3::const_type N_tilde_; - View_Nx6x6 qp_Quu_; + size_t i_elem; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type x0pupSS_; + Kokkos::View::const_type N_tilde_; + Kokkos::View qp_Quu_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Cuu = Kokkos::subview(qp_Cuu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto x0pupSS = Kokkos::subview(x0pupSS_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto N_tilde = Kokkos::subview(N_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); + 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 m1 = Kokkos::Array{}; auto M1 = View_3x3(m1.data()); - auto Quu = Kokkos::subview(qp_Quu_, i_qp, Kokkos::ALL, Kokkos::ALL); + auto Quu = Kokkos::subview(qp_Quu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); auto C11 = Kokkos::subview(Cuu, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3)); KokkosBlas::SerialSet::invoke(0., Quu); diff --git a/src/restruct_poc/system/calculate_RR0.hpp b/src/restruct_poc/system/calculate_RR0.hpp index 0cbdb524..727c2571 100644 --- a/src/restruct_poc/system/calculate_RR0.hpp +++ b/src/restruct_poc/system/calculate_RR0.hpp @@ -8,24 +8,25 @@ namespace openturbine { struct CalculateRR0 { - View_Nx4::const_type qp_r0_; - View_Nx4::const_type qp_r_; - View_Nx6x6 qp_RR0_; + size_t i_elem; + Kokkos::View::const_type qp_r0_; + Kokkos::View::const_type qp_r_; + Kokkos::View qp_RR0_; KOKKOS_FUNCTION void operator()(const int i_qp) const { auto RR0_quaternion_data = Kokkos::Array{}; auto RR0_quaternion = Kokkos::View(RR0_quaternion_data.data()); QuaternionCompose( - Kokkos::subview(qp_r_, i_qp, Kokkos::ALL), Kokkos::subview(qp_r0_, i_qp, Kokkos::ALL), - RR0_quaternion + Kokkos::subview(qp_r_, i_elem, i_qp, Kokkos::ALL), + Kokkos::subview(qp_r0_, i_elem, i_qp, Kokkos::ALL), RR0_quaternion ); auto RR0_data = Kokkos::Array{}; auto RR0 = View_3x3(RR0_data.data()); QuaternionToRotationMatrix(RR0_quaternion, RR0); for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { - qp_RR0_(i_qp, i, j) = RR0(i, j); - qp_RR0_(i_qp, 3 + i, 3 + j) = RR0(i, j); + qp_RR0_(i_elem, i_qp, i, j) = RR0(i, j); + qp_RR0_(i_elem, i_qp, 3 + i, 3 + j) = RR0(i, j); } } } diff --git a/src/restruct_poc/system/calculate_force_FC.hpp b/src/restruct_poc/system/calculate_force_FC.hpp index d9972067..5fe7134f 100644 --- a/src/restruct_poc/system/calculate_force_FC.hpp +++ b/src/restruct_poc/system/calculate_force_FC.hpp @@ -12,19 +12,20 @@ struct CalculateForceFC { using NoTranspose = KokkosBlas::Trans::NoTranspose; using Default = KokkosBlas::Algo::Gemv::Default; using Gemv = KokkosBlas::SerialGemv; - View_Nx6x6::const_type qp_Cuu_; - View_Nx6::const_type qp_strain_; - View_Nx6 qp_FC_; - View_Nx3x3 M_tilde_; - View_Nx3x3 N_tilde_; + size_t i_elem; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type qp_strain_; + Kokkos::View qp_FC_; + Kokkos::View M_tilde_; + Kokkos::View N_tilde_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Cuu = Kokkos::subview(qp_Cuu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto strain = Kokkos::subview(qp_strain_, i_qp, Kokkos::ALL); - auto FC = Kokkos::subview(qp_FC_, i_qp, Kokkos::ALL); - auto M_tilde = Kokkos::subview(M_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto N_tilde = Kokkos::subview(N_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); + auto Cuu = Kokkos::subview(qp_Cuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto strain = Kokkos::subview(qp_strain_, i_elem, i_qp, Kokkos::ALL); + auto FC = Kokkos::subview(qp_FC_, i_elem, i_qp, 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); Gemv::invoke(1., Cuu, strain, 0., FC); auto N = Kokkos::subview(FC, Kokkos::make_pair(0, 3)); diff --git a/src/restruct_poc/system/calculate_force_FD.hpp b/src/restruct_poc/system/calculate_force_FD.hpp index a986d99d..9a579241 100644 --- a/src/restruct_poc/system/calculate_force_FD.hpp +++ b/src/restruct_poc/system/calculate_force_FD.hpp @@ -12,15 +12,16 @@ struct CalculateForceFD { using Transpose = KokkosBlas::Trans::Transpose; using Default = KokkosBlas::Algo::Gemv::Default; using Gemv = KokkosBlas::SerialGemv; - View_Nx3x3::const_type x0pupSS_; - View_Nx6::const_type qp_FC_; - View_Nx6 qp_FD_; + size_t i_elem; + Kokkos::View::const_type x0pupSS_; + Kokkos::View::const_type qp_FC_; + Kokkos::View qp_FD_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto x0pupSS = Kokkos::subview(x0pupSS_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto FC = Kokkos::subview(qp_FC_, i_qp, Kokkos::ALL); - auto FD = Kokkos::subview(qp_FD_, i_qp, Kokkos::ALL); + auto x0pupSS = Kokkos::subview(x0pupSS_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto FC = Kokkos::subview(qp_FC_, i_elem, i_qp, Kokkos::ALL); + auto FD = Kokkos::subview(qp_FD_, i_elem, i_qp, Kokkos::ALL); auto N = Kokkos::subview(FC, Kokkos::make_pair(0, 3)); for (int i = 0; i < FD.extent_int(0); ++i) { diff --git a/src/restruct_poc/system/calculate_gravity_force.hpp b/src/restruct_poc/system/calculate_gravity_force.hpp index 9bdfa960..4d74e9fd 100644 --- a/src/restruct_poc/system/calculate_gravity_force.hpp +++ b/src/restruct_poc/system/calculate_gravity_force.hpp @@ -12,16 +12,17 @@ struct CalculateGravityForce { using NoTranspose = KokkosBlas::Trans::NoTranspose; using Default = KokkosBlas::Algo::Gemv::Default; using Gemv = KokkosBlas::SerialGemv; + size_t i_elem; View_3::const_type gravity; - View_Nx6x6::const_type qp_Muu_; - View_Nx3x3::const_type eta_tilde_; - View_Nx6 qp_FG_; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type eta_tilde_; + Kokkos::View qp_FG_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Muu = Kokkos::subview(qp_Muu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta_tilde = Kokkos::subview(eta_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto FG = Kokkos::subview(qp_FG_, i_qp, Kokkos::ALL); + auto Muu = Kokkos::subview(qp_Muu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta_tilde = Kokkos::subview(eta_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto FG = Kokkos::subview(qp_FG_, i_elem, i_qp, Kokkos::ALL); auto m = Muu(0, 0); for (int i = 0; i < 3; ++i) { FG(i) = m * gravity(i); diff --git a/src/restruct_poc/system/calculate_gyroscopic_matrix.hpp b/src/restruct_poc/system/calculate_gyroscopic_matrix.hpp index da63a729..670301c0 100644 --- a/src/restruct_poc/system/calculate_gyroscopic_matrix.hpp +++ b/src/restruct_poc/system/calculate_gyroscopic_matrix.hpp @@ -18,27 +18,28 @@ struct CalculateGyroscopicMatrix { using GemmNN = KokkosBatched::SerialGemm; using GemmNT = KokkosBatched::SerialGemm; using Gemv = KokkosBlas::SerialGemv; - View_Nx6x6::const_type qp_Muu_; - View_Nx3::const_type qp_omega_; - View_Nx3x3::const_type omega_tilde_; - View_Nx3x3::const_type rho_; - View_Nx3::const_type eta_; - View_Nx6x6 qp_Guu_; + size_t i_elem; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type qp_omega_; + Kokkos::View::const_type omega_tilde_; + Kokkos::View::const_type rho_; + Kokkos::View::const_type eta_; + Kokkos::View qp_Guu_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Muu = Kokkos::subview(qp_Muu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto omega = Kokkos::subview(qp_omega_, i_qp, Kokkos::ALL); - auto omega_tilde = Kokkos::subview(omega_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto rho = Kokkos::subview(rho_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta = Kokkos::subview(eta_, i_qp, Kokkos::ALL); + auto Muu = Kokkos::subview(qp_Muu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto omega = Kokkos::subview(qp_omega_, i_elem, i_qp, Kokkos::ALL); + auto omega_tilde = Kokkos::subview(omega_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto rho = Kokkos::subview(rho_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta = Kokkos::subview(eta_, i_elem, i_qp, Kokkos::ALL); auto v1 = Kokkos::Array{}; auto V1 = Kokkos::View(v1.data()); auto v2 = Kokkos::Array{}; auto V2 = Kokkos::View(v2.data()); auto m1 = Kokkos::Array{}; auto M1 = Kokkos::View(m1.data()); - auto Guu = Kokkos::subview(qp_Guu_, i_qp, Kokkos::ALL, Kokkos::ALL); + auto Guu = Kokkos::subview(qp_Guu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); auto m = Muu(0, 0); // Inertia gyroscopic matrix diff --git a/src/restruct_poc/system/calculate_inertia_stiffness_matrix.hpp b/src/restruct_poc/system/calculate_inertia_stiffness_matrix.hpp index 5ae0920a..20eb43fa 100644 --- a/src/restruct_poc/system/calculate_inertia_stiffness_matrix.hpp +++ b/src/restruct_poc/system/calculate_inertia_stiffness_matrix.hpp @@ -18,34 +18,35 @@ struct CalculateInertiaStiffnessMatrix { using GemmNN = KokkosBatched::SerialGemm; using GemmNT = KokkosBatched::SerialGemm; using Gemv = KokkosBlas::SerialGemv; - - View_Nx6x6::const_type qp_Muu_; - View_Nx3::const_type qp_u_ddot_; - View_Nx3::const_type qp_omega_; - View_Nx3::const_type qp_omega_dot_; - View_Nx3x3::const_type omega_tilde_; - View_Nx3x3::const_type omega_dot_tilde_; - View_Nx3x3::const_type rho_; - View_Nx3::const_type eta_; - View_Nx6x6 qp_Kuu_; + size_t i_elem; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type qp_u_ddot_; + Kokkos::View::const_type qp_omega_; + Kokkos::View::const_type qp_omega_dot_; + Kokkos::View::const_type omega_tilde_; + Kokkos::View::const_type omega_dot_tilde_; + Kokkos::View::const_type rho_; + Kokkos::View::const_type eta_; + Kokkos::View qp_Kuu_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Muu = Kokkos::subview(qp_Muu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto u_ddot = Kokkos::subview(qp_u_ddot_, i_qp, Kokkos::ALL); - auto omega = Kokkos::subview(qp_omega_, i_qp, Kokkos::ALL); - auto omega_dot = Kokkos::subview(qp_omega_dot_, i_qp, Kokkos::ALL); - auto omega_tilde = Kokkos::subview(omega_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto omega_dot_tilde = Kokkos::subview(omega_dot_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto rho = Kokkos::subview(rho_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta = Kokkos::subview(eta_, i_qp, Kokkos::ALL); + auto Muu = Kokkos::subview(qp_Muu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto u_ddot = Kokkos::subview(qp_u_ddot_, i_elem, i_qp, Kokkos::ALL); + auto omega = Kokkos::subview(qp_omega_, i_elem, i_qp, Kokkos::ALL); + auto omega_dot = Kokkos::subview(qp_omega_dot_, i_elem, i_qp, Kokkos::ALL); + auto omega_tilde = Kokkos::subview(omega_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto omega_dot_tilde = + Kokkos::subview(omega_dot_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto rho = Kokkos::subview(rho_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta = Kokkos::subview(eta_, i_elem, i_qp, Kokkos::ALL); auto v1 = Kokkos::Array{}; auto V1 = View_3(v1.data()); auto m1 = Kokkos::Array{}; auto M1 = View_3x3(m1.data()); auto m2 = Kokkos::Array{}; auto M2 = View_3x3(m2.data()); - auto Kuu = Kokkos::subview(qp_Kuu_, i_qp, Kokkos::ALL, Kokkos::ALL); + auto Kuu = Kokkos::subview(qp_Kuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); auto m = Muu(0, 0); diff --git a/src/restruct_poc/system/calculate_inertial_forces.hpp b/src/restruct_poc/system/calculate_inertial_forces.hpp index ce89dbce..cb1de801 100644 --- a/src/restruct_poc/system/calculate_inertial_forces.hpp +++ b/src/restruct_poc/system/calculate_inertial_forces.hpp @@ -15,33 +15,35 @@ struct CalculateInertialForces { using GemvDefault = KokkosBlas::Algo::Gemv::Default; using Gemm = KokkosBatched::SerialGemm; using Gemv = KokkosBlas::SerialGemv; - View_Nx6x6::const_type qp_Muu_; - View_Nx3::const_type qp_u_ddot_; - View_Nx3::const_type qp_omega_; - View_Nx3::const_type qp_omega_dot_; - View_Nx3x3::const_type eta_tilde_; - View_Nx3x3 omega_tilde_; - View_Nx3x3 omega_dot_tilde_; - View_Nx3x3::const_type rho_; - View_Nx3::const_type eta_; - View_Nx6 qp_FI_; + size_t i_elem; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type qp_u_ddot_; + Kokkos::View::const_type qp_omega_; + Kokkos::View::const_type qp_omega_dot_; + Kokkos::View::const_type eta_tilde_; + Kokkos::View omega_tilde_; + Kokkos::View omega_dot_tilde_; + Kokkos::View::const_type rho_; + Kokkos::View::const_type eta_; + Kokkos::View qp_FI_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Muu = Kokkos::subview(qp_Muu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto u_ddot = Kokkos::subview(qp_u_ddot_, i_qp, Kokkos::ALL); - auto omega = Kokkos::subview(qp_omega_, i_qp, Kokkos::ALL); - auto omega_dot = Kokkos::subview(qp_omega_dot_, i_qp, Kokkos::ALL); - auto eta_tilde = Kokkos::subview(eta_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto omega_tilde = Kokkos::subview(omega_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto omega_dot_tilde = Kokkos::subview(omega_dot_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto rho = Kokkos::subview(rho_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta = Kokkos::subview(eta_, i_qp, Kokkos::ALL); + auto Muu = Kokkos::subview(qp_Muu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto u_ddot = Kokkos::subview(qp_u_ddot_, i_elem, i_qp, Kokkos::ALL); + auto omega = Kokkos::subview(qp_omega_, i_elem, i_qp, Kokkos::ALL); + auto omega_dot = Kokkos::subview(qp_omega_dot_, i_elem, i_qp, Kokkos::ALL); + auto eta_tilde = Kokkos::subview(eta_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto omega_tilde = Kokkos::subview(omega_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto omega_dot_tilde = + Kokkos::subview(omega_dot_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto rho = Kokkos::subview(rho_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta = Kokkos::subview(eta_, i_elem, i_qp, Kokkos::ALL); auto v1 = Kokkos::Array{}; auto V1 = View_3(v1.data()); auto m1 = Kokkos::Array{}; auto M1 = View_3x3(m1.data()); - auto FI = Kokkos::subview(qp_FI_, i_qp, Kokkos::ALL); + auto FI = Kokkos::subview(qp_FI_, i_elem, i_qp, Kokkos::ALL); auto m = Muu(0, 0); VecTilde(omega, omega_tilde); diff --git a/src/restruct_poc/system/calculate_mass_matrix_components.hpp b/src/restruct_poc/system/calculate_mass_matrix_components.hpp index 0b70b564..0d6735bc 100644 --- a/src/restruct_poc/system/calculate_mass_matrix_components.hpp +++ b/src/restruct_poc/system/calculate_mass_matrix_components.hpp @@ -8,17 +8,18 @@ namespace openturbine { struct CalculateMassMatrixComponents { - View_Nx6x6::const_type qp_Muu_; - View_Nx3 eta_; - View_Nx3x3 rho_; - View_Nx3x3 eta_tilde_; + size_t i_elem; + Kokkos::View::const_type qp_Muu_; + Kokkos::View eta_; + Kokkos::View rho_; + Kokkos::View eta_tilde_; KOKKOS_FUNCTION void operator()(int i_qp) const { - auto Muu = Kokkos::subview(qp_Muu_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta = Kokkos::subview(eta_, i_qp, Kokkos::ALL); - auto rho = Kokkos::subview(rho_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto eta_tilde = Kokkos::subview(eta_tilde_, i_qp, Kokkos::ALL, Kokkos::ALL); + auto Muu = Kokkos::subview(qp_Muu_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta = Kokkos::subview(eta_, i_elem, i_qp, Kokkos::ALL); + auto rho = Kokkos::subview(rho_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); + auto eta_tilde = Kokkos::subview(eta_tilde_, i_elem, i_qp, Kokkos::ALL, Kokkos::ALL); auto m = Muu(0, 0); if (m == 0.) { diff --git a/src/restruct_poc/system/calculate_node_forces.hpp b/src/restruct_poc/system/calculate_node_forces.hpp index fcafa1d0..487c01f7 100644 --- a/src/restruct_poc/system/calculate_node_forces.hpp +++ b/src/restruct_poc/system/calculate_node_forces.hpp @@ -16,8 +16,8 @@ struct CalculateNodeForces_FE { View_NxN::const_type qp_jacobian_; Kokkos::View::const_type shape_interp_; Kokkos::View::const_type shape_deriv_; - View_Nx6::const_type qp_Fc_; - View_Nx6::const_type qp_Fd_; + Kokkos::View::const_type qp_Fc_; + Kokkos::View::const_type qp_Fd_; View_Nx6 node_FE_; KOKKOS_FUNCTION @@ -25,13 +25,13 @@ struct CalculateNodeForces_FE { const auto i = first_node + i_index; auto FE = Kokkos::Array{}; for (auto j_index = 0U; j_index < num_qps; ++j_index) { // QPs - const auto j = first_qp + j_index; + // const auto j = first_qp + j_index; const auto weight = qp_weight_(i_elem, j_index); const auto coeff_c = weight * shape_deriv_(i_elem, i_index, j_index); const auto coeff_d = weight * qp_jacobian_(i_elem, j_index) * shape_interp_(i_elem, i_index, j_index); for (auto k = 0U; k < 6U; ++k) { - FE[k] += coeff_c * qp_Fc_(j, k) + coeff_d * qp_Fd_(j, k); + FE[k] += coeff_c * qp_Fc_(i_elem, j_index, k) + coeff_d * qp_Fd_(i_elem, j_index, k); } } for (auto k = 0U; k < 6U; ++k) { @@ -49,7 +49,7 @@ struct CalculateNodeForces_FI_FG { View_NxN::const_type qp_jacobian_; Kokkos::View::const_type shape_interp_; Kokkos::View::const_type shape_deriv_; - View_Nx6::const_type qp_Fig_; + Kokkos::View::const_type qp_Fig_; View_Nx6 node_FIG_; KOKKOS_FUNCTION @@ -57,12 +57,12 @@ struct CalculateNodeForces_FI_FG { const auto i = first_node + i_index; auto FIG = Kokkos::Array{}; for (auto j_index = 0U; j_index < num_qps; ++j_index) { // QPs - const auto j = first_qp + j_index; + // const auto j = first_qp + j_index; const auto weight = qp_weight_(i_elem, j_index); const auto coeff_ig = weight * qp_jacobian_(i_elem, j_index) * shape_interp_(i_elem, i_index, j_index); for (auto k = 0U; k < 6U; ++k) { - FIG[k] += coeff_ig * qp_Fig_(j, k); + FIG[k] += coeff_ig * qp_Fig_(i_elem, j_index, k); } } for (auto k = 0U; k < 6U; ++k) { @@ -77,10 +77,10 @@ struct CalculateNodeForces { View_NxN::const_type qp_jacobian_; Kokkos::View::const_type shape_interp_; Kokkos::View::const_type shape_deriv_; - View_Nx6::const_type qp_Fc_; - View_Nx6::const_type qp_Fd_; - View_Nx6::const_type qp_Fi_; - View_Nx6::const_type qp_Fg_; + Kokkos::View::const_type qp_Fc_; + Kokkos::View::const_type qp_Fd_; + Kokkos::View::const_type qp_Fi_; + Kokkos::View::const_type qp_Fg_; View_Nx6 node_FE_; View_Nx6 node_FI_; View_Nx6 node_FG_; diff --git a/src/restruct_poc/system/calculate_quadrature_point_values.hpp b/src/restruct_poc/system/calculate_quadrature_point_values.hpp new file mode 100644 index 00000000..d199633e --- /dev/null +++ b/src/restruct_poc/system/calculate_quadrature_point_values.hpp @@ -0,0 +1,146 @@ +#pragma once + +#include + +#include "calculate_Ouu.hpp" +#include "calculate_Puu.hpp" +#include "calculate_Quu.hpp" +#include "calculate_RR0.hpp" +#include "calculate_force_FC.hpp" +#include "calculate_force_FD.hpp" +#include "calculate_gravity_force.hpp" +#include "calculate_gyroscopic_matrix.hpp" +#include "calculate_inertia_stiffness_matrix.hpp" +#include "calculate_inertial_forces.hpp" +#include "calculate_mass_matrix_components.hpp" +#include "calculate_strain.hpp" +#include "calculate_temporary_variables.hpp" +#include "rotate_section_matrix.hpp" + +#include "src/restruct_poc/beams/beams.hpp" +#include "src/restruct_poc/types.hpp" + +namespace openturbine { +struct CalculateQuadraturePointValues { + Kokkos::View::const_type elem_indices; + View_3::const_type gravity_; + Kokkos::View::const_type qp_u_prime_; + Kokkos::View::const_type qp_r_; + Kokkos::View::const_type qp_r_prime_; + Kokkos::View::const_type qp_r0_; + Kokkos::View::const_type qp_x0_prime_; + Kokkos::View::const_type qp_u_ddot_; + Kokkos::View::const_type qp_omega_; + Kokkos::View::const_type qp_omega_dot_; + Kokkos::View::const_type qp_Mstar_; + Kokkos::View::const_type qp_Cstar_; + Kokkos::View qp_RR0_; + Kokkos::View qp_strain_; + Kokkos::View qp_eta_; + Kokkos::View qp_rho_; + Kokkos::View qp_eta_tilde_; + Kokkos::View qp_x0pupSS_; + Kokkos::View qp_M_tilde_; + Kokkos::View qp_N_tilde_; + Kokkos::View qp_omega_tilde_; + Kokkos::View qp_omega_dot_tilde_; + Kokkos::View qp_FC_; + Kokkos::View qp_FD_; + Kokkos::View qp_FI_; + Kokkos::View qp_FG_; + Kokkos::View qp_Muu_; + Kokkos::View qp_Cuu_; + Kokkos::View qp_Ouu_; + Kokkos::View qp_Puu_; + Kokkos::View qp_Quu_; + Kokkos::View qp_Guu_; + Kokkos::View qp_Kuu_; + + KOKKOS_FUNCTION + void operator()(Kokkos::TeamPolicy<>::member_type member) const { + const auto i_elem = static_cast(member.league_rank()); + const auto idx = elem_indices(i_elem); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateRR0{i_elem, qp_r0_, qp_r_, qp_RR0_} + ); + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateTemporaryVariables{i_elem, qp_x0_prime_, qp_u_prime_, qp_x0pupSS_} + ); + member.team_barrier(); + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + RotateSectionMatrix{i_elem, qp_RR0_, qp_Mstar_, qp_Muu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + RotateSectionMatrix{i_elem, qp_RR0_, qp_Cstar_, qp_Cuu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateStrain{i_elem, qp_x0_prime_, qp_u_prime_, qp_r_, qp_r_prime_, qp_strain_} + ); + member.team_barrier(); + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateMassMatrixComponents{i_elem, qp_Muu_, qp_eta_, qp_rho_, qp_eta_tilde_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateForceFC{i_elem, qp_Cuu_, qp_strain_, qp_FC_, qp_M_tilde_, qp_N_tilde_} + ); + member.team_barrier(); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateInertialForces{ + i_elem, qp_Muu_, qp_u_ddot_, qp_omega_, qp_omega_dot_, qp_eta_tilde_, + qp_omega_tilde_, qp_omega_dot_tilde_, qp_rho_, qp_eta_, qp_FI_} + ); + member.team_barrier(); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateForceFD{i_elem, qp_x0pupSS_, qp_FC_, qp_FD_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateGravityForce{i_elem, gravity_, qp_Muu_, qp_eta_tilde_, qp_FG_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateOuu{i_elem, qp_Cuu_, qp_x0pupSS_, qp_M_tilde_, qp_N_tilde_, qp_Ouu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculatePuu{i_elem, qp_Cuu_, qp_x0pupSS_, qp_N_tilde_, qp_Puu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateQuu{i_elem, qp_Cuu_, qp_x0pupSS_, qp_N_tilde_, qp_Quu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateGyroscopicMatrix{ + i_elem, qp_Muu_, qp_omega_, qp_omega_tilde_, qp_rho_, qp_eta_, qp_Guu_} + ); + + Kokkos::parallel_for( + Kokkos::TeamThreadRange(member, idx.num_qps), + CalculateInertiaStiffnessMatrix{ + i_elem, qp_Muu_, qp_u_ddot_, qp_omega_, qp_omega_dot_, qp_omega_tilde_, + qp_omega_dot_tilde_, qp_rho_, qp_eta_, qp_Kuu_} + ); + } +}; +} // namespace openturbine \ No newline at end of file diff --git a/src/restruct_poc/system/calculate_strain.hpp b/src/restruct_poc/system/calculate_strain.hpp index ba65d66d..da152611 100644 --- a/src/restruct_poc/system/calculate_strain.hpp +++ b/src/restruct_poc/system/calculate_strain.hpp @@ -13,22 +13,26 @@ struct CalculateStrain { using NoTranspose = KokkosBlas::Trans::NoTranspose; using Default = KokkosBlas::Algo::Gemv::Default; using Gemv = KokkosBlas::SerialGemv; - View_Nx3::const_type qp_x0_prime_; - View_Nx3::const_type qp_u_prime_; - View_Nx4::const_type qp_r_; - View_Nx4::const_type qp_r_prime_; - View_Nx6 qp_strain_; + size_t i_elem; + Kokkos::View::const_type qp_x0_prime_; + Kokkos::View::const_type qp_u_prime_; + Kokkos::View::const_type qp_r_; + Kokkos::View::const_type qp_r_prime_; + Kokkos::View qp_strain_; KOKKOS_FUNCTION void operator()(const int i_qp) const { auto x0_prime_data = Kokkos::Array{ - qp_x0_prime_(i_qp, 0), qp_x0_prime_(i_qp, 1), qp_x0_prime_(i_qp, 2)}; + qp_x0_prime_(i_elem, i_qp, 0), qp_x0_prime_(i_elem, i_qp, 1), + qp_x0_prime_(i_elem, i_qp, 2)}; auto x0_prime = Kokkos::View(x0_prime_data.data()); auto u_prime_data = Kokkos::Array{ - qp_u_prime_(i_qp, 0), qp_u_prime_(i_qp, 1), qp_u_prime_(i_qp, 2)}; + qp_u_prime_(i_elem, i_qp, 0), qp_u_prime_(i_elem, i_qp, 1), + qp_u_prime_(i_elem, i_qp, 2)}; auto u_prime = Kokkos::View(u_prime_data.data()); - auto R_data = - Kokkos::Array{qp_r_(i_qp, 0), qp_r_(i_qp, 1), qp_r_(i_qp, 2), qp_r_(i_qp, 3)}; + auto R_data = Kokkos::Array{ + qp_r_(i_elem, i_qp, 0), qp_r_(i_elem, i_qp, 1), qp_r_(i_elem, i_qp, 2), + qp_r_(i_elem, i_qp, 3)}; auto R = Kokkos::View(R_data.data()); auto R_x0_prime_data = Kokkos::Array{}; @@ -42,18 +46,19 @@ struct CalculateStrain { auto E = Kokkos::View(E_data.data()); QuaternionDerivative(R, E); auto R_prime_data = Kokkos::Array{ - qp_r_prime_(i_qp, 0), qp_r_prime_(i_qp, 1), qp_r_prime_(i_qp, 2), qp_r_prime_(i_qp, 3)}; + qp_r_prime_(i_elem, i_qp, 0), qp_r_prime_(i_elem, i_qp, 1), qp_r_prime_(i_elem, i_qp, 2), + qp_r_prime_(i_elem, i_qp, 3)}; auto R_prime = Kokkos::View(R_prime_data.data()); auto e2_data = Kokkos::Array{}; auto e2 = Kokkos::View{e2_data.data()}; Gemv::invoke(2., E, R_prime, 0., e2); - qp_strain_(i_qp, 0) = -R_x0_prime(0); - qp_strain_(i_qp, 1) = -R_x0_prime(1); - qp_strain_(i_qp, 2) = -R_x0_prime(2); - qp_strain_(i_qp, 3) = e2(0); - qp_strain_(i_qp, 4) = e2(1); - qp_strain_(i_qp, 5) = e2(2); + qp_strain_(i_elem, i_qp, 0) = -R_x0_prime(0); + qp_strain_(i_elem, i_qp, 1) = -R_x0_prime(1); + qp_strain_(i_elem, i_qp, 2) = -R_x0_prime(2); + qp_strain_(i_elem, i_qp, 3) = e2(0); + qp_strain_(i_elem, i_qp, 4) = e2(1); + qp_strain_(i_elem, i_qp, 5) = e2(2); } }; diff --git a/src/restruct_poc/system/calculate_temporary_variables.hpp b/src/restruct_poc/system/calculate_temporary_variables.hpp index b9896ff3..ea76da06 100644 --- a/src/restruct_poc/system/calculate_temporary_variables.hpp +++ b/src/restruct_poc/system/calculate_temporary_variables.hpp @@ -9,17 +9,20 @@ namespace openturbine { struct CalculateTemporaryVariables { - View_Nx3::const_type qp_x0_prime_; - View_Nx3::const_type qp_u_prime_; - View_Nx3x3 x0pupSS_; + size_t i_elem; + Kokkos::View::const_type qp_x0_prime_; + Kokkos::View::const_type qp_u_prime_; + Kokkos::View x0pupSS_; KOKKOS_FUNCTION void operator()(int i_qp) const { auto x0pup_data = Kokkos::Array{ - qp_x0_prime_(i_qp, 0), qp_x0_prime_(i_qp, 1), qp_x0_prime_(i_qp, 2)}; + qp_x0_prime_(i_elem, i_qp, 0), qp_x0_prime_(i_elem, i_qp, 1), + qp_x0_prime_(i_elem, i_qp, 2)}; auto x0pup = View_3{x0pup_data.data()}; auto u_prime_data = Kokkos::Array{ - qp_u_prime_(i_qp, 0), qp_u_prime_(i_qp, 1), qp_u_prime_(i_qp, 2)}; + qp_u_prime_(i_elem, i_qp, 0), qp_u_prime_(i_elem, i_qp, 1), + qp_u_prime_(i_elem, i_qp, 2)}; auto u_prime = View_3{u_prime_data.data()}; KokkosBlas::serial_axpy(1., u_prime, x0pup); auto tmp_data = Kokkos::Array{}; @@ -27,7 +30,7 @@ struct CalculateTemporaryVariables { VecTilde(x0pup, tmp); for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { - x0pupSS_(i_qp, i, j) = tmp(i, j); + x0pupSS_(i_elem, i_qp, i, j) = tmp(i, j); } } } diff --git a/src/restruct_poc/system/integrate_inertia_matrix.hpp b/src/restruct_poc/system/integrate_inertia_matrix.hpp index 2b6f4fe9..90b13798 100644 --- a/src/restruct_poc/system/integrate_inertia_matrix.hpp +++ b/src/restruct_poc/system/integrate_inertia_matrix.hpp @@ -12,32 +12,29 @@ struct IntegrateInertiaMatrixElement { size_t num_qps; size_t first_node; size_t first_qp; - View_NxN::const_type qp_weight_; - View_NxN::const_type qp_jacobian_; - Kokkos::View::const_type shape_interp_; - View_Nx6x6::const_type qp_Muu_; - View_Nx6x6::const_type qp_Guu_; + View_N::const_type qp_weight_; + View_N::const_type qp_jacobian_; + Kokkos::View::const_type shape_interp_; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type qp_Guu_; double beta_prime_; double gamma_prime_; Kokkos::View gbl_M_; KOKKOS_FUNCTION void operator()(size_t i_index, size_t j_index) const { - // const auto i = i_index + first_node; - // const auto j = j_index + first_node; auto local_M_data = Kokkos::Array{}; const auto local_M = Kokkos::View(local_M_data.data()); for (auto k = 0U; k < num_qps; ++k) { - const auto k_qp = first_qp + k; - const auto w = qp_weight_(i_elem, k); - const auto jacobian = qp_jacobian_(i_elem, k); - const auto phi_i = shape_interp_(i_elem, i_index, k); - const auto phi_j = shape_interp_(i_elem, j_index, k); + const auto w = qp_weight_(k); + const auto jacobian = qp_jacobian_(k); + const auto phi_i = shape_interp_(i_index, k); + const auto phi_j = shape_interp_(j_index, k); const auto coeff = w * phi_i * phi_j * jacobian; for (auto m = 0U; m < 6U; ++m) { for (auto n = 0U; n < 6U; ++n) { - local_M(m, n) += beta_prime_ * coeff * qp_Muu_(k_qp, m, n) + - gamma_prime_ * coeff * qp_Guu_(k_qp, m, n); + local_M(m, n) += + coeff * (beta_prime_ * qp_Muu_(k, m, n) + gamma_prime_ * qp_Guu_(k, m, n)); } } } @@ -48,13 +45,14 @@ struct IntegrateInertiaMatrixElement { } } }; + struct IntegrateInertiaMatrix { Kokkos::View::const_type elem_indices; View_NxN::const_type qp_weight_; View_NxN::const_type qp_jacobian_; Kokkos::View::const_type shape_interp_; - View_Nx6x6::const_type qp_Muu_; - View_Nx6x6::const_type qp_Guu_; + Kokkos::View::const_type qp_Muu_; + Kokkos::View::const_type qp_Guu_; double beta_prime_; double gamma_prime_; Kokkos::View gbl_M_; @@ -63,11 +61,35 @@ struct IntegrateInertiaMatrix { void operator()(const Kokkos::TeamPolicy<>::member_type& member) const { const auto i_elem = member.league_rank(); const auto idx = elem_indices(i_elem); + const auto shape_interp = + Kokkos::View(member.team_scratch(1), idx.num_nodes, idx.num_qps); + + const auto qp_weight = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_jacobian = Kokkos::View(member.team_scratch(1), idx.num_qps); + + const auto qp_Muu = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_Guu = Kokkos::View(member.team_scratch(1), idx.num_qps); + + Kokkos::parallel_for(Kokkos::TeamThreadRange(member, idx.num_qps), [=](size_t k) { + for (auto i = 0U; i < idx.num_nodes; ++i) { + shape_interp(i, k) = shape_interp_(i_elem, i, k); + } + qp_weight(k) = qp_weight_(i_elem, k); + qp_jacobian(k) = qp_jacobian_(i_elem, k); + for (auto m = 0U; m < 6U; ++m) { + for (auto n = 0U; n < 6U; ++n) { + qp_Muu(k, m, n) = qp_Muu_(i_elem, k, m, n); + qp_Guu(k, m, n) = qp_Guu_(i_elem, k, m, n); + } + } + }); + member.team_barrier(); + const auto node_range = Kokkos::TeamThreadMDRange(member, idx.num_nodes, idx.num_nodes); const auto element_integrator = IntegrateInertiaMatrixElement{ - i_elem, idx.num_qps, idx.node_range.first, idx.qp_range.first, - qp_weight_, qp_jacobian_, shape_interp_, qp_Muu_, - qp_Guu_, beta_prime_, gamma_prime_, gbl_M_}; + i_elem, idx.num_qps, idx.node_range.first, idx.qp_range.first, + qp_weight, qp_jacobian, shape_interp, qp_Muu, + qp_Guu, beta_prime_, gamma_prime_, gbl_M_}; Kokkos::parallel_for(node_range, element_integrator); } }; diff --git a/src/restruct_poc/system/integrate_stiffness_matrix.hpp b/src/restruct_poc/system/integrate_stiffness_matrix.hpp index e8f542d1..7be6ceba 100644 --- a/src/restruct_poc/system/integrate_stiffness_matrix.hpp +++ b/src/restruct_poc/system/integrate_stiffness_matrix.hpp @@ -6,47 +6,42 @@ #include "src/restruct_poc/types.hpp" namespace openturbine { - struct IntegrateStiffnessMatrixElement { int i_elem; size_t num_qps; size_t first_node; size_t first_qp; - View_NxN::const_type qp_weight_; - View_NxN::const_type qp_jacobian_; - Kokkos::View::const_type shape_interp_; - Kokkos::View::const_type shape_deriv_; - View_Nx6x6::const_type qp_Kuu_; - View_Nx6x6::const_type qp_Puu_; - View_Nx6x6::const_type qp_Cuu_; - View_Nx6x6::const_type qp_Ouu_; - View_Nx6x6::const_type qp_Quu_; + View_N::const_type qp_weight_; + View_N::const_type qp_jacobian_; + Kokkos::View::const_type shape_interp_; + Kokkos::View::const_type shape_deriv_; + Kokkos::View::const_type qp_Kuu_; + Kokkos::View::const_type qp_Puu_; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type qp_Ouu_; + Kokkos::View::const_type qp_Quu_; Kokkos::View gbl_M_; KOKKOS_FUNCTION void operator()(size_t i_index, size_t j_index) const { auto local_M_data = Kokkos::Array{}; const auto local_M = Kokkos::View(local_M_data.data()); - // const auto i = i_index + first_node; - // const auto j = j_index + first_node; for (auto k = 0U; k < num_qps; ++k) { - const auto k_qp = first_qp + k; - const auto w = qp_weight_(i_elem, k); - const auto jacobian = qp_jacobian_(i_elem, k); - const auto phi_i = shape_interp_(i_elem, i_index, k); - const auto phi_j = shape_interp_(i_elem, j_index, k); - const auto phi_prime_i = shape_deriv_(i_elem, i_index, k); - const auto phi_prime_j = shape_deriv_(i_elem, j_index, k); + const auto w = qp_weight_(k); + const auto jacobian = qp_jacobian_(k); + const auto phi_i = shape_interp_(i_index, k); + const auto phi_j = shape_interp_(j_index, k); + const auto phi_prime_i = shape_deriv_(i_index, k); + const auto phi_prime_j = shape_deriv_(j_index, k); const auto K = w * phi_i * phi_j * jacobian; const auto P = w * (phi_i * phi_prime_j); - const auto Q = w * phi_i * phi_j * jacobian; const auto C = w * (phi_prime_i * phi_prime_j / jacobian); const auto O = w * (phi_prime_i * phi_j); for (auto m = 0U; m < 6U; ++m) { for (auto n = 0U; n < 6U; ++n) { - local_M(m, n) += K * qp_Kuu_(k_qp, m, n) + P * qp_Puu_(k_qp, m, n) + - Q * qp_Quu_(k_qp, m, n) + C * qp_Cuu_(k_qp, m, n) + - O * qp_Ouu_(k_qp, m, n); + local_M(m, n) += K * (qp_Kuu_(k, m, n) + qp_Quu_(k, m, n)) + + P * qp_Puu_(k, m, n) + C * qp_Cuu_(k, m, n) + + O * qp_Ouu_(k, m, n); } } } @@ -64,11 +59,11 @@ struct IntegrateStiffnessMatrix { View_NxN::const_type qp_jacobian_; Kokkos::View::const_type shape_interp_; Kokkos::View::const_type shape_deriv_; - View_Nx6x6::const_type qp_Kuu_; - View_Nx6x6::const_type qp_Puu_; - View_Nx6x6::const_type qp_Cuu_; - View_Nx6x6::const_type qp_Ouu_; - View_Nx6x6::const_type qp_Quu_; + Kokkos::View::const_type qp_Kuu_; + Kokkos::View::const_type qp_Puu_; + Kokkos::View::const_type qp_Cuu_; + Kokkos::View::const_type qp_Ouu_; + Kokkos::View::const_type qp_Quu_; Kokkos::View gbl_M_; KOKKOS_FUNCTION @@ -76,21 +71,54 @@ struct IntegrateStiffnessMatrix { const auto i_elem = member.league_rank(); const auto idx = elem_indices(i_elem); + const auto shape_interp = + Kokkos::View(member.team_scratch(1), idx.num_nodes, idx.num_qps); + const auto shape_deriv = + Kokkos::View(member.team_scratch(1), idx.num_nodes, idx.num_qps); + + const auto qp_weight = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_jacobian = Kokkos::View(member.team_scratch(1), idx.num_qps); + + const auto qp_Kuu = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_Puu = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_Cuu = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_Ouu = Kokkos::View(member.team_scratch(1), idx.num_qps); + const auto qp_Quu = Kokkos::View(member.team_scratch(1), idx.num_qps); + + Kokkos::parallel_for(Kokkos::TeamThreadRange(member, idx.num_qps), [=](size_t k) { + for (auto i = 0U; i < idx.num_nodes; ++i) { + shape_interp(i, k) = shape_interp_(i_elem, i, k); + shape_deriv(i, k) = shape_deriv_(i_elem, i, k); + } + qp_weight(k) = qp_weight_(i_elem, k); + qp_jacobian(k) = qp_jacobian_(i_elem, k); + for (auto m = 0U; m < 6U; ++m) { + for (auto n = 0U; n < 6U; ++n) { + qp_Kuu(k, m, n) = qp_Kuu_(i_elem, k, m, n); + qp_Puu(k, m, n) = qp_Puu_(i_elem, k, m, n); + qp_Cuu(k, m, n) = qp_Cuu_(i_elem, k, m, n); + qp_Ouu(k, m, n) = qp_Ouu_(i_elem, k, m, n); + qp_Quu(k, m, n) = qp_Quu_(i_elem, k, m, n); + } + } + }); + member.team_barrier(); + const auto node_range = Kokkos::TeamThreadMDRange(member, idx.num_nodes, idx.num_nodes); const auto element_integrator = IntegrateStiffnessMatrixElement{ i_elem, idx.num_qps, idx.node_range.first, idx.qp_range.first, - qp_weight_, - qp_jacobian_, - shape_interp_, - shape_deriv_, - qp_Kuu_, - qp_Puu_, - qp_Cuu_, - qp_Ouu_, - qp_Quu_, + qp_weight, + qp_jacobian, + shape_interp, + shape_deriv, + qp_Kuu, + qp_Puu, + qp_Cuu, + qp_Ouu, + qp_Quu, gbl_M_}; Kokkos::parallel_for(node_range, element_integrator); } diff --git a/src/restruct_poc/system/rotate_section_matrix.hpp b/src/restruct_poc/system/rotate_section_matrix.hpp index 5bb59632..9b1d6305 100644 --- a/src/restruct_poc/system/rotate_section_matrix.hpp +++ b/src/restruct_poc/system/rotate_section_matrix.hpp @@ -14,19 +14,34 @@ struct RotateSectionMatrix { using Default = KokkosBatched::Algo::Gemm::Default; using GemmNN = KokkosBatched::SerialGemm; using GemmNT = KokkosBatched::SerialGemm; - View_Nx6x6::const_type qp_RR0_; - View_Nx6x6::const_type qp_Cstar_; - View_Nx6x6 qp_Cuu_; + size_t i_elem; + Kokkos::View::const_type qp_RR0_; + Kokkos::View::const_type qp_Cstar_; + Kokkos::View qp_Cuu_; KOKKOS_FUNCTION void operator()(const int i_qp) const { - auto RR0 = Kokkos::subview(qp_RR0_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto Cstar = Kokkos::subview(qp_Cstar_, i_qp, Kokkos::ALL, Kokkos::ALL); - auto Cuu = Kokkos::subview(qp_Cuu_, i_qp, Kokkos::ALL, Kokkos::ALL); + const auto RR0 = + Kokkos::subview(qp_RR0_, i_elem, i_qp, Kokkos::make_pair(0, 3), Kokkos::make_pair(0, 3)); + const auto Cstar_top = + Kokkos::subview(qp_Cstar_, i_elem, i_qp, Kokkos::make_pair(0, 3), Kokkos::ALL); + const auto Cstar_bottom = + Kokkos::subview(qp_Cstar_, i_elem, i_qp, Kokkos::make_pair(3, 6), Kokkos::ALL); auto ctmp_data = Kokkos::Array{}; - auto Ctmp = View_6x6(ctmp_data.data()); - GemmNN::invoke(1., RR0, Cstar, 0., Ctmp); - GemmNT::invoke(1., Ctmp, RR0, 0., Cuu); + const auto Ctmp = View_6x6(ctmp_data.data()); + const auto Ctmp_top = Kokkos::subview(Ctmp, Kokkos::make_pair(0, 3), Kokkos::ALL); + const auto Ctmp_bottom = Kokkos::subview(Ctmp, Kokkos::make_pair(3, 6), Kokkos::ALL); + const auto Ctmp_left = Kokkos::subview(Ctmp, Kokkos::ALL, Kokkos::make_pair(0, 3)); + const auto Ctmp_right = Kokkos::subview(Ctmp, Kokkos::ALL, Kokkos::make_pair(3, 6)); + GemmNN::invoke(1., RR0, Cstar_top, 0., Ctmp_top); + GemmNN::invoke(1., RR0, Cstar_bottom, 0., Ctmp_bottom); + + const auto Cuu_left = + Kokkos::subview(qp_Cuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::make_pair(0, 3)); + const auto Cuu_right = + Kokkos::subview(qp_Cuu_, i_elem, i_qp, Kokkos::ALL, Kokkos::make_pair(3, 6)); + GemmNT::invoke(1., Ctmp_left, RR0, 0., Cuu_left); + GemmNT::invoke(1., Ctmp_right, RR0, 0., Cuu_right); } }; diff --git a/src/restruct_poc/system/update_state.hpp b/src/restruct_poc/system/update_state.hpp index fccc4136..0471aa47 100644 --- a/src/restruct_poc/system/update_state.hpp +++ b/src/restruct_poc/system/update_state.hpp @@ -3,21 +3,8 @@ #include #include -#include "calculate_Ouu.hpp" -#include "calculate_Puu.hpp" -#include "calculate_Quu.hpp" -#include "calculate_RR0.hpp" -#include "calculate_force_FC.hpp" -#include "calculate_force_FD.hpp" -#include "calculate_gravity_force.hpp" -#include "calculate_gyroscopic_matrix.hpp" -#include "calculate_inertia_stiffness_matrix.hpp" -#include "calculate_inertial_forces.hpp" -#include "calculate_mass_matrix_components.hpp" #include "calculate_node_forces.hpp" -#include "calculate_strain.hpp" -#include "calculate_temporary_variables.hpp" -#include "rotate_section_matrix.hpp" +#include "calculate_quadrature_point_values.hpp" #include "update_node_state.hpp" #include "src/restruct_poc/beams/beams.hpp" @@ -55,86 +42,24 @@ inline void UpdateState( ); Kokkos::parallel_for( - "CalculateRR0", beams.num_qps, - CalculateRR0{ - beams.qp_r0, - beams.qp_r, - beams.qp_RR0, - } - ); - - Kokkos::parallel_for( - "RotateSectionMatrix", beams.num_qps, - RotateSectionMatrix{beams.qp_RR0, beams.qp_Mstar, beams.qp_Muu} - ); - - Kokkos::parallel_for( - "RotateSectionMatrix", beams.num_qps, - RotateSectionMatrix{beams.qp_RR0, beams.qp_Cstar, beams.qp_Cuu} - ); - - Kokkos::parallel_for( - "CalculateStrain", beams.num_qps, - CalculateStrain{ - beams.qp_x0_prime, - beams.qp_u_prime, - beams.qp_r, - beams.qp_r_prime, - beams.qp_strain, - } - ); - - Kokkos::parallel_for( - "CalculateMassMatrixComponents", beams.num_qps, - CalculateMassMatrixComponents{beams.qp_Muu, beams.qp_eta, beams.qp_rho, beams.qp_eta_tilde} - ); - Kokkos::parallel_for( - "CalculateTemporaryVariables", beams.num_qps, - CalculateTemporaryVariables{beams.qp_x0_prime, beams.qp_u_prime, beams.qp_x0pupss} - ); - Kokkos::parallel_for( - "CalculateForceFC", beams.num_qps, - CalculateForceFC{ - beams.qp_Cuu, beams.qp_strain, beams.qp_Fc, beams.qp_M_tilde, beams.qp_N_tilde} - ); - Kokkos::parallel_for( - "CalculateForceFD", beams.num_qps, - CalculateForceFD{beams.qp_x0pupss, beams.qp_Fc, beams.qp_Fd} - ); - Kokkos::parallel_for( - "CalculateInertialForces", beams.num_qps, - CalculateInertialForces{ - beams.qp_Muu, beams.qp_u_ddot, beams.qp_omega, beams.qp_omega_dot, beams.qp_eta_tilde, - beams.qp_omega_tilde, beams.qp_omega_dot_tilde, beams.qp_rho, beams.qp_eta, beams.qp_Fi} - ); - Kokkos::parallel_for( - "CalculateGravityForce", beams.num_qps, - CalculateGravityForce{beams.gravity, beams.qp_Muu, beams.qp_eta_tilde, beams.qp_Fg} - ); - Kokkos::parallel_for( - "CalculateOuu", beams.num_qps, - CalculateOuu{ - beams.qp_Cuu, beams.qp_x0pupss, beams.qp_M_tilde, beams.qp_N_tilde, beams.qp_Ouu} - ); - Kokkos::parallel_for( - "CalculatePuu", beams.num_qps, - CalculatePuu{beams.qp_Cuu, beams.qp_x0pupss, beams.qp_N_tilde, beams.qp_Puu} - ); - Kokkos::parallel_for( - "CalculateQuu", beams.num_qps, - CalculateQuu{beams.qp_Cuu, beams.qp_x0pupss, beams.qp_N_tilde, beams.qp_Quu} - ); - Kokkos::parallel_for( - "CalculateGyroscopicMatrix", beams.num_qps, - CalculateGyroscopicMatrix{ - beams.qp_Muu, beams.qp_omega, beams.qp_omega_tilde, beams.qp_rho, beams.qp_eta, - beams.qp_Guu} - ); - Kokkos::parallel_for( - "CalculateInertiaStiffnessMatrix", beams.num_qps, - CalculateInertiaStiffnessMatrix{ - beams.qp_Muu, beams.qp_u_ddot, beams.qp_omega, beams.qp_omega_dot, beams.qp_omega_tilde, - beams.qp_omega_dot_tilde, beams.qp_rho, beams.qp_eta, beams.qp_Kuu} + "CalculateQuadraturePointValues", range_policy, + CalculateQuadraturePointValues{beams.elem_indices, beams.gravity, + beams.qp_u_prime, beams.qp_r, + beams.qp_r_prime, beams.qp_r0, + beams.qp_x0_prime, beams.qp_u_ddot, + beams.qp_omega, beams.qp_omega_dot, + beams.qp_Mstar, beams.qp_Cstar, + 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_Fg, + beams.qp_Muu, beams.qp_Cuu, + beams.qp_Ouu, beams.qp_Puu, + beams.qp_Quu, beams.qp_Guu, + beams.qp_Kuu} ); Kokkos::parallel_for( diff --git a/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_state.cpp b/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_state.cpp index 909efab2..1b256590 100644 --- a/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_state.cpp +++ b/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_state.cpp @@ -27,16 +27,16 @@ TEST(InterpolateQPStateTests, u_OneNodeOneQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeOneQP(); auto node_u = create_node_u_OneNode(); - auto qp_u = Kokkos::View("qp_u"); + auto qp_u = Kokkos::View("qp_u"); Kokkos::parallel_for( num_qp, InterpolateQPState_u{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_u} ); auto qp_u_mirror = Kokkos::create_mirror(qp_u); Kokkos::deep_copy(qp_u_mirror, qp_u); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 2), 6., tolerance); } TEST(InterpolateQPStateTests, uprime_OneNodeOneQP) { @@ -47,7 +47,7 @@ TEST(InterpolateQPStateTests, uprime_OneNodeOneQP) { auto shape_deriv = create_shape_deriv_OneNodeOneQP(); auto jacobian = create_jacobian_OneQP(); auto node_u = create_node_u_OneNode(); - auto qp_uprime = Kokkos::View("qp_uprime"); + auto qp_uprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_uprime{ @@ -56,9 +56,9 @@ TEST(InterpolateQPStateTests, uprime_OneNodeOneQP) { auto qp_uprime_mirror = Kokkos::create_mirror(qp_uprime); Kokkos::deep_copy(qp_uprime_mirror, qp_uprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_uprime_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 2), 6., tolerance); } TEST(InterpolateQPStateTests, r_OneNodeOneQP) { @@ -68,17 +68,17 @@ TEST(InterpolateQPStateTests, r_OneNodeOneQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeOneQP(); auto node_u = create_node_u_OneNode(); - auto qp_r = Kokkos::View("qp_r"); + auto qp_r = Kokkos::View("qp_r"); Kokkos::parallel_for( num_qp, InterpolateQPState_r{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_r} ); auto qp_r_mirror = Kokkos::create_mirror(qp_r); Kokkos::deep_copy(qp_r_mirror, qp_r); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_r_mirror(0, 0), 8., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 1), 10., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 2), 12., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 3), 14., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 0), 8., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 1), 10., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 2), 12., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 3), 14., tolerance); } TEST(InterpolateQPStateTests, rprime_OneNodeOneQP) { @@ -89,7 +89,7 @@ TEST(InterpolateQPStateTests, rprime_OneNodeOneQP) { auto shape_deriv = create_shape_deriv_OneNodeOneQP(); auto jacobian = create_jacobian_OneQP(); auto node_u = create_node_u_OneNode(); - auto qp_rprime = Kokkos::View("qp_uprime"); + auto qp_rprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_rprime{ @@ -98,10 +98,10 @@ TEST(InterpolateQPStateTests, rprime_OneNodeOneQP) { auto qp_rprime_mirror = Kokkos::create_mirror(qp_rprime); Kokkos::deep_copy(qp_rprime_mirror, qp_rprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_rprime_mirror(0, 0), 8., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 1), 10., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 2), 12., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 3), 14., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 0), 8., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 1), 10., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 2), 12., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 3), 14., tolerance); } TEST(InterpolateQPStateTests, u_OneNodeTwoQP) { @@ -111,20 +111,20 @@ TEST(InterpolateQPStateTests, u_OneNodeTwoQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeTwoQP(); auto node_u = create_node_u_OneNode(); - auto qp_u = Kokkos::View("qp_u"); + auto qp_u = Kokkos::View("qp_u"); Kokkos::parallel_for( num_qp, InterpolateQPState_u{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_u} ); auto qp_u_mirror = Kokkos::create_mirror(qp_u); Kokkos::deep_copy(qp_u_mirror, qp_u); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 2), 6., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 0), 4., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 1), 8., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 2), 12., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 0), 4., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 1), 8., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 2), 12., tolerance); } TEST(InterpolateQPStateTests, uprime_OneNodeTwoQP) { @@ -135,7 +135,7 @@ TEST(InterpolateQPStateTests, uprime_OneNodeTwoQP) { auto shape_deriv = create_shape_deriv_OneNodeTwoQP(); auto jacobian = create_jacobian_TwoQP(); auto node_u = create_node_u_OneNode(); - auto qp_uprime = Kokkos::View("qp_uprime"); + auto qp_uprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_uprime{ @@ -144,13 +144,13 @@ TEST(InterpolateQPStateTests, uprime_OneNodeTwoQP) { auto qp_uprime_mirror = Kokkos::create_mirror(qp_uprime); Kokkos::deep_copy(qp_uprime_mirror, qp_uprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_uprime_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 2), 6., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 0), 3., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 1), 6., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 2), 9., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 0), 3., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 1), 6., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 2), 9., tolerance); } TEST(InterpolateQPStateTests, r_OneNodeTwoQP) { @@ -160,22 +160,22 @@ TEST(InterpolateQPStateTests, r_OneNodeTwoQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeTwoQP(); auto node_u = create_node_u_OneNode(); - auto qp_r = Kokkos::View("qp_r"); + auto qp_r = Kokkos::View("qp_r"); Kokkos::parallel_for( num_qp, InterpolateQPState_r{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_r} ); auto qp_r_mirror = Kokkos::create_mirror(qp_r); Kokkos::deep_copy(qp_r_mirror, qp_r); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_r_mirror(0, 0), 8., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 1), 10., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 2), 12., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 3), 14., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 0), 8., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 1), 10., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 2), 12., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 3), 14., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 0), 16., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 1), 20., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 2), 24., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 3), 28., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 0), 16., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 1), 20., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 2), 24., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 3), 28., tolerance); } TEST(InterpolateQPStateTests, rprime_OneNodeTwoQP) { @@ -186,7 +186,7 @@ TEST(InterpolateQPStateTests, rprime_OneNodeTwoQP) { auto shape_deriv = create_shape_deriv_OneNodeTwoQP(); auto jacobian = create_jacobian_TwoQP(); auto node_u = create_node_u_OneNode(); - auto qp_rprime = Kokkos::View("qp_uprime"); + auto qp_rprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_rprime{ @@ -195,15 +195,15 @@ TEST(InterpolateQPStateTests, rprime_OneNodeTwoQP) { auto qp_rprime_mirror = Kokkos::create_mirror(qp_rprime); Kokkos::deep_copy(qp_rprime_mirror, qp_rprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_rprime_mirror(0, 0), 8., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 1), 10., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 2), 12., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 3), 14., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 0), 8., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 1), 10., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 2), 12., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 3), 14., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 0), 12., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 1), 15., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 2), 18., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 3), 21., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 0), 12., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 1), 15., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 2), 18., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 3), 21., tolerance); } inline auto create_node_u_TwoNode() { @@ -227,20 +227,20 @@ TEST(InterpolateQPStateTests, u_TwoNodeTwoQP) { constexpr auto num_nodes = 2; auto shape_interp = create_shape_interp_TwoNodeTwoQP(); auto node_u = create_node_u_TwoNode(); - auto qp_u = Kokkos::View("qp_u"); + auto qp_u = Kokkos::View("qp_u"); Kokkos::parallel_for( num_qp, InterpolateQPState_u{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_u} ); auto qp_u_mirror = Kokkos::create_mirror(qp_u); Kokkos::deep_copy(qp_u_mirror, qp_u); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_mirror(0, 0), 34., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 1), 40., tolerance); - EXPECT_NEAR(qp_u_mirror(0, 2), 46., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 0), 34., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 1), 40., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 0, 2), 46., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 0), 43., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 1), 51., tolerance); - EXPECT_NEAR(qp_u_mirror(1, 2), 59., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 0), 43., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 1), 51., tolerance); + EXPECT_NEAR(qp_u_mirror(0, 1, 2), 59., tolerance); } TEST(InterpolateQPStateTests, uprime_TwoNodeTwoQP) { @@ -251,7 +251,7 @@ TEST(InterpolateQPStateTests, uprime_TwoNodeTwoQP) { auto shape_deriv = create_shape_deriv_TwoNodeTwoQP(); auto jacobian = create_jacobian_TwoQP(); auto node_u = create_node_u_TwoNode(); - auto qp_uprime = Kokkos::View("qp_uprime"); + auto qp_uprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_uprime{ @@ -260,13 +260,13 @@ TEST(InterpolateQPStateTests, uprime_TwoNodeTwoQP) { auto qp_uprime_mirror = Kokkos::create_mirror(qp_uprime); Kokkos::deep_copy(qp_uprime_mirror, qp_uprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_uprime_mirror(0, 0), 34., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 1), 40., tolerance); - EXPECT_NEAR(qp_uprime_mirror(0, 2), 46., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 0), 34., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 1), 40., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 0, 2), 46., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 0), 43., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 1), 51., tolerance); - EXPECT_NEAR(qp_uprime_mirror(1, 2), 59., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 0), 43., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 1), 51., tolerance); + EXPECT_NEAR(qp_uprime_mirror(0, 1, 2), 59., tolerance); } TEST(InterpolateQPStateTests, r_TwoNodeTwoQP) { @@ -276,22 +276,22 @@ TEST(InterpolateQPStateTests, r_TwoNodeTwoQP) { constexpr auto num_nodes = 2; auto shape_interp = create_shape_interp_TwoNodeTwoQP(); auto node_u = create_node_u_TwoNode(); - auto qp_r = Kokkos::View("qp_r"); + auto qp_r = Kokkos::View("qp_r"); Kokkos::parallel_for( num_qp, InterpolateQPState_r{0, first_qp, first_node, num_nodes, shape_interp, node_u, qp_r} ); auto qp_r_mirror = Kokkos::create_mirror(qp_r); Kokkos::deep_copy(qp_r_mirror, qp_r); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_r_mirror(0, 0), 52., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 1), 58., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 2), 64., tolerance); - EXPECT_NEAR(qp_r_mirror(0, 3), 70., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 0), 52., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 1), 58., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 2), 64., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 0, 3), 70., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 0), 67., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 1), 75., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 2), 83., tolerance); - EXPECT_NEAR(qp_r_mirror(1, 3), 91., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 0), 67., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 1), 75., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 2), 83., tolerance); + EXPECT_NEAR(qp_r_mirror(0, 1, 3), 91., tolerance); } TEST(InterpolateQPStateTests, rprime_TwoNodeTwoQP) { @@ -302,7 +302,7 @@ TEST(InterpolateQPStateTests, rprime_TwoNodeTwoQP) { auto shape_deriv = create_shape_deriv_TwoNodeTwoQP(); auto jacobian = create_jacobian_TwoQP(); auto node_u = create_node_u_TwoNode(); - auto qp_rprime = Kokkos::View("qp_uprime"); + auto qp_rprime = Kokkos::View("qp_uprime"); Kokkos::parallel_for( num_qp, InterpolateQPState_rprime{ @@ -311,15 +311,15 @@ TEST(InterpolateQPStateTests, rprime_TwoNodeTwoQP) { auto qp_rprime_mirror = Kokkos::create_mirror(qp_rprime); Kokkos::deep_copy(qp_rprime_mirror, qp_rprime); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_rprime_mirror(0, 0), 52., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 1), 58., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 2), 64., tolerance); - EXPECT_NEAR(qp_rprime_mirror(0, 3), 70., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 0), 52., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 1), 58., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 2), 64., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 0, 3), 70., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 0), 67., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 1), 75., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 2), 83., tolerance); - EXPECT_NEAR(qp_rprime_mirror(1, 3), 91., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 0), 67., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 1), 75., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 2), 83., tolerance); + EXPECT_NEAR(qp_rprime_mirror(0, 1, 3), 91., tolerance); } } // namespace openturbine::tests \ No newline at end of file diff --git a/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_vector.cpp b/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_vector.cpp index 4d04f574..9cb23ae1 100644 --- a/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_vector.cpp +++ b/tests/unit_tests/restruct_poc/beams/test_interpolate_QP_vector.cpp @@ -27,7 +27,7 @@ TEST(InterpolateQPVectorTests, OneNodeOneQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeOneQP(); auto node_u_dot = create_node_u_dot_OneNode(); - auto qp_u_dot = Kokkos::View("qp_u_dot"); + auto qp_u_dot = Kokkos::View("qp_u_dot"); Kokkos::parallel_for( num_qp, InterpolateQPVector{ @@ -37,9 +37,9 @@ TEST(InterpolateQPVectorTests, OneNodeOneQP) { auto qp_u_dot_mirror = Kokkos::create_mirror(qp_u_dot); Kokkos::deep_copy(qp_u_dot_mirror, qp_u_dot); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_dot_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 2), 6., tolerance); } TEST(InterpolateQPVectorTests, OneNodeTwoQP) { @@ -49,7 +49,7 @@ TEST(InterpolateQPVectorTests, OneNodeTwoQP) { constexpr auto num_nodes = 1; auto shape_interp = create_shape_interp_OneNodeTwoQP(); auto node_u_dot = create_node_u_dot_OneNode(); - auto qp_u_dot = Kokkos::View("qp_u_dot"); + auto qp_u_dot = Kokkos::View("qp_u_dot"); Kokkos::parallel_for( num_qp, InterpolateQPVector{ @@ -59,13 +59,13 @@ TEST(InterpolateQPVectorTests, OneNodeTwoQP) { auto qp_u_dot_mirror = Kokkos::create_mirror(qp_u_dot); Kokkos::deep_copy(qp_u_dot_mirror, qp_u_dot); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_dot_mirror(0, 0), 2., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 1), 4., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 2), 6., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 0), 2., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 1), 4., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 2), 6., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 0), 4., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 1), 8., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 2), 12., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 0), 4., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 1), 8., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 2), 12., tolerance); } inline auto create_node_u_dot_TwoNode() { @@ -89,7 +89,7 @@ TEST(InterpolateQPVectorTests, TwoNodeTwoQP) { constexpr auto num_nodes = 2; auto shape_interp = create_shape_interp_TwoNodeTwoQP(); auto node_u_dot = create_node_u_dot_TwoNode(); - auto qp_u_dot = Kokkos::View("qp_u_dot"); + auto qp_u_dot = Kokkos::View("qp_u_dot"); Kokkos::parallel_for( num_qp, InterpolateQPVector{ @@ -99,13 +99,13 @@ TEST(InterpolateQPVectorTests, TwoNodeTwoQP) { auto qp_u_dot_mirror = Kokkos::create_mirror(qp_u_dot); Kokkos::deep_copy(qp_u_dot_mirror, qp_u_dot); constexpr auto tolerance = 1.e-16; - EXPECT_NEAR(qp_u_dot_mirror(0, 0), 30., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 1), 36., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(0, 2), 42., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 0), 30., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 1), 36., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 0, 2), 42., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 0), 38., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 1), 46., tolerance); - EXPECT_NEAR(qp_u_dot_mirror(1, 2), 54., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 0), 38., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 1), 46., tolerance); + EXPECT_NEAR(qp_u_dot_mirror(0, 1, 2), 54., tolerance); } } // namespace openturbine::tests \ No newline at end of file diff --git a/tests/unit_tests/restruct_poc/system/test_calculate.hpp b/tests/unit_tests/restruct_poc/system/test_calculate.hpp index 72eb2fac..8253c940 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate.hpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate.hpp @@ -29,4 +29,19 @@ inline void CompareWithExpected( } } +inline void CompareWithExpected( + const Kokkos::View::host_mirror_type& result, + const Kokkos::View& expected +) { + for (auto i = 0U; i < result.extent(0); ++i) { + for (auto j = 0U; j < result.extent(1); ++j) { + for (auto k = 0U; k < result.extent(2); ++k) { + for (auto l = 0U; l < result.extent(3); ++l) { + EXPECT_DOUBLE_EQ(result(i, j, k, l), expected(i, j, k, l)); + } + } + } + } +} + } // namespace openturbine::tests \ No newline at end of file diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_Ouu.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_Ouu.cpp index acbe2987..dc22fc29 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_Ouu.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_Ouu.cpp @@ -9,49 +9,49 @@ namespace openturbine::tests { TEST(CalculateOuuTests, OneNode) { - const auto Cuu = Kokkos::View("Cuu"); + const auto Cuu = Kokkos::View("Cuu"); constexpr auto Cuu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Cuu_host = Kokkos::View(Cuu_data.data()); + const auto Cuu_host = Kokkos::View(Cuu_data.data()); const auto Cuu_mirror = Kokkos::create_mirror(Cuu); Kokkos::deep_copy(Cuu_mirror, Cuu_host); Kokkos::deep_copy(Cuu, Cuu_mirror); - const auto x0pupSS = Kokkos::View("x0pupSS"); + const auto x0pupSS = Kokkos::View("x0pupSS"); constexpr auto x0pupSS_data = std::array{37., 38., 39., 40., 41., 42., 43., 44., 45.}; const auto x0pupSS_host = - Kokkos::View(x0pupSS_data.data()); + Kokkos::View(x0pupSS_data.data()); const auto x0pupSS_mirror = Kokkos::create_mirror(x0pupSS); Kokkos::deep_copy(x0pupSS_mirror, x0pupSS_host); Kokkos::deep_copy(x0pupSS, x0pupSS_mirror); - const auto M_tilde = Kokkos::View("M_tilde"); + const auto M_tilde = Kokkos::View("M_tilde"); constexpr auto M_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto M_tilde_host = - Kokkos::View(M_tilde_data.data()); + Kokkos::View(M_tilde_data.data()); const auto M_tilde_mirror = Kokkos::create_mirror(M_tilde); Kokkos::deep_copy(M_tilde_mirror, M_tilde_host); Kokkos::deep_copy(M_tilde, M_tilde_mirror); - const auto N_tilde = Kokkos::View("N_tilde"); + const auto N_tilde = Kokkos::View("N_tilde"); constexpr auto N_tilde_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; const auto N_tilde_host = - Kokkos::View(N_tilde_data.data()); + Kokkos::View(N_tilde_data.data()); const auto N_tilde_mirror = Kokkos::create_mirror(N_tilde); Kokkos::deep_copy(N_tilde_mirror, N_tilde_host); Kokkos::deep_copy(N_tilde, N_tilde_mirror); - const auto Ouu = Kokkos::View("Ouu"); + const auto Ouu = Kokkos::View("Ouu"); - Kokkos::parallel_for("CalculateOuu", 1, CalculateOuu{Cuu, x0pupSS, M_tilde, N_tilde, Ouu}); + Kokkos::parallel_for("CalculateOuu", 1, CalculateOuu{0, Cuu, x0pupSS, M_tilde, N_tilde, Ouu}); constexpr auto Ouu_exact_data = std::array{0., 0., 0., 191., 196., 201., 0., 0., 0., 908., 931., 954., 0., 0., 0., 1625., 1666., 1707., 0., 0., 0., 2360., 2419., 2478., 0., 0., 0., 3077., 3154., 3231., 0., 0., 0., 3794., 3889., 3984.}; const auto Ouu_exact = - Kokkos::View(Ouu_exact_data.data()); + Kokkos::View(Ouu_exact_data.data()); const auto Ouu_mirror = Kokkos::create_mirror(Ouu); Kokkos::deep_copy(Ouu_mirror, Ouu); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_Puu.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_Puu.cpp index bd80df08..22b373cd 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_Puu.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_Puu.cpp @@ -9,49 +9,49 @@ namespace openturbine::tests { TEST(CalculatePuuTests, OneNode) { - const auto Cuu = Kokkos::View("Cuu"); + const auto Cuu = Kokkos::View("Cuu"); constexpr auto Cuu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Cuu_host = Kokkos::View(Cuu_data.data()); + const auto Cuu_host = Kokkos::View(Cuu_data.data()); const auto Cuu_mirror = Kokkos::create_mirror(Cuu); Kokkos::deep_copy(Cuu_mirror, Cuu_host); Kokkos::deep_copy(Cuu, Cuu_mirror); - const auto x0pupSS = Kokkos::View("x0pupSS"); + const auto x0pupSS = Kokkos::View("x0pupSS"); constexpr auto x0pupSS_data = std::array{37., 38., 39., 40., 41., 42., 43., 44., 45.}; const auto x0pupSS_host = - Kokkos::View(x0pupSS_data.data()); + Kokkos::View(x0pupSS_data.data()); const auto x0pupSS_mirror = Kokkos::create_mirror(x0pupSS); Kokkos::deep_copy(x0pupSS_mirror, x0pupSS_host); Kokkos::deep_copy(x0pupSS, x0pupSS_mirror); - const auto M_tilde = Kokkos::View("M_tilde"); + const auto M_tilde = Kokkos::View("M_tilde"); constexpr auto M_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto M_tilde_host = - Kokkos::View(M_tilde_data.data()); + Kokkos::View(M_tilde_data.data()); const auto M_tilde_mirror = Kokkos::create_mirror(M_tilde); Kokkos::deep_copy(M_tilde_mirror, M_tilde_host); Kokkos::deep_copy(M_tilde, M_tilde_mirror); - const auto N_tilde = Kokkos::View("N_tilde"); + const auto N_tilde = Kokkos::View("N_tilde"); constexpr auto N_tilde_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; const auto N_tilde_host = - Kokkos::View(N_tilde_data.data()); + Kokkos::View(N_tilde_data.data()); const auto N_tilde_mirror = Kokkos::create_mirror(N_tilde); Kokkos::deep_copy(N_tilde_mirror, N_tilde_host); Kokkos::deep_copy(N_tilde, N_tilde_mirror); - const auto Puu = Kokkos::View("Puu"); + const auto Puu = Kokkos::View("Puu"); - Kokkos::parallel_for("CalculatePuu", 1, CalculatePuu{Cuu, x0pupSS, N_tilde, Puu}); + Kokkos::parallel_for("CalculatePuu", 1, CalculatePuu{0, Cuu, x0pupSS, N_tilde, Puu}); constexpr auto Puu_exact_data = std::array{0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 931., 1052., 1173., 1236., 1356., 1476., 955., 1079., 1203., 1266., 1389., 1512., 979., 1106., 1233., 1296., 1422., 1548.}; const auto Puu_exact = - Kokkos::View(Puu_exact_data.data()); + Kokkos::View(Puu_exact_data.data()); const auto Puu_mirror = Kokkos::create_mirror(Puu); Kokkos::deep_copy(Puu_mirror, Puu); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_Quu.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_Quu.cpp index bf4d5b78..09f3e9fb 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_Quu.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_Quu.cpp @@ -9,49 +9,49 @@ namespace openturbine::tests { TEST(CalculateQuuTests, OneNode) { - const auto Cuu = Kokkos::View("Cuu"); + const auto Cuu = Kokkos::View("Cuu"); constexpr auto Cuu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Cuu_host = Kokkos::View(Cuu_data.data()); + const auto Cuu_host = Kokkos::View(Cuu_data.data()); const auto Cuu_mirror = Kokkos::create_mirror(Cuu); Kokkos::deep_copy(Cuu_mirror, Cuu_host); Kokkos::deep_copy(Cuu, Cuu_mirror); - const auto x0pupSS = Kokkos::View("x0pupSS"); + const auto x0pupSS = Kokkos::View("x0pupSS"); constexpr auto x0pupSS_data = std::array{37., 38., 39., 40., 41., 42., 43., 44., 45.}; const auto x0pupSS_host = - Kokkos::View(x0pupSS_data.data()); + Kokkos::View(x0pupSS_data.data()); const auto x0pupSS_mirror = Kokkos::create_mirror(x0pupSS); Kokkos::deep_copy(x0pupSS_mirror, x0pupSS_host); Kokkos::deep_copy(x0pupSS, x0pupSS_mirror); - const auto M_tilde = Kokkos::View("M_tilde"); + const auto M_tilde = Kokkos::View("M_tilde"); constexpr auto M_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto M_tilde_host = - Kokkos::View(M_tilde_data.data()); + Kokkos::View(M_tilde_data.data()); const auto M_tilde_mirror = Kokkos::create_mirror(M_tilde); Kokkos::deep_copy(M_tilde_mirror, M_tilde_host); Kokkos::deep_copy(M_tilde, M_tilde_mirror); - const auto N_tilde = Kokkos::View("N_tilde"); + const auto N_tilde = Kokkos::View("N_tilde"); constexpr auto N_tilde_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; const auto N_tilde_host = - Kokkos::View(N_tilde_data.data()); + Kokkos::View(N_tilde_data.data()); const auto N_tilde_mirror = Kokkos::create_mirror(N_tilde); Kokkos::deep_copy(N_tilde_mirror, N_tilde_host); Kokkos::deep_copy(N_tilde, N_tilde_mirror); - const auto Quu = Kokkos::View("Quu"); + const auto Quu = Kokkos::View("Quu"); - Kokkos::parallel_for("CalculateQuu", 1, CalculateQuu{Cuu, x0pupSS, N_tilde, Quu}); + Kokkos::parallel_for("CalculateQuu", 1, CalculateQuu{0, Cuu, x0pupSS, N_tilde, Quu}); constexpr auto Quu_exact_data = std::array{0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 113262., 116130., 118998., 0., 0., 0., 115986., 118923., 121860., 0., 0., 0., 118710., 121716., 124722.}; const auto Quu_exact = - Kokkos::View(Quu_exact_data.data()); + Kokkos::View(Quu_exact_data.data()); const auto Quu_mirror = Kokkos::create_mirror(Quu); Kokkos::deep_copy(Quu_mirror, Quu); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_RR0.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_RR0.cpp index 120e495a..9c81e43f 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_RR0.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_RR0.cpp @@ -9,30 +9,30 @@ namespace openturbine::tests { TEST(CalculateRR0Tests, OneNode) { - const auto r0 = Kokkos::View("r0"); + const auto r0 = Kokkos::View("r0"); constexpr auto r0_host_data = std::array{1., 2., 3., 4.}; - const auto r0_host = Kokkos::View(r0_host_data.data()); + const auto r0_host = Kokkos::View(r0_host_data.data()); const auto r0_mirror = Kokkos::create_mirror(r0); Kokkos::deep_copy(r0_mirror, r0_host); Kokkos::deep_copy(r0, r0_mirror); - const auto r = Kokkos::View("r"); + const auto r = Kokkos::View("r"); constexpr auto r_host_data = std::array{5., 6., 7., 8.}; - const auto r_host = Kokkos::View(r_host_data.data()); + const auto r_host = Kokkos::View(r_host_data.data()); const auto r_mirror = Kokkos::create_mirror(r); Kokkos::deep_copy(r_mirror, r_host); Kokkos::deep_copy(r, r_mirror); - const auto rr0 = Kokkos::View("rr0"); + const auto rr0 = Kokkos::View("rr0"); - Kokkos::parallel_for("CalculateRR0", 1, CalculateRR0{r0, r, rr0}); + Kokkos::parallel_for("CalculateRR0", 1, CalculateRR0{0, r0, r, rr0}); constexpr auto expected_rr0_data = std::array{ 2780., 4400., -400., 0., 0., 0., -3280., 2372., 3296., 0., 0., 0., 2960., -1504., 4028., 0., 0., 0., 0., 0., 0., 2780., 4400., -400., 0., 0., 0., -3280., 2372., 3296., 0., 0., 0., 2960., -1504., 4028.}; const auto expected_rr0 = - Kokkos::View(expected_rr0_data.data()); + Kokkos::View(expected_rr0_data.data()); const auto rr0_mirror = Kokkos::create_mirror(rr0); Kokkos::deep_copy(rr0_mirror, rr0); @@ -40,23 +40,23 @@ TEST(CalculateRR0Tests, OneNode) { } TEST(CalculateRR0Tests, TwoNodes) { - const auto r0 = Kokkos::View("r0"); + const auto r0 = Kokkos::View("r0"); constexpr auto r0_host_data = std::array{1., 2., 3., 4., 5., 6., 7., 8.}; - const auto r0_host = Kokkos::View(r0_host_data.data()); + const auto r0_host = Kokkos::View(r0_host_data.data()); const auto r0_mirror = Kokkos::create_mirror(r0); Kokkos::deep_copy(r0_mirror, r0_host); Kokkos::deep_copy(r0, r0_mirror); - const auto r = Kokkos::View("r"); + const auto r = Kokkos::View("r"); constexpr auto r_host_data = std::array{5., 6., 7., 8., 9., 10., 11., 12.}; - const auto r_host = Kokkos::View(r_host_data.data()); + const auto r_host = Kokkos::View(r_host_data.data()); const auto r_mirror = Kokkos::create_mirror(r); Kokkos::deep_copy(r_mirror, r_host); Kokkos::deep_copy(r, r_mirror); - const auto rr0 = Kokkos::View("rr0"); + const auto rr0 = Kokkos::View("rr0"); - Kokkos::parallel_for("CalculateRR0", 2, CalculateRR0{r0, r, rr0}); + Kokkos::parallel_for("CalculateRR0", 2, CalculateRR0{0, r0, r, rr0}); constexpr auto expected_rr0_data = std::array{2780., 4400., -400., 0., 0., 0., -3280., 2372., 3296., @@ -69,18 +69,18 @@ TEST(CalculateRR0Tests, TwoNodes) { 0., 0., 0., 16412., 74896., -11984., 0., 0., 0., -27376., 17284., 70528., 0., 0., 0., 70736., -10688., 30076.}; const auto expected_rr0 = - Kokkos::View(expected_rr0_data.data()); + Kokkos::View(expected_rr0_data.data()); const auto rr0_mirror = Kokkos::create_mirror(rr0); Kokkos::deep_copy(rr0_mirror, rr0); for (int i = 0; i < 6; ++i) { for (int j = 0; j < 6; ++j) { - EXPECT_EQ(rr0_mirror(0, i, j), expected_rr0(0, i, j)); + EXPECT_EQ(rr0_mirror(0, 0, i, j), expected_rr0(0, 0, i, j)); } } for (int i = 0; i < 6; ++i) { for (int j = 0; j < 6; ++j) { - EXPECT_EQ(rr0_mirror(1, i, j), expected_rr0(1, i, j)); + EXPECT_EQ(rr0_mirror(0, 1, i, j), expected_rr0(0, 1, i, j)); } } } diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_force_FC.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_force_FC.cpp index d123b5cc..35929ce5 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_force_FC.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_force_FC.cpp @@ -9,31 +9,35 @@ namespace openturbine::tests { TEST(CalculateForceFCTests, OneNode) { - const auto Cuu = Kokkos::View("Cuu"); + const auto Cuu = Kokkos::View("Cuu"); constexpr auto Cuu_data = std::array{ 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., }; - const auto Cuu_host = Kokkos::View(Cuu_data.data()); + const auto Cuu_host = Kokkos::View(Cuu_data.data()); const auto Cuu_mirror = Kokkos::create_mirror(Cuu); Kokkos::deep_copy(Cuu_mirror, Cuu_host); Kokkos::deep_copy(Cuu, Cuu_mirror); - const auto strain = Kokkos::View("strain"); + const auto strain = Kokkos::View("strain"); constexpr auto strain_data = std::array{37., 38., 39., 40., 41., 42.}; - const auto strain_host = Kokkos::View(strain_data.data()); + const auto strain_host = + Kokkos::View(strain_data.data()); const auto strain_mirror = Kokkos::create_mirror(strain); Kokkos::deep_copy(strain_mirror, strain_host); Kokkos::deep_copy(strain, strain_mirror); - const auto FC = Kokkos::View("FC"); - const auto M_tilde = Kokkos::View("M_tilde"); - const auto N_tilde = Kokkos::View("N_tilde"); + const auto FC = Kokkos::View("FC"); + const auto M_tilde = Kokkos::View("M_tilde"); + const auto N_tilde = Kokkos::View("N_tilde"); - Kokkos::parallel_for("CalculateForceFC", 1, CalculateForceFC{Cuu, strain, FC, M_tilde, N_tilde}); + Kokkos::parallel_for( + "CalculateForceFC", 1, CalculateForceFC{0, Cuu, strain, FC, M_tilde, N_tilde} + ); constexpr auto FC_exact_data = std::array{847., 2269., 3691., 5113., 6535., 7957.}; - const auto FC_exact = Kokkos::View(FC_exact_data.data()); + const auto FC_exact = + Kokkos::View(FC_exact_data.data()); const auto FC_mirror = Kokkos::create_mirror(FC); Kokkos::deep_copy(FC_mirror, FC); @@ -42,7 +46,7 @@ TEST(CalculateForceFCTests, OneNode) { constexpr auto M_tilde_exact_data = std::array{0., -7957., 6535., 7957., 0., -5113., -6535., 5113., 0.}; const auto M_tilde_exact = - Kokkos::View(M_tilde_exact_data.data()); + Kokkos::View(M_tilde_exact_data.data()); const auto M_tilde_mirror = Kokkos::create_mirror(M_tilde); Kokkos::deep_copy(M_tilde_mirror, M_tilde); @@ -51,7 +55,7 @@ TEST(CalculateForceFCTests, OneNode) { constexpr auto N_tilde_exact_data = std::array{0., -3691., 2269., 3691., 0., -847., -2269., 847., 0.}; const auto N_tilde_exact = - Kokkos::View(N_tilde_exact_data.data()); + Kokkos::View(N_tilde_exact_data.data()); const auto N_tilde_mirror = Kokkos::create_mirror(N_tilde); Kokkos::deep_copy(N_tilde_mirror, N_tilde); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_force_FD.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_force_FD.cpp index 739ad471..2c05fee2 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_force_FD.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_force_FD.cpp @@ -9,27 +9,28 @@ namespace openturbine::tests { TEST(CalculateForceFDTests, OneNode) { - const auto x0pupSS = Kokkos::View("x0pupSS"); + const auto x0pupSS = Kokkos::View("x0pupSS"); constexpr auto x0pupSS_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9.}; const auto x0pupSS_host = - Kokkos::View(x0pupSS_data.data()); + Kokkos::View(x0pupSS_data.data()); const auto x0pupSS_mirror = Kokkos::create_mirror(x0pupSS); Kokkos::deep_copy(x0pupSS_mirror, x0pupSS_host); Kokkos::deep_copy(x0pupSS, x0pupSS_mirror); - const auto FC = Kokkos::View("FC"); + const auto FC = Kokkos::View("FC"); constexpr auto FC_data = std::array{10., 11., 12., 13., 14., 15.}; - const auto FC_host = Kokkos::View(FC_data.data()); + const auto FC_host = Kokkos::View(FC_data.data()); const auto FC_mirror = Kokkos::create_mirror(FC); Kokkos::deep_copy(FC_mirror, FC_host); Kokkos::deep_copy(FC, FC_mirror); - const auto FD = Kokkos::View("FD"); + const auto FD = Kokkos::View("FD"); - Kokkos::parallel_for("CalculateForceFD", 1, CalculateForceFD{x0pupSS, FC, FD}); + Kokkos::parallel_for("CalculateForceFD", 1, CalculateForceFD{0, x0pupSS, FC, FD}); constexpr auto FD_exact_data = std::array{0., 0., 0., 138., 171., 204.}; - const auto FD_exact = Kokkos::View(FD_exact_data.data()); + const auto FD_exact = + Kokkos::View(FD_exact_data.data()); const auto FD_mirror = Kokkos::create_mirror(FD); Kokkos::deep_copy(FD_mirror, FD); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_gravity_force.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_gravity_force.cpp index ac604890..ff8341f4 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_gravity_force.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_gravity_force.cpp @@ -9,19 +9,19 @@ namespace openturbine::tests { TEST(CalculateGravityForceTests, OneNode) { - const auto Muu = Kokkos::View("Muu"); + const auto Muu = Kokkos::View("Muu"); constexpr auto Muu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Muu_host = Kokkos::View(Muu_data.data()); + const auto Muu_host = Kokkos::View(Muu_data.data()); const auto Muu_mirror = Kokkos::create_mirror(Muu); Kokkos::deep_copy(Muu_mirror, Muu_host); Kokkos::deep_copy(Muu, Muu_mirror); - const auto eta_tilde = Kokkos::View("eta_tilde"); + const auto eta_tilde = Kokkos::View("eta_tilde"); constexpr auto eta_tilde_data = std::array{37., 38., 39., 40., 41., 42., 43., 44., 45.}; const auto eta_tilde_host = - Kokkos::View(eta_tilde_data.data()); + Kokkos::View(eta_tilde_data.data()); const auto eta_tilde_mirror = Kokkos::create_mirror(eta_tilde); Kokkos::deep_copy(eta_tilde_mirror, eta_tilde_host); Kokkos::deep_copy(eta_tilde, eta_tilde_mirror); @@ -33,14 +33,15 @@ TEST(CalculateGravityForceTests, OneNode) { Kokkos::deep_copy(gravity_mirror, gravity_host); Kokkos::deep_copy(gravity, gravity_mirror); - const auto FG = Kokkos::View("FG"); + const auto FG = Kokkos::View("FG"); Kokkos::parallel_for( - "CalculateGravityForce", 1, CalculateGravityForce{gravity, Muu, eta_tilde, FG} + "CalculateGravityForce", 1, CalculateGravityForce{0, gravity, Muu, eta_tilde, FG} ); constexpr auto FG_exact_data = std::array{46., 47., 48., 5360., 5783., 6206.}; - const auto FG_exact = Kokkos::View(FG_exact_data.data()); + const auto FG_exact = + Kokkos::View(FG_exact_data.data()); const auto FG_mirror = Kokkos::create_mirror(FG); Kokkos::deep_copy(FG_mirror, FG); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_gyroscopic_matrix.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_gyroscopic_matrix.cpp index 7de57f05..a352050b 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_gyroscopic_matrix.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_gyroscopic_matrix.cpp @@ -9,49 +9,50 @@ namespace openturbine::tests { TEST(CalculateGyroscopicMatrixTests, OneNode) { - const auto Muu = Kokkos::View("Muu"); + const auto Muu = Kokkos::View("Muu"); constexpr auto Muu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Muu_host = Kokkos::View(Muu_data.data()); + const auto Muu_host = Kokkos::View(Muu_data.data()); const auto Muu_mirror = Kokkos::create_mirror(Muu); Kokkos::deep_copy(Muu_mirror, Muu_host); Kokkos::deep_copy(Muu, Muu_mirror); - const auto omega = Kokkos::View("omega"); + const auto omega = Kokkos::View("omega"); constexpr auto omega_data = std::array{40., 41., 42.}; - const auto omega_host = Kokkos::View(omega_data.data()); + const auto omega_host = + Kokkos::View(omega_data.data()); const auto omega_mirror = Kokkos::create_mirror(omega); Kokkos::deep_copy(omega_mirror, omega_host); Kokkos::deep_copy(omega, omega_mirror); - const auto omega_tilde = Kokkos::View("omega_tilde"); + const auto omega_tilde = Kokkos::View("omega_tilde"); constexpr auto omega_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto omega_tilde_host = - Kokkos::View(omega_tilde_data.data()); + Kokkos::View(omega_tilde_data.data()); const auto omega_tilde_mirror = Kokkos::create_mirror(omega_tilde); Kokkos::deep_copy(omega_tilde_mirror, omega_tilde_host); Kokkos::deep_copy(omega_tilde, omega_tilde_mirror); - const auto rho = Kokkos::View("rho"); + const auto rho = Kokkos::View("rho"); constexpr auto rho_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; - const auto rho_host = Kokkos::View(rho_data.data()); + const auto rho_host = Kokkos::View(rho_data.data()); const auto rho_mirror = Kokkos::create_mirror(rho); Kokkos::deep_copy(rho_mirror, rho_host); Kokkos::deep_copy(rho, rho_mirror); - const auto eta = Kokkos::View("eta"); + const auto eta = Kokkos::View("eta"); constexpr auto eta_data = std::array{64., 65., 66.}; - const auto eta_host = Kokkos::View(eta_data.data()); + const auto eta_host = Kokkos::View(eta_data.data()); const auto eta_mirror = Kokkos::create_mirror(eta); Kokkos::deep_copy(eta_mirror, eta_host); Kokkos::deep_copy(eta, eta_mirror); - const auto Guu = Kokkos::View("Guu"); + const auto Guu = Kokkos::View("Guu"); Kokkos::parallel_for( "CalculateGyroscopicMatrix", 1, - CalculateGyroscopicMatrix{Muu, omega, omega_tilde, rho, eta, Guu} + CalculateGyroscopicMatrix{0, Muu, omega, omega_tilde, rho, eta, Guu} ); constexpr auto Guu_exact_data = @@ -59,7 +60,7 @@ TEST(CalculateGyroscopicMatrixTests, OneNode) { 0., 0., 0., 9764., -9191., 12., 0., 0., 0., 8184., 15953., 1207., 0., 0., 0., 1078., 8856., 15896., 0., 0., 0., 16487., 2497., 9546.}; const auto Guu_exact = - Kokkos::View(Guu_exact_data.data()); + Kokkos::View(Guu_exact_data.data()); const auto Guu_mirror = Kokkos::create_mirror(Guu); Kokkos::deep_copy(Guu_mirror, Guu); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_inertia_stiffness_matrix.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_inertia_stiffness_matrix.cpp index c74efb46..fd673742 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_inertia_stiffness_matrix.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_inertia_stiffness_matrix.cpp @@ -9,81 +9,83 @@ namespace openturbine::tests { TEST(CalculateInertiaStiffnessMatrixTests, OneNode) { - const auto Muu = Kokkos::View("Muu"); + const auto Muu = Kokkos::View("Muu"); constexpr auto Muu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Muu_host = Kokkos::View(Muu_data.data()); + const auto Muu_host = Kokkos::View(Muu_data.data()); const auto Muu_mirror = Kokkos::create_mirror(Muu); Kokkos::deep_copy(Muu_mirror, Muu_host); Kokkos::deep_copy(Muu, Muu_mirror); - const auto u_ddot = Kokkos::View("u_ddot"); + const auto u_ddot = Kokkos::View("u_ddot"); constexpr auto u_ddot_data = std::array{37., 38., 39.}; - const auto u_ddot_host = Kokkos::View(u_ddot_data.data()); + const auto u_ddot_host = + Kokkos::View(u_ddot_data.data()); const auto u_ddot_mirror = Kokkos::create_mirror(u_ddot); Kokkos::deep_copy(u_ddot_mirror, u_ddot_host); Kokkos::deep_copy(u_ddot, u_ddot_mirror); - const auto omega = Kokkos::View("omega"); + const auto omega = Kokkos::View("omega"); constexpr auto omega_data = std::array{40., 41., 42.}; - const auto omega_host = Kokkos::View(omega_data.data()); + const auto omega_host = + Kokkos::View(omega_data.data()); const auto omega_mirror = Kokkos::create_mirror(omega); Kokkos::deep_copy(omega_mirror, omega_host); Kokkos::deep_copy(omega, omega_mirror); - const auto omega_dot = Kokkos::View("omega_dot"); + const auto omega_dot = Kokkos::View("omega_dot"); constexpr auto omega_dot_data = std::array{43., 44., 45.}; const auto omega_dot_host = - Kokkos::View(omega_dot_data.data()); + Kokkos::View(omega_dot_data.data()); const auto omega_dot_mirror = Kokkos::create_mirror(omega_dot); Kokkos::deep_copy(omega_dot_mirror, omega_dot_host); Kokkos::deep_copy(omega_dot, omega_dot_mirror); - const auto eta_tilde = Kokkos::View("eta_tilde"); + const auto eta_tilde = Kokkos::View("eta_tilde"); constexpr auto eta_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto eta_tilde_host = - Kokkos::View(eta_tilde_data.data()); + Kokkos::View(eta_tilde_data.data()); const auto eta_tilde_mirror = Kokkos::create_mirror(eta_tilde); Kokkos::deep_copy(eta_tilde_mirror, eta_tilde_host); Kokkos::deep_copy(eta_tilde, eta_tilde_mirror); - const auto omega_tilde = Kokkos::View("omega_tilde"); + const auto omega_tilde = Kokkos::View("omega_tilde"); constexpr auto omega_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto omega_tilde_host = - Kokkos::View(omega_tilde_data.data()); + Kokkos::View(omega_tilde_data.data()); const auto omega_tilde_mirror = Kokkos::create_mirror(omega_tilde); Kokkos::deep_copy(omega_tilde_mirror, omega_tilde_host); Kokkos::deep_copy(omega_tilde, omega_tilde_mirror); - const auto omega_dot_tilde = Kokkos::View("omega_dot_tilde"); + const auto omega_dot_tilde = Kokkos::View("omega_dot_tilde"); constexpr auto omega_dot_tilde_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; const auto omega_dot_tilde_host = - Kokkos::View(omega_dot_tilde_data.data()); + Kokkos::View(omega_dot_tilde_data.data()); const auto omega_dot_tilde_mirror = Kokkos::create_mirror(omega_dot_tilde); Kokkos::deep_copy(omega_dot_tilde_mirror, omega_dot_tilde_host); Kokkos::deep_copy(omega_dot_tilde, omega_dot_tilde_mirror); - const auto rho = Kokkos::View("rho"); + const auto rho = Kokkos::View("rho"); constexpr auto rho_data = std::array{64., 65., 66., 67., 68., 69., 70., 71., 72.}; - const auto rho_host = Kokkos::View(rho_data.data()); + const auto rho_host = Kokkos::View(rho_data.data()); const auto rho_mirror = Kokkos::create_mirror(rho); Kokkos::deep_copy(rho_mirror, rho_host); Kokkos::deep_copy(rho, rho_mirror); - const auto eta = Kokkos::View("eta"); + const auto eta = Kokkos::View("eta"); constexpr auto eta_data = std::array{73., 74., 75.}; - const auto eta_host = Kokkos::View(eta_data.data()); + const auto eta_host = Kokkos::View(eta_data.data()); const auto eta_mirror = Kokkos::create_mirror(eta); Kokkos::deep_copy(eta_mirror, eta_host); Kokkos::deep_copy(eta, eta_mirror); - const auto Kuu = Kokkos::View("Kuu"); + const auto Kuu = Kokkos::View("Kuu"); Kokkos::parallel_for( "CalculateInertiaStiffnessMatrix", 1, CalculateInertiaStiffnessMatrix{ - Muu, u_ddot, omega, omega_dot, omega_tilde, omega_dot_tilde, rho, eta, Kuu} + 0, Muu, u_ddot, omega, omega_dot, omega_tilde, omega_dot_tilde, rho, eta, Kuu} ); constexpr auto Kuu_exact_data = std::array{ @@ -91,7 +93,7 @@ TEST(CalculateInertiaStiffnessMatrixTests, OneNode) { 0., 0., 0., 3822., -7644., 3822., 0., 0., 0., 1407766., 1481559., 1465326., 0., 0., 0., 1496300., 1558384., 1576048., 0., 0., 0., 1604122., 1652877., 1652190.}; const auto Kuu_exact = - Kokkos::View(Kuu_exact_data.data()); + Kokkos::View(Kuu_exact_data.data()); const auto Kuu_mirror = Kokkos::create_mirror(Kuu); Kokkos::deep_copy(Kuu_mirror, Kuu); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_inertial_forces.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_inertial_forces.cpp index e9e86f25..336f9533 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_inertial_forces.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_inertial_forces.cpp @@ -9,72 +9,74 @@ namespace openturbine::tests { TEST(CalculateInertialForcesTests, OneNode) { - const auto Muu = Kokkos::View("Muu"); + const auto Muu = Kokkos::View("Muu"); constexpr auto Muu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Muu_host = Kokkos::View(Muu_data.data()); + const auto Muu_host = Kokkos::View(Muu_data.data()); const auto Muu_mirror = Kokkos::create_mirror(Muu); Kokkos::deep_copy(Muu_mirror, Muu_host); Kokkos::deep_copy(Muu, Muu_mirror); - const auto u_ddot = Kokkos::View("u_ddot"); + const auto u_ddot = Kokkos::View("u_ddot"); constexpr auto u_ddot_data = std::array{37., 38., 39.}; - const auto u_ddot_host = Kokkos::View(u_ddot_data.data()); + const auto u_ddot_host = + Kokkos::View(u_ddot_data.data()); const auto u_ddot_mirror = Kokkos::create_mirror(u_ddot); Kokkos::deep_copy(u_ddot_mirror, u_ddot_host); Kokkos::deep_copy(u_ddot, u_ddot_mirror); - const auto omega = Kokkos::View("omega"); + const auto omega = Kokkos::View("omega"); constexpr auto omega_data = std::array{40., 41., 42.}; - const auto omega_host = Kokkos::View(omega_data.data()); + const auto omega_host = + Kokkos::View(omega_data.data()); const auto omega_mirror = Kokkos::create_mirror(omega); Kokkos::deep_copy(omega_mirror, omega_host); Kokkos::deep_copy(omega, omega_mirror); - const auto omega_dot = Kokkos::View("omega_dot"); + const auto omega_dot = Kokkos::View("omega_dot"); constexpr auto omega_dot_data = std::array{43., 44., 45.}; const auto omega_dot_host = - Kokkos::View(omega_dot_data.data()); + Kokkos::View(omega_dot_data.data()); const auto omega_dot_mirror = Kokkos::create_mirror(omega_dot); Kokkos::deep_copy(omega_dot_mirror, omega_dot_host); Kokkos::deep_copy(omega_dot, omega_dot_mirror); - const auto eta_tilde = Kokkos::View("eta_tilde"); + const auto eta_tilde = Kokkos::View("eta_tilde"); constexpr auto eta_tilde_data = std::array{46., 47., 48., 49., 50., 51., 52., 53., 54.}; const auto eta_tilde_host = - Kokkos::View(eta_tilde_data.data()); + Kokkos::View(eta_tilde_data.data()); const auto eta_tilde_mirror = Kokkos::create_mirror(eta_tilde); Kokkos::deep_copy(eta_tilde_mirror, eta_tilde_host); Kokkos::deep_copy(eta_tilde, eta_tilde_mirror); - const auto rho = Kokkos::View("rho"); + const auto rho = Kokkos::View("rho"); const auto rho_data = std::array{55., 56., 57., 58., 59., 60., 61., 62., 63.}; - const auto rho_host = Kokkos::View(rho_data.data()); + const auto rho_host = Kokkos::View(rho_data.data()); const auto rho_mirror = Kokkos::create_mirror(rho); Kokkos::deep_copy(rho_mirror, rho_host); Kokkos::deep_copy(rho, rho_mirror); - const auto eta = Kokkos::View("eta"); + const auto eta = Kokkos::View("eta"); const auto eta_data = std::array{64., 65., 66.}; - const auto eta_host = Kokkos::View(eta_data.data()); + const auto eta_host = Kokkos::View(eta_data.data()); const auto eta_mirror = Kokkos::create_mirror(eta); Kokkos::deep_copy(eta_mirror, eta_host); Kokkos::deep_copy(eta, eta_mirror); - const auto omega_tilde = Kokkos::View("omega_tilde"); - const auto omega_dot_tilde = Kokkos::View("omega_dot_tilde"); - const auto FI = Kokkos::View("FI"); + const auto omega_tilde = Kokkos::View("omega_tilde"); + const auto omega_dot_tilde = Kokkos::View("omega_dot_tilde"); + const auto FI = Kokkos::View("FI"); Kokkos::parallel_for( "CalculateInertialForces", 1, CalculateInertialForces{ - Muu, u_ddot, omega, omega_dot, eta_tilde, omega_tilde, omega_dot_tilde, rho, eta, FI} + 0, Muu, u_ddot, omega, omega_dot, eta_tilde, omega_tilde, omega_dot_tilde, rho, eta, FI} ); constexpr auto omega_tilde_exact_data = std::array{0., -42., 41., 42., 0., -40., -41., 40., 0.}; const auto omega_tilde_exact = - Kokkos::View(omega_tilde_exact_data.data()); + Kokkos::View(omega_tilde_exact_data.data()); const auto omega_tilde_mirror = Kokkos::create_mirror(omega_tilde); Kokkos::deep_copy(omega_tilde_mirror, omega_tilde); @@ -83,14 +85,15 @@ TEST(CalculateInertialForcesTests, OneNode) { constexpr auto omega_dot_tilde_exact_data = std::array{0., -45., 44., 45., 0., -43., -44., 43., 0.}; const auto omega_dot_tilde_exact = - Kokkos::View(omega_dot_tilde_exact_data.data()); + Kokkos::View(omega_dot_tilde_exact_data.data()); const auto omega_dot_tilde_mirror = Kokkos::create_mirror(omega_dot_tilde); Kokkos::deep_copy(omega_dot_tilde_mirror, omega_dot_tilde); CompareWithExpected(omega_dot_tilde_mirror, omega_dot_tilde_exact); constexpr auto FI_exact_data = std::array{-2984., 32., 2922., 20624., -2248., 22100.}; - const auto FI_exact = Kokkos::View(FI_exact_data.data()); + const auto FI_exact = + Kokkos::View(FI_exact_data.data()); const auto FI_mirror = Kokkos::create_mirror(FI); Kokkos::deep_copy(FI_mirror, FI); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_mass_matrix_components.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_mass_matrix_components.cpp index a907e1ee..c729f5db 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_mass_matrix_components.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_mass_matrix_components.cpp @@ -9,26 +9,27 @@ namespace openturbine::tests { TEST(CalculateMassMatrixComponentsTests, OneQuadPoint) { - const auto Muu = Kokkos::View("Muu"); + const auto Muu = Kokkos::View("Muu"); constexpr auto Muu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; - const auto Muu_host = Kokkos::View(Muu_data.data()); + const auto Muu_host = Kokkos::View(Muu_data.data()); const auto Muu_mirror = Kokkos::create_mirror(Muu); Kokkos::deep_copy(Muu_mirror, Muu_host); Kokkos::deep_copy(Muu, Muu_mirror); - const auto eta = Kokkos::View("eta"); - const auto rho = Kokkos::View("rho"); - const auto eta_tilde = Kokkos::View("eta_tilde"); + const auto eta = Kokkos::View("eta"); + const auto rho = Kokkos::View("rho"); + const auto eta_tilde = Kokkos::View("eta_tilde"); Kokkos::parallel_for( - "CalculateMassMatrixComponents", 1, CalculateMassMatrixComponents{Muu, eta, rho, eta_tilde} + "CalculateMassMatrixComponents", 1, + CalculateMassMatrixComponents{0, Muu, eta, rho, eta_tilde} ); constexpr auto eta_exact_data = std::array{32., -31., 25.}; const auto eta_exact = - Kokkos::View(eta_exact_data.data()); + Kokkos::View(eta_exact_data.data()); const auto eta_mirror = Kokkos::create_mirror(eta); Kokkos::deep_copy(eta_mirror, eta); @@ -36,7 +37,7 @@ TEST(CalculateMassMatrixComponentsTests, OneQuadPoint) { constexpr auto rho_exact_data = std::array{22., 23., 24., 28., 29., 30., 34., 35., 36.}; const auto rho_exact = - Kokkos::View(rho_exact_data.data()); + Kokkos::View(rho_exact_data.data()); const auto rho_mirror = Kokkos::create_mirror(rho); Kokkos::deep_copy(rho_mirror, rho); @@ -44,7 +45,7 @@ TEST(CalculateMassMatrixComponentsTests, OneQuadPoint) { constexpr auto eta_tilde_exact_data = std::array{0., -25., -31., 25., 0., -32., 31., 32., 0.}; const auto eta_tilde_exact = - Kokkos::View(eta_tilde_exact_data.data()); + Kokkos::View(eta_tilde_exact_data.data()); const auto eta_tilde_mirror = Kokkos::create_mirror(eta_tilde); Kokkos::deep_copy(eta_tilde_mirror, eta_tilde); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_node_forces.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_node_forces.cpp index 29569b5e..cec8ccdb 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_node_forces.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_node_forces.cpp @@ -48,16 +48,18 @@ TEST(CalculateNodeForcesTests, FE_OneNodeOneQP) { Kokkos::deep_copy(shape_deriv_mirror, shape_deriv_host); Kokkos::deep_copy(shape_deriv, shape_deriv_mirror); - const auto Fc = Kokkos::View("Fc"); + const auto Fc = Kokkos::View("Fc"); constexpr auto Fc_data = std::array{1., 2., 3., 4., 5., 6.}; - const auto Fc_host = Kokkos::View(Fc_data.data()); + const auto Fc_host = + Kokkos::View(Fc_data.data()); const auto Fc_mirror = Kokkos::create_mirror(Fc); Kokkos::deep_copy(Fc_mirror, Fc_host); Kokkos::deep_copy(Fc, Fc_mirror); - const auto Fd = Kokkos::View("Fd"); + const auto Fd = Kokkos::View("Fd"); constexpr auto Fd_data = std::array{7., 8., 9., 10., 11., 12.}; - const auto Fd_host = Kokkos::View(Fd_data.data()); + const auto Fd_host = + Kokkos::View(Fd_data.data()); const auto Fd_mirror = Kokkos::create_mirror(Fd); Kokkos::deep_copy(Fd_mirror, Fd_host); Kokkos::deep_copy(Fd, Fd_mirror); @@ -120,16 +122,18 @@ TEST(CalculateNodeForcesTests, FE_TwoNodesTwoQPs) { Kokkos::deep_copy(shape_deriv_mirror, shape_deriv_host); Kokkos::deep_copy(shape_deriv, shape_deriv_mirror); - const auto Fc = Kokkos::View("Fc"); + const auto Fc = Kokkos::View("Fc"); constexpr auto Fc_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12.}; - const auto Fc_host = Kokkos::View(Fc_data.data()); + const auto Fc_host = + Kokkos::View(Fc_data.data()); const auto Fc_mirror = Kokkos::create_mirror(Fc); Kokkos::deep_copy(Fc_mirror, Fc_host); Kokkos::deep_copy(Fc, Fc_mirror); - const auto Fd = Kokkos::View("Fd"); + const auto Fd = Kokkos::View("Fd"); constexpr auto Fd_data = std::array{13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24.}; - const auto Fd_host = Kokkos::View(Fd_data.data()); + const auto Fd_host = + Kokkos::View(Fd_data.data()); const auto Fd_mirror = Kokkos::create_mirror(Fd); Kokkos::deep_copy(Fd_mirror, Fd_host); Kokkos::deep_copy(Fd, Fd_mirror); @@ -193,9 +197,10 @@ TEST(CalculateNodeForcesTests, FI_FG_OneNodeOneQP) { Kokkos::deep_copy(shape_deriv_mirror, shape_deriv_host); Kokkos::deep_copy(shape_deriv, shape_deriv_mirror); - const auto Fig = Kokkos::View("Fig"); + const auto Fig = Kokkos::View("Fig"); constexpr auto Fig_data = std::array{1., 2., 3., 4., 5., 6.}; - const auto Fig_host = Kokkos::View(Fig_data.data()); + const auto Fig_host = + Kokkos::View(Fig_data.data()); const auto Fig_mirror = Kokkos::create_mirror(Fig); Kokkos::deep_copy(Fig_mirror, Fig_host); Kokkos::deep_copy(Fig, Fig_mirror); @@ -257,9 +262,10 @@ TEST(CalculateNodeForcesTests, FI_FG_TwoNodesTwoQP) { Kokkos::deep_copy(shape_deriv_mirror, shape_deriv_host); Kokkos::deep_copy(shape_deriv, shape_deriv_mirror); - const auto Fig = Kokkos::View("Fig"); + const auto Fig = Kokkos::View("Fig"); constexpr auto Fig_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12.}; - const auto Fig_host = Kokkos::View(Fig_data.data()); + const auto Fig_host = + Kokkos::View(Fig_data.data()); const auto Fig_mirror = Kokkos::create_mirror(Fig); Kokkos::deep_copy(Fig_mirror, Fig_host); Kokkos::deep_copy(Fig, Fig_mirror); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_strain.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_strain.cpp index c0a73938..45694ae4 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_strain.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_strain.cpp @@ -9,46 +9,46 @@ namespace openturbine::tests { TEST(CalculateStrainTests, OneNode) { - const auto x0_prime = Kokkos::View("x0_prime"); + const auto x0_prime = Kokkos::View("x0_prime"); constexpr auto x0_prime_data = std::array{1., 2., 3.}; const auto x0_prime_host = - Kokkos::View(x0_prime_data.data()); + Kokkos::View(x0_prime_data.data()); const auto x0_prime_mirror = Kokkos::create_mirror(x0_prime); Kokkos::deep_copy(x0_prime_mirror, x0_prime_host); Kokkos::deep_copy(x0_prime, x0_prime_mirror); - const auto u_prime = Kokkos::View("u_prime"); + const auto u_prime = Kokkos::View("u_prime"); constexpr auto u_prime_data = std::array{4., 5., 6.}; const auto u_prime_host = - Kokkos::View(u_prime_data.data()); + Kokkos::View(u_prime_data.data()); const auto u_prime_mirror = Kokkos::create_mirror(u_prime); Kokkos::deep_copy(u_prime_mirror, u_prime_host); Kokkos::deep_copy(u_prime, u_prime_mirror); - const auto r = Kokkos::View("r"); + const auto r = Kokkos::View("r"); constexpr auto r_data = std::array{7., 8., 9., 10.}; - const auto r_host = Kokkos::View(r_data.data()); + const auto r_host = Kokkos::View(r_data.data()); const auto r_mirror = Kokkos::create_mirror(r); Kokkos::deep_copy(r_mirror, r_host); Kokkos::deep_copy(r, r_mirror); - const auto r_prime = Kokkos::View("r_prime"); + const auto r_prime = Kokkos::View("r_prime"); constexpr auto r_prime_data = std::array{11., 12., 13., 14.}; const auto r_prime_host = - Kokkos::View(r_prime_data.data()); + Kokkos::View(r_prime_data.data()); const auto r_prime_mirror = Kokkos::create_mirror(r_prime); Kokkos::deep_copy(r_prime_mirror, r_prime_host); Kokkos::deep_copy(r_prime, r_prime_mirror); - const auto strain = Kokkos::View("strain"); + const auto strain = Kokkos::View("strain"); Kokkos::parallel_for( - "CalculateStrain", 1, CalculateStrain{x0_prime, u_prime, r, r_prime, strain} + "CalculateStrain", 1, CalculateStrain{0, x0_prime, u_prime, r, r_prime, strain} ); constexpr auto strain_exact_data = std::array{-793., -413., -621., -16., 0., -32.}; const auto strain_exact = - Kokkos::View(strain_exact_data.data()); + Kokkos::View(strain_exact_data.data()); const auto strain_mirror = Kokkos::create_mirror(strain); Kokkos::deep_copy(strain_mirror, strain); diff --git a/tests/unit_tests/restruct_poc/system/test_calculate_temporary_variables.cpp b/tests/unit_tests/restruct_poc/system/test_calculate_temporary_variables.cpp index fb75f7d2..224d722e 100644 --- a/tests/unit_tests/restruct_poc/system/test_calculate_temporary_variables.cpp +++ b/tests/unit_tests/restruct_poc/system/test_calculate_temporary_variables.cpp @@ -9,31 +9,31 @@ namespace openturbine::tests { TEST(CalculateTemporaryVariablesTests, OneNode) { - const auto x0_prime = Kokkos::View("x0_prime"); + const auto x0_prime = Kokkos::View("x0_prime"); constexpr auto x0_prime_data = std::array{1., 2., 3.}; const auto x0_prime_host = - Kokkos::View(x0_prime_data.data()); + Kokkos::View(x0_prime_data.data()); const auto x0_prime_mirror = Kokkos::create_mirror(x0_prime); Kokkos::deep_copy(x0_prime_mirror, x0_prime_host); Kokkos::deep_copy(x0_prime, x0_prime_mirror); - const auto u_prime = Kokkos::View("u_prime"); + const auto u_prime = Kokkos::View("u_prime"); constexpr auto u_prime_data = std::array{4., 5., 6.}; const auto u_prime_host = - Kokkos::View(u_prime_data.data()); + Kokkos::View(u_prime_data.data()); const auto u_prime_mirror = Kokkos::create_mirror(u_prime); Kokkos::deep_copy(u_prime_mirror, u_prime_host); Kokkos::deep_copy(u_prime, u_prime_mirror); - const auto x0pupSS = Kokkos::View("x0pupSS"); + const auto x0pupSS = Kokkos::View("x0pupSS"); Kokkos::parallel_for( - "CalculateTemporaryVariables", 1, CalculateTemporaryVariables{x0_prime, u_prime, x0pupSS} + "CalculateTemporaryVariables", 1, CalculateTemporaryVariables{0, x0_prime, u_prime, x0pupSS} ); constexpr auto x0pupSS_exact_data = std::array{0., -9., 7., 9., 0., -5., -7., 5., 0.}; const auto x0pupSS_exact = - Kokkos::View(x0pupSS_exact_data.data()); + Kokkos::View(x0pupSS_exact_data.data()); const auto x0pupSS_mirror = Kokkos::create_mirror(x0pupSS); Kokkos::deep_copy(x0pupSS_mirror, x0pupSS); diff --git a/tests/unit_tests/restruct_poc/system/test_integrate_inertia_matrix.cpp b/tests/unit_tests/restruct_poc/system/test_integrate_inertia_matrix.cpp index d155d8a7..a60e867d 100644 --- a/tests/unit_tests/restruct_poc/system/test_integrate_inertia_matrix.cpp +++ b/tests/unit_tests/restruct_poc/system/test_integrate_inertia_matrix.cpp @@ -12,26 +12,22 @@ namespace openturbine::tests { inline void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Muu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({2.}); - const auto qp_jacobian = get_qp_jacobian({3.}); - const auto shape_interp = - get_shape_interp({5.}); - const auto qp_Muu = get_qp_Muu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); - const auto qp_Guu = get_qp_Guu( - {1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006., - 6001., 6002., 6003., 6004., 6005., 6006., 7001., 7002., 7003., 7004., 7005., 7006.} - ); + const auto qp_weights = get_qp_weights({2.}); + const auto qp_jacobian = get_qp_jacobian({3.}); + const auto shape_interp = get_shape_interp({5.}); + const auto qp_Muu = + get_qp_Muu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); + const auto qp_Guu = + get_qp_Guu({1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., + 2004., 2005., 2006., 4001., 4002., 4003., 4004., 4005., 4006., + 5001., 5002., 5003., 5004., 5005., 5006., 6001., 6002., 6003., + 6004., 6005., 6006., 7001., 7002., 7003., 7004., 7005., 7006.}); const auto gbl_M = Kokkos::View("global_M"); @@ -58,27 +54,22 @@ TEST(IntegrateInertiaMatrixTests, OneElementOneNodeOneQP_Muu) { } void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Guu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto node_state_indices = get_node_state_indices(); - const auto qp_weights = get_qp_weights({2.}); - const auto qp_jacobian = get_qp_jacobian({3.}); - const auto shape_interp = - get_shape_interp({5.}); - const auto qp_Muu = get_qp_Muu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); - const auto qp_Guu = get_qp_Guu( - {1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., - 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., 4004., 4005., 4006., - 5001., 5002., 5003., 5004., 5005., 5006., 6001., 6002., 6003., 6004., 6005., 6006.} - ); + const auto qp_weights = get_qp_weights({2.}); + const auto qp_jacobian = get_qp_jacobian({3.}); + const auto shape_interp = get_shape_interp({5.}); + const auto qp_Muu = + get_qp_Muu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); + const auto qp_Guu = + get_qp_Guu({1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., + 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., + 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., + 5004., 5005., 5006., 6001., 6002., 6003., 6004., 6005., 6006.}); const auto gbl_M = Kokkos::View("global_M"); @@ -105,32 +96,24 @@ TEST(IntegrateInertiaMatrixTests, OneElementOneNodeOneQP_Guu) { } void IntegrateInertiaMatrix_TestTwoElementsOneNodeOneQP() { - constexpr auto number_of_elements = 2; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1., 1.}); - const auto qp_jacobian = get_qp_jacobian({1., 1.}); - const auto shape_interp = - get_shape_interp({1., 1.}); - using QpMatrixView = Kokkos::View; - const auto qp_Muu = get_qp_Muu( - {00001., 00002., 00003., 00004., 00005., 00006., 00101., 00102., 00103., - 00104., 00105., 00106., 00201., 00202., 00203., 00204., 00205., 00206., - 00301., 00302., 00303., 00304., 00305., 00306., 00401., 00402., 00403., - 00404., 00405., 00406., 00501., 00502., 00503., 00504., 00505., 00506., - - 00001., 00002., 00003., 00004., 00005., 00006., 10001., 10002., 10003., - 10004., 10005., 10006., 20001., 20002., 20003., 20004., 20005., 20006., - 30001., 30002., 30003., 30004., 30005., 30006., 40001., 40002., 40003., - 40004., 40005., 40006., 50001., 50002., 50003., 50004., 50005., 50006.} - ); + const auto qp_weights = get_qp_weights({1.}); + const auto qp_jacobian = get_qp_jacobian({1.}); + const auto shape_interp = get_shape_interp({1.}); + using QpMatrixView = Kokkos::View; + const auto qp_Guu = QpMatrixView("Guu"); const auto gbl_M = Kokkos::View("global_M"); { + const auto qp_Muu = get_qp_Muu( + {00001., 00002., 00003., 00004., 00005., 00006., 00101., 00102., 00103., + 00104., 00105., 00106., 00201., 00202., 00203., 00204., 00205., 00206., + 00301., 00302., 00303., 00304., 00305., 00306., 00401., 00402., 00403., + 00404., 00405., 00406., 00501., 00502., 00503., 00504., 00505., 00506.} + ); const auto policy = Kokkos::MDRangePolicy({0, 0}, {number_of_nodes, number_of_nodes}); const auto integrator = IntegrateInertiaMatrixElement{ 0, number_of_qps, 0, 0, qp_weights, qp_jacobian, shape_interp, @@ -139,6 +122,12 @@ void IntegrateInertiaMatrix_TestTwoElementsOneNodeOneQP() { } { + const auto qp_Muu = get_qp_Muu( + {00001., 00002., 00003., 00004., 00005., 00006., 10001., 10002., 10003., + 10004., 10005., 10006., 20001., 20002., 20003., 20004., 20005., 20006., + 30001., 30002., 30003., 30004., 30005., 30006., 40001., 40002., 40003., + 40004., 40005., 40006., 50001., 50002., 50003., 50004., 50005., 50006.} + ); const auto policy = Kokkos::MDRangePolicy({0, 0}, {number_of_nodes, number_of_nodes}); const auto integrator = IntegrateInertiaMatrixElement{ 1, number_of_qps, 1, 1, qp_weights, qp_jacobian, shape_interp, @@ -168,22 +157,18 @@ TEST(IntegrateInertiaMatrixTests, TwoElementsOneNodeOneQP) { } void IntegrateInertiaMatrix_TestOneElementTwoNodesOneQP() { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 2; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1.}); - const auto qp_jacobian = get_qp_jacobian({1.}); - const auto shape_interp = - get_shape_interp({1., 2.}); - using QpMatrixView = Kokkos::View; - const auto qp_Muu = get_qp_Muu( - {0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., 0104., 0105., 0106., - 0201., 0202., 0203., 0204., 0205., 0206., 0301., 0302., 0303., 0304., 0305., 0306., - 0401., 0402., 0403., 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.} - ); + const auto qp_weights = get_qp_weights({1.}); + const auto qp_jacobian = get_qp_jacobian({1.}); + const auto shape_interp = get_shape_interp({1., 2.}); + using QpMatrixView = Kokkos::View; + const auto qp_Muu = + get_qp_Muu({0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., + 0104., 0105., 0106., 0201., 0202., 0203., 0204., 0205., 0206., + 0301., 0302., 0303., 0304., 0305., 0306., 0401., 0402., 0403., + 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); const auto qp_Guu = QpMatrixView("Guu"); const auto gbl_M = Kokkos::View("global_M"); @@ -221,18 +206,14 @@ TEST(IntegrateInertiaMatrixTests, OneElementTwoNodesOneQP) { } void IntegrateInertiaMatrix_TestOneElementOneNodeTwoQPs() { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 2; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({9., 1.}); - const auto qp_jacobian = get_qp_jacobian({1., 4.}); - const auto shape_interp = - get_shape_interp({1. / 3., 1. / 2.}); - using QpMatrixView = Kokkos::View; - const auto qp_Muu = get_qp_Muu( + const auto qp_weights = get_qp_weights({9., 1.}); + const auto qp_jacobian = get_qp_jacobian({1., 4.}); + const auto shape_interp = get_shape_interp({1. / 3., 1. / 2.}); + using QpMatrixView = Kokkos::View; + const auto qp_Muu = get_qp_Muu( {00001., 00002., 00003., 00004., 00005., 00006., 00011., 00012., 00013., 00014., 00015., 00016., 00021., 00022., 00023., 00024., 00025., 00026., 00031., 00032., 00033., 00034., 00035., 00036., 00041., 00042., 00043., @@ -270,22 +251,18 @@ TEST(IntegrateInertiaMatrixTests, OneElementOneNodeTwoQPs) { } void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_WithMultiplicationFactor() { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1.}); - const auto qp_jacobian = get_qp_jacobian({1.}); - const auto shape_interp = - get_shape_interp({1.}); - using QpMatrixView = Kokkos::View; - const auto qp_Muu = get_qp_Muu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); + const auto qp_weights = get_qp_weights({1.}); + const auto qp_jacobian = get_qp_jacobian({1.}); + const auto shape_interp = get_shape_interp({1.}); + using QpMatrixView = Kokkos::View; + const auto qp_Muu = + get_qp_Muu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); const auto qp_Guu = QpMatrixView("Guu"); const auto multiplication_factor = 5.; diff --git a/tests/unit_tests/restruct_poc/system/test_integrate_matrix.hpp b/tests/unit_tests/restruct_poc/system/test_integrate_matrix.hpp index ab0240db..a18d07ab 100644 --- a/tests/unit_tests/restruct_poc/system/test_integrate_matrix.hpp +++ b/tests/unit_tests/restruct_poc/system/test_integrate_matrix.hpp @@ -7,17 +7,17 @@ namespace openturbine::tests { -template -auto get_element_indices() { - using IndicesView = Kokkos::View; - auto elem_indices = IndicesView("elem_indices"); - const auto host_elem_indices = Kokkos::create_mirror(elem_indices); - for (auto i = 0U; i < n_elem; ++i) { - host_elem_indices(i) = Beams::ElemIndices(n_nodes, n_qps, i, i); - } - Kokkos::deep_copy(elem_indices, host_elem_indices); - return elem_indices; -} +// template +// auto get_element_indices() { +// using IndicesView = Kokkos::View; +// auto elem_indices = IndicesView("elem_indices"); +// const auto host_elem_indices = Kokkos::create_mirror(elem_indices); +// for (auto i = 0U; i < n_elem; ++i) { +// host_elem_indices(i) = Beams::ElemIndices(n_nodes, n_qps, i, i); +// } +// Kokkos::deep_copy(elem_indices, host_elem_indices); +// return elem_indices; +// } template auto get_node_state_indices() { @@ -31,10 +31,10 @@ auto get_node_state_indices() { return indices; } -template -auto get_qp_vector(std::string_view name, const std::array& vector_data) { - using VectorView = Kokkos::View; - using HostVectorView = Kokkos::View; +template +auto get_qp_vector(std::string_view name, const std::array& vector_data) { + using VectorView = Kokkos::View; + using HostVectorView = Kokkos::View; auto vector = VectorView(std::string{name}); const auto host_vector = Kokkos::create_mirror(vector); const auto vector_data_view = HostVectorView(vector_data.data()); @@ -43,22 +43,20 @@ auto get_qp_vector(std::string_view name, const std::array -auto get_qp_weights(const std::array& weight_data) { - return get_qp_vector("weights", weight_data); +template +auto get_qp_weights(const std::array& weight_data) { + return get_qp_vector("weights", weight_data); } -template -auto get_qp_jacobian(const std::array& jacobian_data) { - return get_qp_vector("jacobian", jacobian_data); +template +auto get_qp_jacobian(const std::array& jacobian_data) { + return get_qp_vector("jacobian", jacobian_data); } -template -auto get_shape_matrix( - std::string_view name, const std::array& shape_data -) { - using ShapeView = Kokkos::View; - using HostShapeView = Kokkos::View; +template +auto get_shape_matrix(std::string_view name, const std::array& shape_data) { + using ShapeView = Kokkos::View; + using HostShapeView = Kokkos::View; auto shape = ShapeView(std::string{name}); const auto host_shape = Kokkos::create_mirror(shape); const auto shape_data_view = HostShapeView(shape_data.data()); @@ -67,22 +65,20 @@ auto get_shape_matrix( return shape; } -template -auto get_shape_interp(const std::array& shape_data) { - return get_shape_matrix("shape_interp", shape_data); +template +auto get_shape_interp(const std::array& shape_data) { + return get_shape_matrix("shape_interp", shape_data); } -template -auto get_shape_interp_deriv(const std::array& shape_data) { - return get_shape_matrix("shape_interp_deriv", shape_data); +template +auto get_shape_interp_deriv(const std::array& shape_data) { + return get_shape_matrix("shape_interp_deriv", shape_data); } -template -auto get_qp_matrix( - std::string_view name, const std::array& matrix_data -) { - using MatrixView = Kokkos::View; - using HostMatrixView = Kokkos::View; +template +auto get_qp_matrix(std::string_view name, const std::array& matrix_data) { + using MatrixView = Kokkos::View; + using HostMatrixView = Kokkos::View; auto matrix = MatrixView(std::string{name}); const auto host_matrix = Kokkos::create_mirror(matrix); const auto matrix_data_view = HostMatrixView(matrix_data.data()); @@ -91,44 +87,44 @@ auto get_qp_matrix( return matrix; } -template -auto get_qp_M(const std::array& M_data) { - return get_qp_matrix("M", M_data); +template +auto get_qp_M(const std::array& M_data) { + return get_qp_matrix("M", M_data); } -template -auto get_qp_Muu(const std::array& M_data) { - return get_qp_matrix("Muu", M_data); +template +auto get_qp_Muu(const std::array& M_data) { + return get_qp_matrix("Muu", M_data); } -template -auto get_qp_Guu(const std::array& M_data) { - return get_qp_matrix("Guu", M_data); +template +auto get_qp_Guu(const std::array& M_data) { + return get_qp_matrix("Guu", M_data); } -template -auto get_qp_Kuu(const std::array& Puu_data) { - return get_qp_matrix("Kuu", Puu_data); +template +auto get_qp_Kuu(const std::array& Puu_data) { + return get_qp_matrix("Kuu", Puu_data); } -template -auto get_qp_Puu(const std::array& Puu_data) { - return get_qp_matrix("Puu", Puu_data); +template +auto get_qp_Puu(const std::array& Puu_data) { + return get_qp_matrix("Puu", Puu_data); } -template -auto get_qp_Quu(const std::array& Quu_data) { - return get_qp_matrix("Quu", Quu_data); +template +auto get_qp_Quu(const std::array& Quu_data) { + return get_qp_matrix("Quu", Quu_data); } -template -auto get_qp_Cuu(const std::array& Cuu_data) { - return get_qp_matrix("Cuu", Cuu_data); +template +auto get_qp_Cuu(const std::array& Cuu_data) { + return get_qp_matrix("Cuu", Cuu_data); } -template -auto get_qp_Ouu(const std::array& Ouu_data) { - return get_qp_matrix("Ouu", Ouu_data); +template +auto get_qp_Ouu(const std::array& Ouu_data) { + return get_qp_matrix("Ouu", Ouu_data); } } // namespace openturbine::tests \ No newline at end of file diff --git a/tests/unit_tests/restruct_poc/system/test_integrate_stiffness_matrix.cpp b/tests/unit_tests/restruct_poc/system/test_integrate_stiffness_matrix.cpp index b87ec1e8..384f379c 100644 --- a/tests/unit_tests/restruct_poc/system/test_integrate_stiffness_matrix.cpp +++ b/tests/unit_tests/restruct_poc/system/test_integrate_stiffness_matrix.cpp @@ -18,16 +18,13 @@ void TestIntegrateStiffnessMatrix_1Element1Node1QP( const Kokkos::View& qp_Ouu, const Kokkos::View& qp_Quu, const std::array& exact_M_data ) { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto qp_weights = get_qp_weights({2.}); - const auto qp_jacobian = get_qp_jacobian({3.}); - const auto shape_interp = - get_shape_interp({4.}); - const auto shape_interp_deriv = - get_shape_interp_deriv({5.}); + const auto qp_weights = get_qp_weights({2.}); + const auto qp_jacobian = get_qp_jacobian({3.}); + const auto shape_interp = get_shape_interp({4.}); + const auto shape_interp_deriv = get_shape_interp_deriv({5.}); auto gbl_M = Kokkos::View("global_M"); @@ -56,15 +53,14 @@ void TestIntegrateStiffnessMatrix_1Element1Node1QP( } void TestIntegrateStiffnessMatrix_1Element1Node1QP_Kuu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; - const auto qp_Kuu = get_qp_Kuu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); + using QpMatrixView = Kokkos::View; + const auto qp_Kuu = + get_qp_Kuu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); const auto qp_Puu = QpMatrixView("Puu"); const auto qp_Quu = QpMatrixView("Quu"); const auto qp_Cuu = QpMatrixView("Cuu"); @@ -86,16 +82,15 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Kuu) { } void TestIntegrateStiffnessMatrix_1Element1Node1QP_Puu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); - const auto qp_Puu = get_qp_Puu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); + const auto qp_Puu = + get_qp_Puu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); const auto qp_Cuu = QpMatrixView("Cuu"); const auto qp_Ouu = QpMatrixView("Ouu"); const auto qp_Quu = QpMatrixView("Quu"); @@ -116,17 +111,16 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Puu) { } void TestIntegrateStiffnessMatrix_1Element1Node1QP_Quu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); - const auto qp_Quu = get_qp_Quu( - {0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., 1004., 1005., 1006., - 2001., 2002., 2003., 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., - 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.} - ); + const auto qp_Quu = + get_qp_Quu({0001., 0002., 0003., 0004., 0005., 0006., 1001., 1002., 1003., + 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., + 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., + 4004., 4005., 4006., 5001., 5002., 5003., 5004., 5005., 5006.}); const auto qp_Cuu = QpMatrixView("Cuu"); const auto qp_Ouu = QpMatrixView("Ouu"); @@ -146,19 +140,18 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Quu) { } void TestIntegrateStiffnessMatrix_1Element1Node1QP_Cuu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); const auto qp_Quu = QpMatrixView("Quu"); - const auto qp_Cuu = get_qp_Cuu( - {03003., 03006., 03009., 03012., 03015., 03018., 06003., 06006., 06009., - 06012., 06015., 06018., 09003., 09006., 09009., 09012., 09015., 09018., - 12003., 12006., 12009., 12012., 12015., 12018., 15003., 15006., 15009., - 15012., 15015., 15018., 18003., 18006., 18009., 18012., 18015., 18018.} - ); + const auto qp_Cuu = + get_qp_Cuu({03003., 03006., 03009., 03012., 03015., 03018., 06003., 06006., + 06009., 06012., 06015., 06018., 09003., 09006., 09009., 09012., + 09015., 09018., 12003., 12006., 12009., 12012., 12015., 12018., + 15003., 15006., 15009., 15012., 15015., 15018., 18003., 18006., + 18009., 18012., 18015., 18018.}); const auto qp_Ouu = QpMatrixView("Ouu"); constexpr auto exact_M_data = @@ -177,19 +170,18 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Cuu) { } void TestIntegrateStiffnessMatrix_1Element1Node1QP_Ouu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); const auto qp_Quu = QpMatrixView("Quu"); const auto qp_Cuu = QpMatrixView("Cuu"); - const auto qp_Ouu = get_qp_Ouu( - {1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., 2004., 2005., 2006., - 3001., 3002., 3003., 3004., 3005., 3006., 4001., 4002., 4003., 4004., 4005., 4006., - 5001., 5002., 5003., 5004., 5005., 5006., 6001., 6002., 6003., 6004., 6005., 6006.} - ); + const auto qp_Ouu = + get_qp_Ouu({1001., 1002., 1003., 1004., 1005., 1006., 2001., 2002., 2003., + 2004., 2005., 2006., 3001., 3002., 3003., 3004., 3005., 3006., + 4001., 4002., 4003., 4004., 4005., 4006., 5001., 5002., 5003., + 5004., 5005., 5006., 6001., 6002., 6003., 6004., 6005., 6006.}); constexpr auto exact_M_data = std::array{040040., 040080., 040120., 040160., 040200., 040240., 080040., 080080., 080120., @@ -207,32 +199,15 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Ouu) { } void TestIntegrateStiffnessMatrix_2Elements1Node1QP() { - constexpr auto number_of_elements = 2; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1., 1.}); - const auto qp_jacobian = get_qp_jacobian({1., 1.}); - const auto shape_interp = - get_shape_interp({1., 1.}); - const auto shape_interp_deriv = - get_shape_interp_deriv({1., 1.}); - - const auto qp_Puu = get_qp_Puu( - {00001., 00002., 00003., 00004., 00005., 00006., 00101., 00102., 00103., - 00104., 00105., 00106., 00201., 00202., 00203., 00204., 00205., 00206., - 00301., 00302., 00303., 00304., 00305., 00306., 00401., 00402., 00403., - 00404., 00405., 00406., 00501., 00502., 00503., 00504., 00505., 00506., - - 00001., 00002., 00003., 00004., 00005., 00006., 10001., 10002., 10003., - 10004., 10005., 10006., 20001., 20002., 20003., 20004., 20005., 20006., - 30001., 30002., 30003., 30004., 30005., 30006., 40001., 40002., 40003., - 40004., 40005., 40006., 50001., 50002., 50003., 50004., 50005., 50006.} - ); + const auto qp_weights = get_qp_weights({1.}); + const auto qp_jacobian = get_qp_jacobian({1.}); + const auto shape_interp = get_shape_interp({1.}); + const auto shape_interp_deriv = get_shape_interp_deriv({1.}); - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Quu = QpMatrixView("Quu"); const auto qp_Cuu = QpMatrixView("Cuu"); @@ -241,6 +216,12 @@ void TestIntegrateStiffnessMatrix_2Elements1Node1QP() { auto gbl_M = Kokkos::View("global_M"); { + const auto qp_Puu = get_qp_Puu( + {00001., 00002., 00003., 00004., 00005., 00006., 00101., 00102., 00103., + 00104., 00105., 00106., 00201., 00202., 00203., 00204., 00205., 00206., + 00301., 00302., 00303., 00304., 00305., 00306., 00401., 00402., 00403., + 00404., 00405., 00406., 00501., 00502., 00503., 00504., 00505., 00506.} + ); const auto policy = Kokkos::MDRangePolicy({0, 0}, {number_of_nodes, number_of_nodes}); const auto integrator = IntegrateStiffnessMatrixElement{0, number_of_qps, @@ -260,6 +241,12 @@ void TestIntegrateStiffnessMatrix_2Elements1Node1QP() { } { + const auto qp_Puu = get_qp_Puu( + {00001., 00002., 00003., 00004., 00005., 00006., 10001., 10002., 10003., + 10004., 10005., 10006., 20001., 20002., 20003., 20004., 20005., 20006., + 30001., 30002., 30003., 30004., 30005., 30006., 40001., 40002., 40003., + 40004., 40005., 40006., 50001., 50002., 50003., 50004., 50005., 50006.} + ); const auto policy = Kokkos::MDRangePolicy({0, 0}, {number_of_nodes, number_of_nodes}); const auto integrator = IntegrateStiffnessMatrixElement{1, number_of_qps, @@ -307,18 +294,13 @@ void TestIntegrateStiffnessMatrix_1Element2Nodes1QP( const Kokkos::View& qp_Ouu, const Kokkos::View& qp_Quu, const std::array& exact_M_data ) { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 2; constexpr auto number_of_qps = 1; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1.}); - const auto qp_jacobian = get_qp_jacobian({1.}); - const auto shape_interp = - get_shape_interp({1., 2.}); - const auto shape_interp_deriv = - get_shape_interp_deriv({1., 4.}); + const auto qp_weights = get_qp_weights({1.}); + const auto qp_jacobian = get_qp_jacobian({1.}); + const auto shape_interp = get_shape_interp({1., 2.}); + const auto shape_interp_deriv = get_shape_interp_deriv({1., 4.}); auto gbl_M = Kokkos::View("global_M"); @@ -348,15 +330,14 @@ void TestIntegrateStiffnessMatrix_1Element2Nodes1QP( } void TestIntegrateStiffnessMatrix_1Element2Nodes1QP_Puu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; - const auto qp_Puu = get_qp_Puu( - {0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., 0104., 0105., 0106., - 0201., 0202., 0203., 0204., 0205., 0206., 0301., 0302., 0303., 0304., 0305., 0306., - 0401., 0402., 0403., 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.} - ); + using QpMatrixView = Kokkos::View; + const auto qp_Puu = + get_qp_Puu({0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., + 0104., 0105., 0106., 0201., 0202., 0203., 0204., 0205., 0206., + 0301., 0302., 0303., 0304., 0305., 0306., 0401., 0402., 0403., + 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Quu = QpMatrixView("Quu"); const auto qp_Cuu = QpMatrixView("Cuu"); @@ -389,17 +370,16 @@ TEST(IntegrateStiffnessMatrixTests, OneElementTwoNodesOneQP_Puu) { } void TestIntegrateStiffnessMatrix_1Element2Nodes1QP_Quu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); - const auto qp_Quu = get_qp_Quu( - {0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., 0104., 0105., 0106., - 0201., 0202., 0203., 0204., 0205., 0206., 0301., 0302., 0303., 0304., 0305., 0306., - 0401., 0402., 0403., 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.} - ); + const auto qp_Quu = + get_qp_Quu({0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., + 0104., 0105., 0106., 0201., 0202., 0203., 0204., 0205., 0206., + 0301., 0302., 0303., 0304., 0305., 0306., 0401., 0402., 0403., + 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); const auto qp_Cuu = QpMatrixView("Cuu"); const auto qp_Ouu = QpMatrixView("Ouu"); @@ -430,18 +410,17 @@ TEST(IntegrateStiffnessMatrixTests, OneElementTwoNodesOneQP_Quu) { } void TestIntegrateStiffnessMatrix_1Element2Nodes1QP_Cuu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); const auto qp_Quu = QpMatrixView("Quu"); - const auto qp_Cuu = get_qp_Cuu( - {0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., 0104., 0105., 0106., - 0201., 0202., 0203., 0204., 0205., 0206., 0301., 0302., 0303., 0304., 0305., 0306., - 0401., 0402., 0403., 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.} - ); + const auto qp_Cuu = + get_qp_Cuu({0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., + 0104., 0105., 0106., 0201., 0202., 0203., 0204., 0205., 0206., + 0301., 0302., 0303., 0304., 0305., 0306., 0401., 0402., 0403., + 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); const auto qp_Ouu = QpMatrixView("Ouu"); constexpr auto exact_M_data = std::array{ @@ -471,19 +450,18 @@ TEST(IntegrateStiffnessMatrixTests, OneElementTwoNodesOneQP_Cuu) { } void TestIntegrateStiffnessMatrix_1Element2Nodes1QP_Ouu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 1; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Puu"); const auto qp_Quu = QpMatrixView("Quu"); const auto qp_Cuu = QpMatrixView("Cuu"); - const auto qp_Ouu = get_qp_Ouu( - {0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., 0104., 0105., 0106., - 0201., 0202., 0203., 0204., 0205., 0206., 0301., 0302., 0303., 0304., 0305., 0306., - 0401., 0402., 0403., 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.} - ); + const auto qp_Ouu = + get_qp_Ouu({0001., 0002., 0003., 0004., 0005., 0006., 0101., 0102., 0103., + 0104., 0105., 0106., 0201., 0202., 0203., 0204., 0205., 0206., + 0301., 0302., 0303., 0304., 0305., 0306., 0401., 0402., 0403., + 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); constexpr auto exact_M_data = std::array{ 00001., 00002., 00003., 00004., 00005., 00006., 00002., 00004., 00006., 00008., 00010., @@ -518,18 +496,13 @@ void TestIntegrateStiffnessMatrix_1Element1Node2QPs( const Kokkos::View& qp_Ouu, const Kokkos::View& qp_Quu, const std::array& exact_M_data ) { - constexpr auto number_of_elements = 1; constexpr auto number_of_nodes = 1; constexpr auto number_of_qps = 2; - const auto element_indices = - get_element_indices(); - const auto qp_weights = get_qp_weights({1., 3.}); - const auto qp_jacobian = get_qp_jacobian({2., 4.}); - const auto shape_interp = - get_shape_interp({1., 1.}); - const auto shape_interp_deriv = - get_shape_interp_deriv({1., 1.}); + const auto qp_weights = get_qp_weights({1., 3.}); + const auto qp_jacobian = get_qp_jacobian({2., 4.}); + const auto shape_interp = get_shape_interp({1., 1.}); + const auto shape_interp_deriv = get_shape_interp_deriv({1., 1.}); auto gbl_M = Kokkos::View("global_M"); @@ -558,11 +531,10 @@ void TestIntegrateStiffnessMatrix_1Element1Node2QPs( } void TestIntegrateStiffnessMatrix_1Element1Node2QPs_Puu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 2; - using QpMatrixView = Kokkos::View; - const auto qp_Puu = get_qp_Puu( + using QpMatrixView = Kokkos::View; + const auto qp_Puu = get_qp_Puu( {10001., 10002., 10003., 10004., 10005., 10006., 10101., 10102., 10103., 10104., 10105., 10106., 10201., 10202., 10203., 10204., 10205., 10206., 10301., 10302., 10303., 10304., 10305., 10306., 10401., 10402., 10403., @@ -594,13 +566,12 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeTwoQPs_Puu) { } void TestIntegrateStiffnessMatrix_1Element1Node2QPs_Quu() { - constexpr auto number_of_elements = 1; constexpr auto number_of_qps = 2; - using QpMatrixView = Kokkos::View; + using QpMatrixView = Kokkos::View; const auto qp_Kuu = QpMatrixView("Kuu"); const auto qp_Puu = QpMatrixView("Cuu"); - const auto qp_Quu = get_qp_Quu( + const auto qp_Quu = get_qp_Quu( {10001., 10002., 10003., 10004., 10005., 10006., 10101., 10102., 10103., 10104., 10105., 10106., 10201., 10202., 10203., 10204., 10205., 10206., 10301., 10302., 10303., 10304., 10305., 10306., 10401., 10402., 10403., diff --git a/tests/unit_tests/restruct_poc/system/test_rotate_section_matrix.cpp b/tests/unit_tests/restruct_poc/system/test_rotate_section_matrix.cpp index 134688a2..a0bf27b5 100644 --- a/tests/unit_tests/restruct_poc/system/test_rotate_section_matrix.cpp +++ b/tests/unit_tests/restruct_poc/system/test_rotate_section_matrix.cpp @@ -9,35 +9,35 @@ namespace openturbine::tests { TEST(RotateSectionMatrixTests, OneNode) { - const auto rr0 = Kokkos::View("rr0"); + const auto rr0 = Kokkos::View("rr0"); constexpr auto rr0_data = std::array{1., 2., 3., 0., 0., 0., 4., 5., 6., 0., 0., 0., 7., 8., 9., 0., 0., 0., 0., 0., 0., 1., 2., 3., 0., 0., 0., 4., 5., 6., 0., 0., 0., 7., 8., 9.}; - const auto rr0_host = Kokkos::View(rr0_data.data()); + const auto rr0_host = Kokkos::View(rr0_data.data()); const auto rr0_mirror = Kokkos::create_mirror(rr0); Kokkos::deep_copy(rr0_mirror, rr0_host); Kokkos::deep_copy(rr0, rr0_mirror); - const auto Cstar = Kokkos::View("Cstar"); + const auto Cstar = Kokkos::View("Cstar"); constexpr auto Cstar_data = std::array{ 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25., 26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36.}; const auto Cstar_host = - Kokkos::View(Cstar_data.data()); + Kokkos::View(Cstar_data.data()); const auto Cstar_mirror = Kokkos::create_mirror(Cstar); Kokkos::deep_copy(Cstar_mirror, Cstar_host); Kokkos::deep_copy(Cstar, Cstar_mirror); - const auto Cuu = Kokkos::View("Cuu"); + const auto Cuu = Kokkos::View("Cuu"); - Kokkos::parallel_for("RotateSectionMatrix", 1, RotateSectionMatrix{rr0, Cstar, Cuu}); + Kokkos::parallel_for("RotateSectionMatrix", 1, RotateSectionMatrix{0, rr0, Cstar, Cuu}); constexpr auto Cuu_exact_data = std::array{ 372., 912., 1452., 480., 1182., 1884., 822., 2010., 3198., 1092., 2685., 4278., 1272., 3108., 4944., 1704., 4188., 6672., 1020., 2532., 4044., 1128., 2802., 4476., 2442., 6060., 9678., 2712., 6735., 10758., 3864., 9588., 15312., 4296., 10668., 17040.}; const auto Cuu_exact = - Kokkos::View(Cuu_exact_data.data()); + Kokkos::View(Cuu_exact_data.data()); const auto Cuu_mirror = Kokkos::create_mirror(Cuu); Kokkos::deep_copy(Cuu_mirror, Cuu); diff --git a/tests/unit_tests/restruct_poc/test_beams.cpp b/tests/unit_tests/restruct_poc/test_beams.cpp index 5bf83d76..3a3feabc 100644 --- a/tests/unit_tests/restruct_poc/test_beams.cpp +++ b/tests/unit_tests/restruct_poc/test_beams.cpp @@ -186,68 +186,10 @@ TEST(BeamsTest, NodeInitialAcceleration) { ); } -// TEST(BeamsTest, ShapeFunctionInterpolationMatrix) { -// const auto beams = SetUpBeams(); -// expect_kokkos_view_2D_equal( -// beams.shape_interp, -// {{0.7643937937285443, 0.13706262395004942, -0.13172898316530468, -// 0.000000000000000022962127484012874, 0.05567285555959517, -0.020342107108930366, -// -0.01995866709520774}, -// {0.308266541035087, 0.95147326166415, 0.7339940232440426, -// -0.00000000000000008184220124322266, -0.1722057227387884, 0.05920536387827322, -// 0.05659843178759581}, -// {-0.1093000994560195, -0.12739914238354233, 0.5142678271004555, 0.9999999999999999, -// 0.5142678271004553, -0.12739914238354247, -0.1093000994560195}, -// {0.05659843178759582, 0.05920536387827313, -0.17220572273878845, -// 0.0000000000000000818422012432227, 0.7339940232440427, 0.9514732616641498, -// 0.308266541035087}, -// {-0.01995866709520774, -0.020342107108930346, 0.055672855559595176, -// -0.000000000000000022962127484012877, -0.1317289831653047, 0.13706262395004964, -// 0.7643937937285443}} -// ); -// } - -// TEST(BeamsTest, ShapeFunctionDerivativeMatrix) { -// const auto beams = SetUpBeams(); -// expect_kokkos_view_2D_equal( -// beams.shape_deriv, -// {{-4.2701511577426, -1.9393626617606694, 0.013055310813328586, 0.375, -// -0.12778431702017545, -// -0.1974469591256584, 0.29092055406654616}, -// {5.3820901606566505, 1.1702482430865344, -1.7874218089539982, -1.3365845776954526, -// 0.4351480290853632, 0.5662571364020152, -0.8312402426318174}, -// {-1.6522586914793211, 1.137924595950492, 2.0817302102058575, -// -0.0000000000000006661338147750939, -2.081730210205858, -1.1379245959504911, -// 1.6522586914793211}, -// {0.8312402426318174, -0.5662571364020155, -0.4351480290853627, 1.3365845776954537, -// 1.7874218089539977, -1.1702482430865357, -5.38209016065665}, -// {-0.2909205540665461, 0.1974469591256585, 0.12778431702017526, -0.3750000000000001, -// -0.013055310813328114, 1.9393626617606703, 4.2701511577426}} -// ); -// } - -// TEST(BeamsTest, JacobianArray) { -// const auto beams = SetUpBeams(); -// expect_kokkos_view_1D_equal( -// beams.qp_jacobian, -// {2.7027484463552844, 2.585197218483525, 2.5041356900076877, 2.5980762113533173, -// 2.8809584014451253, 3.2234919864103784, 3.4713669823269462} -// ); -// } - -// TEST(BeamsTest, QuadraturePointWeights) { -// const auto beams = SetUpBeams(); -// expect_kokkos_view_1D_equal( -// beams.qp_weight, -// {0.1294849661688697, 0.27970539148927664, 0.3818300505051189, 0.4179591836734694, -// 0.3818300505051189, 0.27970539148927664, 0.1294849661688697} -// ); -// } - TEST(BeamsTest, QuadraturePointMassMatrixInMaterialFrame) { const auto beams = SetUpBeams(); - auto Mstar = View_NxN("Mstar", beams.qp_Mstar.extent(1), beams.qp_Mstar.extent(2)); - Kokkos::deep_copy(Mstar, Kokkos::subview(beams.qp_Mstar, 0, Kokkos::ALL, Kokkos::ALL)); + auto Mstar = View_NxN("Mstar", beams.qp_Mstar.extent(2), beams.qp_Mstar.extent(3)); + Kokkos::deep_copy(Mstar, Kokkos::subview(beams.qp_Mstar, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Mstar, { @@ -264,8 +206,8 @@ TEST(BeamsTest, QuadraturePointMassMatrixInMaterialFrame) { TEST(BeamsTest, QuadraturePointStiffnessMatrixInMaterialFrame) { const auto beams = SetUpBeams(); - auto Cstar = View_NxN("Cstar", beams.qp_Cstar.extent(1), beams.qp_Cstar.extent(2)); - Kokkos::deep_copy(Cstar, Kokkos::subview(beams.qp_Cstar, 0, Kokkos::ALL, Kokkos::ALL)); + auto Cstar = View_NxN("Cstar", beams.qp_Cstar.extent(2), beams.qp_Cstar.extent(3)); + Kokkos::deep_copy(Cstar, Kokkos::subview(beams.qp_Cstar, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Cstar, { @@ -279,186 +221,10 @@ TEST(BeamsTest, QuadraturePointStiffnessMatrixInMaterialFrame) { ); } -TEST(BeamsTest, QuadraturePointInitialPosition) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_x0, - { - {0.12723021914310378, -0.04894958421765723, 0.024151041535564563}, - {0.6461720360015141, -0.20836421838736455, 0.09583134319147545}, - {1.4853871215565078, -0.32938986051629177, 0.12056743224042737}, - {2.5, -0.24999999999999994, -3.061616997868384e-17}, - {3.5146128784434927, 0.07645529086110522, -0.28527771913696975}, - {4.353827963998485, 0.5331669672120298, -0.645699842407919}, - {4.8727697808568955, 0.9001583281251011, -0.9249568708071938}, - } - ); -} - -TEST(BeamsTest, QuadraturePointInitialPositionDerivative) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_x0_prime, - { - {0.924984344499876, -0.3417491071948319, 0.16616711516322952}, - {0.9670442092872504, -0.23684722156643212, 0.09342853375847142}, - {0.9983484561063567, -0.0434352369562536, -0.03759973910292136}, - {0.9622504486493763, 0.19245008972987515, -0.1924500897298753}, - {0.8677667816189111, 0.38486072083162454, -0.3144249326623439}, - {0.7755564495086442, 0.5001708660037699, -0.38515100730308954}, - {0.7201773862365269, 0.5541511105877541, -0.4174458994742709}, - } - ); -} - -TEST(BeamsTest, QuadraturePointInitialRotation) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_r0, - { - {0.980884413320975, -0.0144723270940525, -0.0824443301646419, -0.1756680160876}, - {0.991669584564107, -0.005383778767255235, -0.04674982717307109, -0.11990372653059925}, - {0.9995861588301111, -0.00017992787003652953, 0.01938431110866726, -0.02125387456601228}, - {0.9904718430204885, -0.00952641109153648, 0.09620741150793369, 0.09807604012323788}, - {0.9659269297215409, -0.03234979016749597, 0.15563090950471747, 0.2042490575781702}, - {0.9405335895294235, -0.05575622959800262, 0.18841261313027519, 0.2771073745704617}, - {0.9248004133377579, -0.06909685323377392, 0.20225483002403755, 0.3147424408869105}, - } - ); -} - -TEST(BeamsTest, QuadraturePointTranslationalDisplacement) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_u, - { - {6.475011465280995e-5, -6.310248039744534e-5, 6.5079641503883e-5}, - {0.001670153200441368, -0.0014543119416486395, 0.0017133214521999145}, - {0.00882549960354371, -0.006203642913062532, 0.009349870941639945}, - {0.025000000000000000, -0.012500000000000000, 0.027500000000000004}, - {0.049410014741283426, -0.014678599914523912, 0.05635629770663533}, - {0.07582327176038081, -0.00979897557794027, 0.08902813099686892}, - {0.09497554134892866, -0.002416751787811821, 0.113487299261152}, - } - ); -} - -TEST(BeamsTest, QuadraturePointTranslationalDisplacementDerivative) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_u_prime, - { - {0.0009414876868372848, -0.0009055519814222241, 0.0009486748279202956}, - {0.0049990154049489330, -0.0040299482162833, 0.00519282884268206}, - {0.0118634715162096380, -0.006576917174070561, 0.012920782384637453}, - {0.0192450089729875180, -0.004811252243246878, 0.022131760318935656}, - {0.0243989144493063000, 0.0013269072337655852, 0.029544078785920684}, - {0.0270131148602409250, 0.008270021601725071, 0.03406974215263411}, - {0.0280740688360788040, 0.012965473438963544, 0.03628197729108727}, - } - ); -} - -TEST(BeamsTest, QuadraturePointRotationalDisplacement) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_r, - { - {0.9999991906236807, 0.001272301844556629, 0.0, 0.0}, - {0.9999791231576566, 0.006461675389885671, 0.0, 0.0}, - {0.9998896832832036, 0.014853325008724992, 0.0, 0.0}, - {0.9996875162757026, 0.024997395914712214, 0.0, 0.0}, - {0.9993824383901835, 0.035138893512620800, 0.0, 0.0}, - {0.9990523588113228, 0.043524525885204780, 0.0, 0.0}, - {0.9988130406194091, 0.048708417020170240, 0.0, 0.0}, - } - ); -} - -TEST(BeamsTest, QuadraturePointRotationalDisplacementDerivative) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_r_prime, - { - {-1.1768592508490864e-5, 0.009249835939573259, 0.0, 0.0}, - {-6.24872579944091e-5, 0.009670240217676533, 0.0, 0.0}, - {-0.00014828794095145858, 0.009982383220428504, 0.0, 0.0}, - {-0.00024053755400424963, 0.009619497597035018, 0.0, 0.0}, - {-0.0003049236454906731, 0.008672308825681862, 0.0, 0.0}, - {-0.00033755726789449716, 0.007748215013234193, 0.0, 0.0}, - {-0.00035078700412695185, 0.0071932256346726306, 0.0, 0.0}, - } - ); -} - -TEST(BeamsTest, QuadraturePointInitialTranslationalVelocity) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_u_dot, - { - {0.0025446043828620765, -0.0024798542682092665, 6.5079641503883e-5}, - {0.0129234407200302820, -0.0112532875195889140, 0.0017133214521999145}, - {0.0297077424311301600, -0.0208822428275864500, 0.009349870941639945}, - {0.0500000000000000000, -0.0249999999999999980, 0.027500000000000004}, - {0.0702922575688698500, -0.0208822428275864400, 0.05635629770663533}, - {0.0870765592799697300, -0.0112532875195889040, 0.08902813099686892}, - {0.0974553956171379200, -0.0024798542682092648, 0.113487299261152}, - } - ); -} - -TEST(BeamsTest, QuadraturePointInitialAngularVelocity) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_omega, - { - {0.0025446043828620765, -0.0024798542682092665, 6.5079641503883e-5}, - {0.0129234407200302820, -0.011253287519588914, 0.0017133214521999145}, - {0.0297077424311301600, -0.020882242827586450, 0.009349870941639945}, - {0.0500000000000000000, -0.024999999999999998, 0.027500000000000004}, - {0.0702922575688698500, -0.020882242827586440, 0.05635629770663533}, - {0.0870765592799697300, -0.011253287519588904, 0.08902813099686892}, - {0.0974553956171379200, -0.0024798542682092648, 0.113487299261152}, - } - ); -} - -TEST(BeamsTest, QuadraturePointTranslationalAcceleration) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_u_ddot, - { - {0.0025446043828620765, -0.0024151041535564553, 0.0001298297561566934}, - {0.012923440720030282, -0.009583134319147544, 0.003383474652641283}, - {0.02970774243113016, -0.01205674322404274, 0.018175370545183655}, - {0.05000000000000000, 3.0616169978683843e-18, 0.052500000000000005}, - {0.07029225756886985, 0.028527771913696987, 0.10576631244791876}, - {0.08707655927996973, 0.06456998424079191, 0.16485140275724972}, - {0.09745539561713792, 0.0924956870807194, 0.2084628406100807}, - } - ); -} - -TEST(BeamsTest, QuadraturePointAngularAcceleration) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_omega_dot, - { - {0.0025446043828620765, -0.0024798542682092665, -0.0024798542682092665}, - {0.012923440720030282, -0.011253287519588914, -0.011253287519588914}, - {0.02970774243113016, -0.02088224282758645, -0.02088224282758645}, - {0.05000000000000000, -0.024999999999999998, -0.024999999999999998}, - {0.07029225756886985, -0.02088224282758644, -0.02088224282758644}, - {0.08707655927996973, -0.011253287519588904, -0.011253287519588904}, - {0.09745539561713792, -0.0024798542682092648, -0.0024798542682092648}, - } - ); -} - TEST(BeamsTest, QuadraturePointRR0) { const auto beams = SetUpBeams(); - auto RR0 = View_NxN("RR0", beams.qp_RR0.extent(1), beams.qp_RR0.extent(2)); - Kokkos::deep_copy(RR0, Kokkos::subview(beams.qp_RR0, 0, Kokkos::ALL, Kokkos::ALL)); + auto RR0 = View_NxN("RR0", beams.qp_RR0.extent(2), beams.qp_RR0.extent(3)); + Kokkos::deep_copy(RR0, Kokkos::subview(beams.qp_RR0, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( RR0, { @@ -474,8 +240,8 @@ TEST(BeamsTest, QuadraturePointRR0) { TEST(BeamsTest, QuadraturePointMassMatrixInGlobalFrame) { const auto beams = SetUpBeams(); - auto Muu = View_NxN("Muu", beams.qp_Muu.extent(1), beams.qp_Muu.extent(2)); - Kokkos::deep_copy(Muu, Kokkos::subview(beams.qp_Muu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Muu = View_NxN("Muu", beams.qp_Muu.extent(2), beams.qp_Muu.extent(3)); + Kokkos::deep_copy(Muu, Kokkos::subview(beams.qp_Muu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Muu, { @@ -497,8 +263,8 @@ TEST(BeamsTest, QuadraturePointMassMatrixInGlobalFrame) { TEST(BeamsTest, QuadraturePointStiffnessMatrixInGlobalFrame) { const auto beams = SetUpBeams(); - auto Cuu = View_NxN("Cuu", beams.qp_Cuu.extent(1), beams.qp_Cuu.extent(2)); - Kokkos::deep_copy(Cuu, Kokkos::subview(beams.qp_Cuu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Cuu = View_NxN("Cuu", beams.qp_Cuu.extent(2), beams.qp_Cuu.extent(3)); + Kokkos::deep_copy(Cuu, Kokkos::subview(beams.qp_Cuu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Cuu, { @@ -518,111 +284,10 @@ TEST(BeamsTest, QuadraturePointStiffnessMatrixInGlobalFrame) { ); } -TEST(BeamsTest, QuadraturePointStrain) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_strain, - { - {0.0009414876868373279, -0.00048382928348705834, 0.0018188281296873943, - 0.0184996868523541, 0.0, 0.0}, - {0.004999015404948959, -0.002842341990545394, 0.008261426556751703, 0.019340884211946498, - 0.0, 0.0}, - {0.01186347151620959, -0.007712921718478594, 0.014194364820045248, 0.0199669691313353, - 0.0, 0.0}, - {0.019245008972987532, -0.014189235354885782, 0.01227275220904131, 0.019245008946139657, - 0.0, 0.0}, - {0.024398914449306308, -0.01980612763870543, 0.0017371550623738186, 0.01735533564038205, - 0.0, 0.0}, - {0.02701311486024094, -0.023330205052589426, -0.010887645811743119, 0.015511129011186278, - 0.0, 0.0}, - {0.02807406883607877, -0.02502305729533416, -0.019618382135299595, 0.014403547695422242, - 0.0, 0.0}, - } - ); -} - -TEST(BeamsTest, QuadraturePointElasticForceFC) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_Fc, - { - {0.10234015755301404, 0.15123731179112573, 0.2788710191555731, 0.4003531623743687, - 0.3249734441776631, 0.587574363833825}, - {0.13306714951787607, 0.19697673529625817, 0.35331128776303233, 0.5133351516878956, - 0.4501862995539333, 0.7288106297098484}, - {0.1574290494109584, 0.24483537583051979, 0.39546209547846906, 0.5824699918301253, - 0.6098871468512939, 0.7841672804415049}, - {0.11793522304442454, 0.22073370020290126, 0.2970111064121941, 0.4152800673577701, - 0.5850266055677404, 0.5612027971947426}, - {0.03186778209076205, 0.08327525615132295, 0.09383878502122098, 0.1098030416906359, - 0.22617087196765523, 0.17014187136266343}, - {-0.023089877459047222, -0.09044007186162746, -0.09136793568603306, -0.08138800637367143, - -0.24723410629067144, -0.16150807105320447}, - {-0.038045836638108975, -0.20629914099635355, -0.19957255488872738, -0.14032215607825765, - -0.565277913007998, -0.34909700109374714}, - } - ); -} - -TEST(BeamsTest, QuadraturePointElasticForceFD) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_Fd, - { - {0.0, 0.0, 0.0, 0.12083059685899937, 0.2411112242070902, -0.1751018655842517}, - {0.0, 0.0, 0.0, 0.10453073708428946, 0.33031057987442725, -0.22352273933363598}, - {0.0, 0.0, 0.0, 0.013735629628543994, 0.40338571047157723, -0.25520898285167615}, - {0.0, 0.0, 0.0, -0.09332581379105467, 0.311601581974594, -0.1945198959425422}, - {0.0, 0.0, 0.0, -0.05996290388705013, 0.0927982659298175, -0.061988383692168025}, - {0.0, 0.0, 0.0, 0.0782070091683667, -0.08143554773131514, 0.06084461128549694}, - {0.0, 0.0, 0.0, 0.19181469531917145, -0.16383215490377, 0.13278720752010728}, - } - ); -} - -TEST(BeamsTest, QuadraturePointInternalForceFI) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_Fi, - { - {0.004375199541621397, -0.006996757474943007, 0.0016854280323566574, - -0.008830739650908434, -0.01379034342897087, -0.02975324221499824}, - {0.022688362568082213, -0.02992652234700804, 0.013688107068036132, -0.03886658700317607, - -0.060824965744675934, -0.12868857402180311}, - {0.05443226231283839, -0.04765607714110308, 0.05164453045055776, -0.06741913573437128, - -0.11199467143793916, -0.21160513689448818}, - {0.09626719733160705, -0.036356394776880435, 0.13017740515825674, -0.0655069009245357, - -0.13688516240854653, -0.2044209307349181}, - {0.1400861741787473, 0.010259103320423194, 0.24646612271293694, -0.03557208624212079, - -0.10605047687360963, -0.11140102512076272}, - {0.1765783599566686, 0.07337977541628125, 0.3727813760978104, -0.017058328302108794, - -0.023041772515279488, 0.021701973146492262}, - {0.19926271187822545, 0.12238033682674138, 0.4651665411925664, -0.022580493439478086, - 0.0575214328048846, 0.13433832751076802}, - } - ); -} - -TEST(BeamsTest, QuadraturePointGravityForceFg) { - const auto beams = SetUpBeams(); - expect_kokkos_view_2D_equal( - beams.qp_Fg, - { - {0.0, 0.0, 19.620000000000008, 3.33069666549358, -2.2538354951632575, 0.0}, - {0.0, 0.0, 19.620000000000005, 3.395755863205606, -2.293994529332462, 0.0}, - {0.0, 0.0, 19.620000000000008, 3.660343899283414, -2.3535996733587927, 0.0}, - {0.0, 0.0, 19.620000000000008, 4.17217336243553, -2.2291394364636914, 0.0}, - {0.0, 0.0, 19.62, 4.7227318298581675, -1.8072954174231637, 0.0}, - {0.0, 0.0, 19.619999999999997, 5.083070688156127, -1.297737572397898, 0.0}, - {0.0, 0.0, 19.620000000000015, 5.230522791902463, -0.964616792447741, 0.0}, - } - ); -} - TEST(BeamsTest, QuadraturePointMatrixOuu) { const auto beams = SetUpBeams(); - auto Ouu = View_NxN("Ouu", beams.qp_Ouu.extent(1), beams.qp_Ouu.extent(2)); - Kokkos::deep_copy(Ouu, Kokkos::subview(beams.qp_Ouu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Ouu = View_NxN("Ouu", beams.qp_Ouu.extent(2), beams.qp_Ouu.extent(3)); + Kokkos::deep_copy(Ouu, Kokkos::subview(beams.qp_Ouu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Ouu, { @@ -638,8 +303,8 @@ TEST(BeamsTest, QuadraturePointMatrixOuu) { TEST(BeamsTest, QuadraturePointMatrixPuu) { const auto beams = SetUpBeams(); - auto Puu = View_NxN("Puu", beams.qp_Puu.extent(1), beams.qp_Puu.extent(2)); - Kokkos::deep_copy(Puu, Kokkos::subview(beams.qp_Puu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Puu = View_NxN("Puu", beams.qp_Puu.extent(2), beams.qp_Puu.extent(3)); + Kokkos::deep_copy(Puu, Kokkos::subview(beams.qp_Puu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Puu, { @@ -658,8 +323,8 @@ TEST(BeamsTest, QuadraturePointMatrixPuu) { TEST(BeamsTest, QuadraturePointMatrixQuu) { const auto beams = SetUpBeams(); - auto Quu = View_NxN("Quu", beams.qp_Quu.extent(1), beams.qp_Quu.extent(2)); - Kokkos::deep_copy(Quu, Kokkos::subview(beams.qp_Quu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Quu = View_NxN("Quu", beams.qp_Quu.extent(2), beams.qp_Quu.extent(3)); + Kokkos::deep_copy(Quu, Kokkos::subview(beams.qp_Quu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Quu, { @@ -675,8 +340,8 @@ TEST(BeamsTest, QuadraturePointMatrixQuu) { TEST(BeamsTest, QuadraturePointMatrixGuu) { const auto beams = SetUpBeams(); - auto Guu = View_NxN("Guu", beams.qp_Guu.extent(1), beams.qp_Guu.extent(2)); - Kokkos::deep_copy(Guu, Kokkos::subview(beams.qp_Guu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Guu = View_NxN("Guu", beams.qp_Guu.extent(2), beams.qp_Guu.extent(3)); + Kokkos::deep_copy(Guu, Kokkos::subview(beams.qp_Guu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Guu, { @@ -692,8 +357,8 @@ TEST(BeamsTest, QuadraturePointMatrixGuu) { TEST(BeamsTest, QuadraturePointMatrixKuu) { const auto beams = SetUpBeams(); - auto Kuu = View_NxN("Kuu", beams.qp_Kuu.extent(1), beams.qp_Kuu.extent(2)); - Kokkos::deep_copy(Kuu, Kokkos::subview(beams.qp_Kuu, 0, Kokkos::ALL, Kokkos::ALL)); + auto Kuu = View_NxN("Kuu", beams.qp_Kuu.extent(2), beams.qp_Kuu.extent(3)); + Kokkos::deep_copy(Kuu, Kokkos::subview(beams.qp_Kuu, 0, 0, Kokkos::ALL, Kokkos::ALL)); expect_kokkos_view_2D_equal( Kuu, { diff --git a/tests/unit_tests/restruct_poc/test_rotor.cpp b/tests/unit_tests/restruct_poc/test_rotor.cpp index 5ba873af..efff059d 100644 --- a/tests/unit_tests/restruct_poc/test_rotor.cpp +++ b/tests/unit_tests/restruct_poc/test_rotor.cpp @@ -156,11 +156,7 @@ TEST(RotorTest, IEA15Rotor) { UpdateState(beams, solver.state.q, solver.state.v, solver.state.vd); // Write quadrature point global positions to file and VTK - std::vector> qp_x0; if (write_output) { - qp_x0 = kokkos_view_2D_to_vector(beams.qp_x0); - WriteMatrixToFile(qp_x0, "steps/step_0000.csv"); - #ifdef OTURB_ENABLE_VTK // Write vtk visualization file BeamsWriteVTK(beams, "steps/step_0000.vtu"); @@ -195,16 +191,6 @@ TEST(RotorTest, IEA15Rotor) { // If flag set, write quadrature point glob position to file if (write_output) { - auto tmp = std::to_string(i + 1); - auto file_name = std::string("steps/step_") + std::string(4 - tmp.size(), '0') + tmp; - auto qp_x = kokkos_view_2D_to_vector(beams.qp_u); - for (size_t j = 0; j < qp_x.size(); ++j) { - for (size_t k = 0; k < qp_x[0].size(); ++k) { - qp_x[j][k] += qp_x0[j][k]; - } - } - WriteMatrixToFile(qp_x, file_name + ".csv"); - #ifdef OTURB_ENABLE_VTK // Write VTK output to file BeamsWriteVTK(beams, file_name + ".vtu"); @@ -322,11 +308,7 @@ TEST(RotorTest, IEA15RotorHub) { UpdateState(beams, solver.state.q, solver.state.v, solver.state.vd); // Write quadrature point global positions to file and VTK - std::vector> qp_x0; if (write_output) { - qp_x0 = kokkos_view_2D_to_vector(beams.qp_x0); - WriteMatrixToFile(qp_x0, "steps/step_0000.csv"); - #ifdef OTURB_ENABLE_VTK // Write vtk visualization file BeamsWriteVTK(beams, "steps/step_0000.vtu"); @@ -356,16 +338,6 @@ TEST(RotorTest, IEA15RotorHub) { // If flag set, write quadrature point glob position to file if (write_output) { - auto tmp = std::to_string(i + 1); - auto file_name = std::string("steps/step_") + std::string(4 - tmp.size(), '0') + tmp; - auto qp_x = kokkos_view_2D_to_vector(beams.qp_u); - for (size_t j = 0; j < qp_x.size(); ++j) { - for (size_t k = 0; k < qp_x[0].size(); ++k) { - qp_x[j][k] += qp_x0[j][k]; - } - } - WriteMatrixToFile(qp_x, file_name + ".csv"); - #ifdef OTURB_ENABLE_VTK // Write VTK output to file BeamsWriteVTK(beams, file_name + ".vtu"); @@ -515,11 +487,7 @@ TEST(RotorTest, IEA15RotorController) { UpdateState(beams, solver.state.q, solver.state.v, solver.state.vd); // Write quadrature point global positions to file and VTK - std::vector> qp_x0; if (write_output) { - qp_x0 = kokkos_view_2D_to_vector(beams.qp_x0); - WriteMatrixToFile(qp_x0, "steps/step_0000.csv"); - #ifdef OTURB_ENABLE_VTK // Write vtk visualization file BeamsWriteVTK(beams, "steps/step_0000.vtu");