From acd8ee7c1440a959f778001e47c35dd211347f5e Mon Sep 17 00:00:00 2001 From: dcdemen Date: Thu, 20 Feb 2025 15:13:10 -0700 Subject: [PATCH] Moved Tangent application from sparse matrix assembly to contribution calculation This change improves performance significantly and decreases memory usage --- src/elements/beams/beams.hpp | 8 +- src/elements/masses/masses.hpp | 6 +- .../contribute_masses_to_sparse_matrix.hpp | 2 +- src/solver/solver.hpp | 22 +--- src/step/assemble_system_matrix.hpp | 53 +-------- src/step/step.hpp | 4 +- src/step/update_system_variables_beams.hpp | 22 ++-- src/step/update_system_variables_masses.hpp | 5 +- src/system/beams/CMakeLists.txt | 1 + .../calculate_quadrature_point_values.hpp | 46 +++++--- src/system/beams/calculate_system_matrix.hpp | 53 +++++++++ src/system/beams/integrate_inertia_matrix.hpp | 14 +-- .../beams/integrate_stiffness_matrix.hpp | 14 +-- src/system/calculate_tangent_operator.hpp | 3 +- .../calculate_quadrature_point_values.hpp | 34 +++--- .../regression/test_rotor.cpp | 4 +- .../system/beams/test_calculate_Puu.cpp | 15 ++- .../beams/test_integrate_inertia_matrix.cpp | 87 ++------------- .../beams/test_integrate_stiffness_matrix.cpp | 101 ++---------------- 19 files changed, 179 insertions(+), 315 deletions(-) create mode 100644 src/system/beams/calculate_system_matrix.hpp diff --git a/src/elements/beams/beams.hpp b/src/elements/beams/beams.hpp index f1d8ed8a1..30873de36 100644 --- a/src/elements/beams/beams.hpp +++ b/src/elements/beams/beams.hpp @@ -61,8 +61,7 @@ struct Beams { Kokkos::View qp_Fe; // External force Kokkos::View residual_vector_terms; - Kokkos::View stiffness_matrix_terms; - Kokkos::View inertia_matrix_terms; + Kokkos::View system_matrix_terms; // Shape Function data Kokkos::View shape_interp; // Shape function values @@ -107,10 +106,7 @@ struct Beams { qp_E("qp_E", num_elems, max_elem_qps), qp_Fe("qp_Fe", num_elems, max_elem_qps), residual_vector_terms("residual_vector_terms", num_elems, max_elem_nodes), - stiffness_matrix_terms( - "stiffness_matrix_terms", num_elems, max_elem_nodes, max_elem_nodes - ), - inertia_matrix_terms("inertia_matrix_terms", num_elems, max_elem_nodes, max_elem_nodes), + system_matrix_terms("system_matrix_terms", num_elems, max_elem_nodes, max_elem_nodes), // Shape Function data shape_interp("shape_interp", num_elems, max_elem_nodes, max_elem_qps), shape_deriv("deriv_interp", num_elems, max_elem_nodes, max_elem_qps) { diff --git a/src/elements/masses/masses.hpp b/src/elements/masses/masses.hpp index f4529afe3..5dd5650d4 100644 --- a/src/elements/masses/masses.hpp +++ b/src/elements/masses/masses.hpp @@ -28,8 +28,7 @@ struct Masses { Kokkos::View qp_Mstar; //< Mass matrix in material frame Kokkos::View residual_vector_terms; - Kokkos::View stiffness_matrix_terms; - Kokkos::View inertia_matrix_terms; + Kokkos::View system_matrix_terms; explicit Masses(const size_t n_mass_elems) : num_elems(n_mass_elems), @@ -41,8 +40,7 @@ struct Masses { node_x0("node_x0", num_elems), qp_Mstar("qp_Mstar", num_elems), residual_vector_terms("residual_vector_terms", num_elems), - stiffness_matrix_terms("stiffness_matrix_terms", num_elems), - inertia_matrix_terms("inertia_matrix_terms", num_elems) { + system_matrix_terms("system_matrix_terms", num_elems) { Kokkos::deep_copy(num_nodes_per_element, 1); // Always 1 node per element Kokkos::deep_copy(element_freedom_signature, FreedomSignature::AllComponents); } diff --git a/src/solver/contribute_masses_to_sparse_matrix.hpp b/src/solver/contribute_masses_to_sparse_matrix.hpp index cc43cf9de..b3445e838 100644 --- a/src/solver/contribute_masses_to_sparse_matrix.hpp +++ b/src/solver/contribute_masses_to_sparse_matrix.hpp @@ -19,7 +19,7 @@ struct ContributeMassesToSparseMatrix { KOKKOS_FUNCTION void operator()(size_t i) const { constexpr auto is_sorted = true; - constexpr auto force_atomic = false; + constexpr auto force_atomic = !std::is_same_v; const auto num_dofs = count_active_dofs(element_freedom_signature(i)); auto row_data_data = Kokkos::Array{}; auto col_idx_data = Kokkos::Array{}; diff --git a/src/solver/solver.hpp b/src/solver/solver.hpp index 4ff00c1bf..71fc83f11 100644 --- a/src/solver/solver.hpp +++ b/src/solver/solver.hpp @@ -52,17 +52,13 @@ struct Solver { size_t num_system_dofs; //< Number of system degrees of freedom size_t num_dofs; //< Number of degrees of freedom - KernelHandle system_spgemm_handle; KernelHandle constraints_spgemm_handle; - KernelHandle system_spadd_handle; KernelHandle spc_spadd_handle; KernelHandle full_system_spadd_handle; - CrsMatrixType K; //< Stiffness matrix CrsMatrixType T; //< Tangent operator CrsMatrixType B; //< Constraints matrix CrsMatrixType B_t; //< Transpose of constraints matrix - CrsMatrixType static_system_matrix; //< Static system matrix CrsMatrixType system_matrix; //< System matrix CrsMatrixType constraints_matrix; //< Constraints matrix CrsMatrixType system_matrix_full; //< System matrix with constraints @@ -115,10 +111,6 @@ struct Solver { : num_system_nodes(node_IDs.extent(0)), num_system_dofs(ComputeNumSystemDofs(node_freedom_allocation_table)), num_dofs(num_system_dofs + num_constraint_dofs), - K(CreateKMatrix( - num_system_dofs, node_freedom_allocation_table, node_freedom_map_table, - num_nodes_per_element, node_state_indices - )), T(CreateTMatrix( num_system_dofs, node_freedom_allocation_table, node_freedom_map_table )), @@ -132,8 +124,10 @@ struct Solver { constraint_base_node_freedom_table, constraint_target_node_freedom_table, constraint_row_range, constraint_base_node_col_range, constraint_target_node_col_range )), - static_system_matrix(CreateMatrixSpgemm(K, T, system_spgemm_handle)), - system_matrix(CreateMatrixSpadd(K, static_system_matrix, system_spadd_handle)), + system_matrix(CreateKMatrix( + num_system_dofs, node_freedom_allocation_table, node_freedom_map_table, + num_nodes_per_element, node_state_indices + )), constraints_matrix(CreateMatrixSpgemm(B, T, constraints_spgemm_handle)), system_matrix_full(CreateSystemMatrixFull(num_system_dofs, num_dofs, system_matrix)), constraints_matrix_full( @@ -160,12 +154,10 @@ struct Solver { : num_system_nodes(other.num_system_nodes), num_system_dofs(other.num_system_dofs), num_dofs(other.num_dofs), - K("K", other.K), T("T", other.T), B("B", other.B), B_t("B_t", other.B_t), - static_system_matrix(CreateMatrixSpgemm(K, T, system_spgemm_handle)), - system_matrix(CreateMatrixSpadd(K, static_system_matrix, system_spadd_handle)), + system_matrix("system_matrix", other.system_matrix), constraints_matrix(CreateMatrixSpgemm(B, T, constraints_spgemm_handle)), system_matrix_full(CreateSystemMatrixFull(num_system_dofs, num_dofs, system_matrix)), constraints_matrix_full( @@ -201,17 +193,13 @@ struct Solver { std::swap(num_system_dofs, tmp.num_system_dofs); std::swap(num_dofs, tmp.num_dofs); - std::swap(system_spgemm_handle, tmp.system_spgemm_handle); std::swap(constraints_spgemm_handle, tmp.constraints_spgemm_handle); - std::swap(system_spadd_handle, tmp.system_spadd_handle); std::swap(spc_spadd_handle, tmp.spc_spadd_handle); std::swap(full_system_spadd_handle, tmp.full_system_spadd_handle); - std::swap(K, tmp.K); std::swap(T, tmp.T); std::swap(B, tmp.B); std::swap(B_t, tmp.B_t); - std::swap(static_system_matrix, tmp.static_system_matrix); std::swap(system_matrix, tmp.system_matrix); std::swap(constraints_matrix, tmp.constraints_matrix); std::swap(system_matrix_full, tmp.system_matrix_full); diff --git a/src/step/assemble_system_matrix.hpp b/src/step/assemble_system_matrix.hpp index aa6eb347b..98ace700f 100644 --- a/src/step/assemble_system_matrix.hpp +++ b/src/step/assemble_system_matrix.hpp @@ -21,69 +21,26 @@ inline void AssembleSystemMatrix(Solver& solver, Elements& elements) { auto springs_sparse_matrix_policy = Kokkos::RangePolicy<>(0, static_cast(elements.springs.num_elems)); - // Assemble stiffness matrix by contributing beam, mass, and spring stiffness matrices to the - // global sparse matrix - Kokkos::deep_copy(solver.K.values, 0.); + Kokkos::deep_copy(solver.system_matrix.values, 0.); Kokkos::parallel_for( "ContributeBeamsToSparseMatrix", beams_sparse_matrix_policy, ContributeBeamsToSparseMatrix{ elements.beams.num_nodes_per_element, elements.beams.element_freedom_signature, - elements.beams.element_freedom_table, elements.beams.stiffness_matrix_terms, solver.K - } + elements.beams.element_freedom_table, elements.beams.system_matrix_terms, + solver.system_matrix} ); - Kokkos::fence(); Kokkos::parallel_for( "ContributeMassesToSparseMatrix", masses_sparse_matrix_policy, ContributeMassesToSparseMatrix{ elements.masses.element_freedom_signature, elements.masses.element_freedom_table, - elements.masses.stiffness_matrix_terms, solver.K - } + elements.masses.system_matrix_terms, solver.system_matrix} ); - Kokkos::fence(); Kokkos::parallel_for( "ContributeSpringsToSparseMatrix", springs_sparse_matrix_policy, ContributeSpringsToSparseMatrix{ elements.springs.element_freedom_signature, elements.springs.element_freedom_table, - elements.springs.stiffness_matrix_terms, solver.K - } + elements.springs.stiffness_matrix_terms, solver.system_matrix} ); - - Kokkos::fence(); - { - auto static_region = Kokkos::Profiling::ScopedRegion("Assemble Static System Matrix"); - KokkosSparse::spgemm_numeric( - solver.system_spgemm_handle, solver.K, false, solver.T, false, - solver.static_system_matrix - ); - } - - // Assemble inertia matrix by contributing beam and mass inertia matrices to the global - // sparse matrix - Kokkos::deep_copy(solver.K.values, 0.); - Kokkos::parallel_for( - "ContributeBeamsToSparseMatrix", beams_sparse_matrix_policy, - ContributeBeamsToSparseMatrix{ - elements.beams.num_nodes_per_element, elements.beams.element_freedom_signature, - elements.beams.element_freedom_table, elements.beams.inertia_matrix_terms, solver.K - } - ); - Kokkos::fence(); - Kokkos::parallel_for( - "ContributeMassesToSparseMatrix", masses_sparse_matrix_policy, - ContributeMassesToSparseMatrix{ - elements.masses.element_freedom_signature, elements.masses.element_freedom_table, - elements.masses.inertia_matrix_terms, solver.K - } - ); - - Kokkos::fence(); - { - auto system_region = Kokkos::Profiling::ScopedRegion("Assemble System Matrix"); - KokkosSparse::spadd_numeric( - &solver.system_spadd_handle, 1., solver.K, 1., solver.static_system_matrix, - solver.system_matrix - ); - } } } // namespace openturbine diff --git a/src/step/step.hpp b/src/step/step.hpp index 168685b97..6b09f77bd 100644 --- a/src/step/step.hpp +++ b/src/step/step.hpp @@ -56,10 +56,10 @@ inline bool Step( return false; } - UpdateSystemVariables(parameters, elements, state); - UpdateTangentOperator(parameters, state); + UpdateSystemVariables(parameters, elements, state); + AssembleTangentOperator(solver, state); AssembleSystemResidual(solver, elements, state); diff --git a/src/step/update_system_variables_beams.hpp b/src/step/update_system_variables_beams.hpp index 9a432b13e..fd367ad7c 100644 --- a/src/step/update_system_variables_beams.hpp +++ b/src/step/update_system_variables_beams.hpp @@ -12,15 +12,18 @@ namespace openturbine { inline void UpdateSystemVariablesBeams( StepParameters& parameters, const Beams& beams, State& state ) { + const auto num_nodes = beams.max_elem_nodes; + const auto num_qps = beams.max_elem_qps; + auto range_policy = Kokkos::TeamPolicy<>(static_cast(beams.num_elems), Kokkos::AUTO()); - const auto shape_size = - Kokkos::View::shmem_size(beams.max_elem_nodes, beams.max_elem_qps); - const auto weight_size = Kokkos::View::shmem_size(beams.max_elem_qps); - const auto node_variable_size = Kokkos::View::shmem_size(beams.max_elem_nodes); - const auto qp_variable_size = Kokkos::View::shmem_size(beams.max_elem_qps); - const auto qp_matrix_size = Kokkos::View::shmem_size(beams.max_elem_qps); + const auto shape_size = Kokkos::View::shmem_size(num_nodes, num_qps); + const auto weight_size = Kokkos::View::shmem_size(num_qps); + const auto node_variable_size = Kokkos::View::shmem_size(num_nodes); + const auto qp_variable_size = Kokkos::View::shmem_size(num_qps); + const auto qp_matrix_size = Kokkos::View::shmem_size(num_qps); + const auto system_matrix_size = Kokkos::View::shmem_size(num_nodes, num_nodes); auto smem = 2 * shape_size + 2 * weight_size + 4 * node_variable_size + 5 * qp_variable_size + - 7 * qp_matrix_size; + 7 * qp_matrix_size + 2 * system_matrix_size; range_policy.set_scratch_size(1, Kokkos::PerTeam(smem)); Kokkos::parallel_for( @@ -31,6 +34,7 @@ inline void UpdateSystemVariablesBeams( state.q, state.v, state.vd, + state.tangent, beams.node_state_indices, beams.num_nodes_per_element, beams.num_qps_per_element, @@ -47,9 +51,7 @@ inline void UpdateSystemVariablesBeams( beams.qp_Cstar, beams.qp_Fe, beams.residual_vector_terms, - beams.stiffness_matrix_terms, - beams.inertia_matrix_terms - } + beams.system_matrix_terms} ); } diff --git a/src/step/update_system_variables_masses.hpp b/src/step/update_system_variables_masses.hpp index 83170f4cb..fc9246e52 100644 --- a/src/step/update_system_variables_masses.hpp +++ b/src/step/update_system_variables_masses.hpp @@ -16,10 +16,9 @@ inline void UpdateSystemVariablesMasses( Kokkos::parallel_for( "masses::CalculateQuadraturePointValues", masses.num_elems, masses::CalculateQuadraturePointValues{ - parameters.beta_prime, parameters.gamma_prime, state.q, state.v, state.vd, + parameters.beta_prime, parameters.gamma_prime, state.q, state.v, state.vd, state.tangent, masses.state_indices, masses.gravity, masses.qp_Mstar, masses.node_x0, - masses.residual_vector_terms, masses.stiffness_matrix_terms, masses.inertia_matrix_terms - } + masses.residual_vector_terms, masses.system_matrix_terms} ); } diff --git a/src/system/beams/CMakeLists.txt b/src/system/beams/CMakeLists.txt index c0f3b6b9b..5cbcf93c6 100644 --- a/src/system/beams/CMakeLists.txt +++ b/src/system/beams/CMakeLists.txt @@ -10,6 +10,7 @@ install(FILES calculate_quadrature_point_values.hpp calculate_stiffness_quadrature_point_values.hpp calculate_strain.hpp + calculate_system_matrix.hpp calculate_temporary_variables.hpp integrate_inertia_matrix.hpp integrate_residual_vector.hpp diff --git a/src/system/beams/calculate_quadrature_point_values.hpp b/src/system/beams/calculate_quadrature_point_values.hpp index bbe6518b1..e0a9d67a4 100644 --- a/src/system/beams/calculate_quadrature_point_values.hpp +++ b/src/system/beams/calculate_quadrature_point_values.hpp @@ -4,6 +4,7 @@ #include "calculate_inertial_quadrature_point_values.hpp" #include "calculate_stiffness_quadrature_point_values.hpp" +#include "calculate_system_matrix.hpp" #include "integrate_inertia_matrix.hpp" #include "integrate_residual_vector.hpp" #include "integrate_stiffness_matrix.hpp" @@ -16,6 +17,7 @@ struct CalculateQuadraturePointValues { Kokkos::View::const_type Q; Kokkos::View::const_type V; Kokkos::View::const_type A; + Kokkos::View::const_type tangent; Kokkos::View::const_type node_state_indices; Kokkos::View::const_type num_nodes_per_element; Kokkos::View::const_type num_qps_per_element; @@ -32,8 +34,7 @@ struct CalculateQuadraturePointValues { Kokkos::View::const_type qp_Cstar_; Kokkos::View qp_FE_; Kokkos::View residual_vector_terms_; - Kokkos::View stiffness_matrix_terms_; - Kokkos::View inertia_matrix_terms_; + Kokkos::View system_matrix_terms_; KOKKOS_FUNCTION void operator()(Kokkos::TeamPolicy<>::member_type member) const { @@ -47,7 +48,8 @@ struct CalculateQuadraturePointValues { const auto qp_range = Kokkos::TeamThreadRange(member, num_qps); const auto node_range = Kokkos::TeamThreadRange(member, num_nodes); - const auto node_squared_range = Kokkos::TeamThreadRange(member, num_nodes * simd_nodes); + const auto node_squared_range = Kokkos::TeamThreadRange(member, num_nodes * num_nodes); + const auto node_squared_simd_range = Kokkos::TeamThreadRange(member, num_nodes * simd_nodes); const auto shape_interp = Kokkos::View(member.team_scratch(1), num_nodes, num_qps); @@ -75,6 +77,10 @@ struct CalculateQuadraturePointValues { const auto qp_Muu = Kokkos::View(member.team_scratch(1), num_qps); const auto qp_Guu = Kokkos::View(member.team_scratch(1), num_qps); + const auto stiffness_matrix_terms = + Kokkos::View(member.team_scratch(1), num_nodes, num_nodes); + const auto inertia_matrix_terms = + Kokkos::View(member.team_scratch(1), num_nodes, num_nodes); KokkosBatched::TeamVectorCopy::member_type>::invoke( member, Kokkos::subview(shape_interp_, i_elem, Kokkos::ALL, Kokkos::ALL), shape_interp ); @@ -114,23 +120,31 @@ struct CalculateQuadraturePointValues { Kokkos::parallel_for(qp_range, stiffness_quad_point_calculator); member.team_barrier(); - const auto residual_integrator = IntegrateResidualVectorElement{ + const auto residual_integrator = beams::IntegrateResidualVectorElement{ i_elem, num_qps, qp_weight, qp_jacobian, shape_interp, shape_deriv, node_FX, - qp_Fc, qp_Fd, qp_Fi, qp_Fe, qp_Fg, residual_vector_terms_ - }; + qp_Fc, qp_Fd, qp_Fi, qp_Fe, qp_Fg, residual_vector_terms_}; Kokkos::parallel_for(node_range, residual_integrator); - const auto stiffness_matrix_integrator = IntegrateStiffnessMatrixElement{ - i_elem, num_nodes, num_qps, qp_weight, qp_jacobian, shape_interp, shape_deriv, - qp_Kuu, qp_Puu, qp_Cuu, qp_Ouu, qp_Quu, stiffness_matrix_terms_ - }; - Kokkos::parallel_for(node_squared_range, stiffness_matrix_integrator); + const auto stiffness_matrix_integrator = beams::IntegrateStiffnessMatrixElement{ + i_elem, num_nodes, num_qps, qp_weight, qp_jacobian, shape_interp, shape_deriv, + qp_Kuu, qp_Puu, qp_Cuu, qp_Ouu, qp_Quu, stiffness_matrix_terms}; + Kokkos::parallel_for(node_squared_simd_range, stiffness_matrix_integrator); - const auto inertia_matrix_integrator = IntegrateInertiaMatrixElement{ - i_elem, num_nodes, num_qps, qp_weight, qp_jacobian, shape_interp, - qp_Muu, qp_Guu, beta_prime_, gamma_prime_, inertia_matrix_terms_ - }; - Kokkos::parallel_for(node_squared_range, inertia_matrix_integrator); + const auto inertia_matrix_integrator = beams::IntegrateInertiaMatrixElement{ + i_elem, num_nodes, num_qps, qp_weight, qp_jacobian, shape_interp, + qp_Muu, qp_Guu, beta_prime_, gamma_prime_, inertia_matrix_terms}; + Kokkos::parallel_for(node_squared_simd_range, inertia_matrix_integrator); + member.team_barrier(); + + const auto system_matrix_calculator = beams::CalculateSystemMatrix{ + i_elem, + num_nodes, + tangent, + node_state_indices, + stiffness_matrix_terms, + inertia_matrix_terms, + system_matrix_terms_}; + Kokkos::parallel_for(node_squared_range, system_matrix_calculator); } }; diff --git a/src/system/beams/calculate_system_matrix.hpp b/src/system/beams/calculate_system_matrix.hpp new file mode 100644 index 000000000..4c3674709 --- /dev/null +++ b/src/system/beams/calculate_system_matrix.hpp @@ -0,0 +1,53 @@ +#pragma once + +#include +#include +#include + +namespace openturbine::beams { + +struct CalculateSystemMatrix { + size_t i_elem; + size_t num_nodes; + Kokkos::View::const_type tangent; + Kokkos::View::const_type node_state_indices; + Kokkos::View::const_type stiffness_matrix_terms; + Kokkos::View::const_type inertia_matrix_terms; + Kokkos::View system_matrix_terms; + + KOKKOS_FUNCTION + void operator()(size_t ij_node) const { + const auto i_node = ij_node / num_nodes; + const auto j_node = ij_node % num_nodes; + const auto T_node = node_state_indices(i_elem, j_node); + + auto S_data = Kokkos::Array{}; + auto T_data = Kokkos::Array{}; + auto STpI_data = Kokkos::Array{}; + + const auto S = Kokkos::View(S_data.data()); + const auto T = Kokkos::View(T_data.data()); + const auto STpI = Kokkos::View(STpI_data.data()); + + KokkosBatched::SerialCopy<>::invoke( + Kokkos::subview(stiffness_matrix_terms, i_node, j_node, Kokkos::ALL, Kokkos::ALL), S + ); + KokkosBatched::SerialCopy<>::invoke( + Kokkos::subview(tangent, T_node, Kokkos::ALL, Kokkos::ALL), T + ); + KokkosBatched::SerialCopy<>::invoke( + Kokkos::subview(inertia_matrix_terms, i_node, j_node, Kokkos::ALL, Kokkos::ALL), STpI + ); + + KokkosBatched::SerialGemm< + KokkosBatched::Trans::NoTranspose, KokkosBatched::Trans::NoTranspose, + KokkosBatched::Algo::Gemm::Default>::invoke(1., S, T, 1., STpI); + + KokkosBatched::SerialCopy<>::invoke( + STpI, + Kokkos::subview(system_matrix_terms, i_elem, i_node, j_node, Kokkos::ALL, Kokkos::ALL) + ); + } +}; + +} // namespace openturbine::beams diff --git a/src/system/beams/integrate_inertia_matrix.hpp b/src/system/beams/integrate_inertia_matrix.hpp index 5b9db66d6..9ec3980a7 100644 --- a/src/system/beams/integrate_inertia_matrix.hpp +++ b/src/system/beams/integrate_inertia_matrix.hpp @@ -16,7 +16,7 @@ struct IntegrateInertiaMatrixElement { Kokkos::View::const_type qp_Guu_; double beta_prime_; double gamma_prime_; - Kokkos::View gbl_M_; + Kokkos::View gbl_M_; KOKKOS_FUNCTION void operator()(size_t ij_index) const { @@ -59,12 +59,12 @@ struct IntegrateInertiaMatrixElement { } for (auto lane = 0U; lane < width && mask[lane]; ++lane) { for (auto m = 0U; m < 6U; ++m) { - gbl_M_(i_elem, i_index, j_index + lane, m, 0) = local_M(m, 0)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 1) = local_M(m, 1)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 2) = local_M(m, 2)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 3) = local_M(m, 3)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 4) = local_M(m, 4)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 5) = local_M(m, 5)[lane]; + gbl_M_(i_index, j_index + lane, m, 0) = local_M(m, 0)[lane]; + gbl_M_(i_index, j_index + lane, m, 1) = local_M(m, 1)[lane]; + gbl_M_(i_index, j_index + lane, m, 2) = local_M(m, 2)[lane]; + gbl_M_(i_index, j_index + lane, m, 3) = local_M(m, 3)[lane]; + gbl_M_(i_index, j_index + lane, m, 4) = local_M(m, 4)[lane]; + gbl_M_(i_index, j_index + lane, m, 5) = local_M(m, 5)[lane]; } } } diff --git a/src/system/beams/integrate_stiffness_matrix.hpp b/src/system/beams/integrate_stiffness_matrix.hpp index 331910927..fd6763e17 100644 --- a/src/system/beams/integrate_stiffness_matrix.hpp +++ b/src/system/beams/integrate_stiffness_matrix.hpp @@ -17,7 +17,7 @@ struct IntegrateStiffnessMatrixElement { Kokkos::View::const_type qp_Cuu_; Kokkos::View::const_type qp_Ouu_; Kokkos::View::const_type qp_Quu_; - Kokkos::View gbl_M_; + Kokkos::View gbl_M_; KOKKOS_FUNCTION void operator()(size_t ij_index) const { @@ -67,12 +67,12 @@ struct IntegrateStiffnessMatrixElement { } for (auto lane = 0U; lane < width && mask[lane]; ++lane) { for (auto m = 0U; m < 6U; ++m) { - gbl_M_(i_elem, i_index, j_index + lane, m, 0) = local_M(m, 0)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 1) = local_M(m, 1)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 2) = local_M(m, 2)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 3) = local_M(m, 3)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 4) = local_M(m, 4)[lane]; - gbl_M_(i_elem, i_index, j_index + lane, m, 5) = local_M(m, 5)[lane]; + gbl_M_(i_index, j_index + lane, m, 0) = local_M(m, 0)[lane]; + gbl_M_(i_index, j_index + lane, m, 1) = local_M(m, 1)[lane]; + gbl_M_(i_index, j_index + lane, m, 2) = local_M(m, 2)[lane]; + gbl_M_(i_index, j_index + lane, m, 3) = local_M(m, 3)[lane]; + gbl_M_(i_index, j_index + lane, m, 4) = local_M(m, 4)[lane]; + gbl_M_(i_index, j_index + lane, m, 5) = local_M(m, 5)[lane]; } } } diff --git a/src/system/calculate_tangent_operator.hpp b/src/system/calculate_tangent_operator.hpp index b9896e6de..3a7d98334 100644 --- a/src/system/calculate_tangent_operator.hpp +++ b/src/system/calculate_tangent_operator.hpp @@ -31,12 +31,11 @@ struct CalculateTangentOperator { T(k, k) = 1.; } + KokkosBlas::serial_axpy(h, Kokkos::subview(q_delta, i_node, Kokkos::make_pair(3, 6)), rv); auto phi = KokkosBlas::serial_nrm2(rv); const auto tmp1 = (phi > 1.e-16) ? (Kokkos::cos(phi) - 1.) / (phi * phi) : 0.; const auto tmp2 = (phi > 1.e-16) ? (1. - Kokkos::sin(phi) / phi) / (phi * phi) : 0.; - KokkosBlas::serial_axpy(h, Kokkos::subview(q_delta, i_node, Kokkos::make_pair(3, 6)), rv); - VecTilde(rv, m2); KokkosBatched::SerialCopy<>::invoke(m2, m1); KokkosBatched::SerialGemm< diff --git a/src/system/masses/calculate_quadrature_point_values.hpp b/src/system/masses/calculate_quadrature_point_values.hpp index d11fb2870..e8e53e7ee 100644 --- a/src/system/masses/calculate_quadrature_point_values.hpp +++ b/src/system/masses/calculate_quadrature_point_values.hpp @@ -19,14 +19,14 @@ struct CalculateQuadraturePointValues { Kokkos::View::const_type V; Kokkos::View::const_type A; + Kokkos::View::const_type tangent; Kokkos::View::const_type node_state_indices; Kokkos::View::const_type gravity; Kokkos::View::const_type qp_Mstar; Kokkos::View::const_type node_x0; Kokkos::View residual_vector_terms; - Kokkos::View stiffness_matrix_terms; - Kokkos::View inertia_matrix_terms; + Kokkos::View system_matrix_terms; KOKKOS_FUNCTION void operator()(size_t i_elem) const { @@ -56,6 +56,8 @@ struct CalculateQuadraturePointValues { auto Fi_data = Kokkos::Array{}; auto Guu_data = Kokkos::Array{}; auto Kuu_data = Kokkos::Array{}; + auto T_data = Kokkos::Array{}; + auto STpI_data = Kokkos::Array{}; // Set up Views const auto Mstar = Kokkos::View(Mstar_data.data()); @@ -77,13 +79,13 @@ struct CalculateQuadraturePointValues { auto Fi = Kokkos::View(Fi_data.data()); auto Guu = Kokkos::View(Guu_data.data()); auto Kuu = Kokkos::View(Kuu_data.data()); + auto T = Kokkos::View(T_data.data()); + auto STpI = Kokkos::View(STpI_data.data()); // Do the math - for (auto i = 0U; i < 6U; ++i) { - for (auto j = 0U; j < 6U; ++j) { - Mstar(i, j) = qp_Mstar(i_elem, i, j); - } - } + KokkosBatched::SerialCopy<>::invoke( + Kokkos::subview(qp_Mstar, i_elem, Kokkos::ALL, Kokkos::ALL), Mstar + ); QuaternionCompose(r, r0, xr); VecTilde(omega, omega_tilde); VecTilde(omega_dot, omega_dot_tilde); @@ -109,17 +111,21 @@ struct CalculateQuadraturePointValues { for (auto i = 0U; i < 6U; ++i) { residual_vector_terms(i_elem, i) = Fi(i) - Fg(i); } + KokkosBatched::SerialCopy<>::invoke( + Kokkos::subview(tangent, index, Kokkos::ALL, Kokkos::ALL), T + ); for (auto i = 0U; i < 6U; ++i) { for (auto j = 0U; j < 6U; ++j) { - stiffness_matrix_terms(i_elem, i, j) = Kuu(i, j); - } - } - for (auto i = 0U; i < 6U; ++i) { - for (auto j = 0U; j < 6U; ++j) { - inertia_matrix_terms(i_elem, i, j) = - beta_prime * Muu(i, j) + gamma_prime * Guu(i, j); + STpI(i, j) = beta_prime * Muu(i, j) + gamma_prime * Guu(i, j); } } + KokkosBatched::SerialGemm< + KokkosBatched::Trans::NoTranspose, KokkosBatched::Trans::NoTranspose, + KokkosBatched::Algo::Gemm::Default>::invoke(1., Kuu, T, 1., STpI); + + KokkosBatched::SerialCopy<>::invoke( + STpI, Kokkos::subview(system_matrix_terms, i_elem, Kokkos::ALL, Kokkos::ALL) + ); } }; diff --git a/tests/regression_tests/regression/test_rotor.cpp b/tests/regression_tests/regression/test_rotor.cpp index 5e0e82ff7..a47fc8961 100644 --- a/tests/regression_tests/regression/test_rotor.cpp +++ b/tests/regression_tests/regression/test_rotor.cpp @@ -76,7 +76,7 @@ TEST(RotorTest, IEA15Rotor) { // Build vector of nodes (straight along x axis, no rotation) // Calculate displacement, velocity, acceleration assuming a // 1 rad/s angular velocity around the z axis - constexpr size_t num_blades = 3; + constexpr size_t num_blades = 3000; auto blade_list = std::array{}; std::iota(std::begin(blade_list), std::end(blade_list), 0); @@ -198,7 +198,7 @@ TEST(RotorTest, IEA15RotorHub) { constexpr size_t max_iter(6); constexpr double step_size(0.01); // seconds constexpr double rho_inf(0.0); - constexpr double t_end(0.1); + constexpr double t_end(100.); constexpr auto num_steps = static_cast(t_end / step_size + 1.0); constexpr auto num_nodes = node_xi.size(); diff --git a/tests/unit_tests/system/beams/test_calculate_Puu.cpp b/tests/unit_tests/system/beams/test_calculate_Puu.cpp index e7cd8f837..9f9bf8edc 100644 --- a/tests/unit_tests/system/beams/test_calculate_Puu.cpp +++ b/tests/unit_tests/system/beams/test_calculate_Puu.cpp @@ -6,6 +6,16 @@ namespace { +struct TestFunctionObject { + Kokkos::View::const_type Cuu; + Kokkos::View::const_type x0pupSS; + Kokkos::View::const_type N_tilde; + Kokkos::View Puu; + + KOKKOS_FUNCTION + void operator()(size_t) const { openturbine::beams::CalculatePuu(Cuu, x0pupSS, N_tilde, Puu); } +}; + void TestCalculatePuu() { const auto Cuu = Kokkos::View("Cuu"); constexpr auto Cuu_data = std::array{1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., @@ -34,10 +44,7 @@ void TestCalculatePuu() { const auto Puu = Kokkos::View("Puu"); - Kokkos::parallel_for( - "CalculatePuu", 1, - KOKKOS_LAMBDA(size_t) { openturbine::beams::CalculatePuu(Cuu, x0pupSS, N_tilde, Puu); } - ); + Kokkos::parallel_for("CalculatePuu", 1, TestFunctionObject{Cuu, x0pupSS, N_tilde, Puu}); constexpr auto Puu_exact_data = std::array{0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., diff --git a/tests/unit_tests/system/beams/test_integrate_inertia_matrix.cpp b/tests/unit_tests/system/beams/test_integrate_inertia_matrix.cpp index aa9c2bd54..f25ab8a02 100644 --- a/tests/unit_tests/system/beams/test_integrate_inertia_matrix.cpp +++ b/tests/unit_tests/system/beams/test_integrate_inertia_matrix.cpp @@ -27,7 +27,7 @@ inline void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Muu() { 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"); + const auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateInertiaMatrixElement{ @@ -44,7 +44,7 @@ inline void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Muu() { 450150., 450300., 450450., 450600., 450750., 450900., 600150., 600300., 600450., 600600., 600750., 600900., 750150., 750300., 750450., 750600., 750750., 750900.}; const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -74,7 +74,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Guu() { 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"); + const auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateInertiaMatrixElement{ @@ -90,7 +90,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Guu() { 600150., 600300., 600450., 600600., 600750., 600900., 750150., 750300., 750450., 750600., 750750., 750900., 900150., 900300., 900450., 900600., 900750., 900900.}; const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -101,73 +101,6 @@ TEST(IntegrateInertiaMatrixTests, OneElementOneNodeOneQP_Guu) { IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_Guu(); } -void IntegrateInertiaMatrix_TestTwoElementsOneNodeOneQP() { - constexpr auto number_of_nodes = size_t{1U}; - constexpr auto number_of_simd_nodes = size_t{1U}; - constexpr auto number_of_qps = size_t{1U}; - - 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::RangePolicy(0, number_of_nodes * number_of_simd_nodes); - const auto integrator = beams::IntegrateInertiaMatrixElement{ - 0U, number_of_nodes, number_of_qps, qp_weights, qp_jacobian, - shape_interp, qp_Muu, qp_Guu, 1., 0., - gbl_M - }; - Kokkos::parallel_for(policy, integrator); - } - - { - 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::RangePolicy(0, number_of_nodes * number_of_simd_nodes); - const auto integrator = beams::IntegrateInertiaMatrixElement{ - 1U, number_of_nodes, number_of_qps, qp_weights, qp_jacobian, - shape_interp, qp_Muu, qp_Guu, 1., 0., - gbl_M - }; - Kokkos::parallel_for(policy, integrator); - } - - constexpr auto exact_M_data = - std::array{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 exact_M = - Kokkos::View(exact_M_data.data()); - - auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); - Kokkos::deep_copy(gbl_M_mirror, gbl_M); - CompareWithExpected(gbl_M_mirror, exact_M); -} - -TEST(IntegrateInertiaMatrixTests, TwoElementsOneNodeOneQP) { - IntegrateInertiaMatrix_TestTwoElementsOneNodeOneQP(); -} - void IntegrateInertiaMatrix_TestOneElementTwoNodesOneQP() { constexpr auto number_of_nodes = size_t{2U}; constexpr auto simd_width = Kokkos::Experimental::native_simd::size(); @@ -185,7 +118,7 @@ void IntegrateInertiaMatrix_TestOneElementTwoNodesOneQP() { 0404., 0405., 0406., 0501., 0502., 0503., 0504., 0505., 0506.}); const auto qp_Guu = QpMatrixView("Guu"); - const auto gbl_M = Kokkos::View("global_M"); + const auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateInertiaMatrixElement{ @@ -211,7 +144,7 @@ void IntegrateInertiaMatrix_TestOneElementTwoNodesOneQP() { }; const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -244,7 +177,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeTwoQPs() { ); const auto qp_Guu = QpMatrixView("Guu"); - const auto gbl_M = Kokkos::View("global_M"); + const auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateInertiaMatrixElement{ @@ -260,7 +193,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeTwoQPs() { 31031., 32032., 33033., 34034., 35035., 36036., 41041., 42042., 43043., 44044., 45045., 46046., 51051., 52052., 53053., 54054., 55055., 56056.}; const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -288,7 +221,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_WithMultiplicationFactor( const auto qp_Guu = QpMatrixView("Guu"); const auto multiplication_factor = 5.; - const auto gbl_M = Kokkos::View("global_M"); + const auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateInertiaMatrixElement{ @@ -303,7 +236,7 @@ void IntegrateInertiaMatrix_TestOneElementOneNodeOneQP_WithMultiplicationFactor( 15005., 15010., 15015., 15020., 15025., 15030., 20005., 20010., 20015., 20020., 20025., 20030., 25005., 25010., 25015., 25020., 25025., 25030.}; const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); diff --git a/tests/unit_tests/system/beams/test_integrate_stiffness_matrix.cpp b/tests/unit_tests/system/beams/test_integrate_stiffness_matrix.cpp index 5ff82b5ea..ac620c320 100644 --- a/tests/unit_tests/system/beams/test_integrate_stiffness_matrix.cpp +++ b/tests/unit_tests/system/beams/test_integrate_stiffness_matrix.cpp @@ -24,7 +24,7 @@ void TestIntegrateStiffnessMatrix_1Element1Node1QP( 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"); + auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateStiffnessMatrixElement{0U, @@ -43,7 +43,7 @@ void TestIntegrateStiffnessMatrix_1Element1Node1QP( Kokkos::parallel_for(policy, integrator); const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -196,95 +196,6 @@ TEST(IntegrateStiffnessMatrixTests, OneElementOneNodeOneQP_Ouu) { TestIntegrateStiffnessMatrix_1Element1Node1QP_Ouu(); } -void TestIntegrateStiffnessMatrix_2Elements1Node1QP() { - constexpr auto number_of_nodes = size_t{1U}; - constexpr auto number_of_simd_nodes = size_t{1U}; - constexpr auto number_of_qps = size_t{1U}; - - 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; - const auto qp_Kuu = QpMatrixView("Kuu"); - const auto qp_Quu = QpMatrixView("Quu"); - const auto qp_Cuu = QpMatrixView("Cuu"); - const auto qp_Ouu = QpMatrixView("Ouu"); - - 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::RangePolicy(0, number_of_nodes * number_of_simd_nodes); - const auto integrator = beams::IntegrateStiffnessMatrixElement{0U, - number_of_nodes, - number_of_qps, - qp_weights, - qp_jacobian, - shape_interp, - shape_interp_deriv, - qp_Kuu, - qp_Puu, - qp_Cuu, - qp_Ouu, - qp_Quu, - gbl_M}; - Kokkos::parallel_for(policy, integrator); - } - - { - 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::RangePolicy(0, number_of_nodes * number_of_simd_nodes); - const auto integrator = beams::IntegrateStiffnessMatrixElement{1U, - number_of_nodes, - number_of_qps, - qp_weights, - qp_jacobian, - shape_interp, - shape_interp_deriv, - qp_Kuu, - qp_Puu, - qp_Cuu, - qp_Ouu, - qp_Quu, - gbl_M}; - Kokkos::parallel_for(policy, integrator); - } - - constexpr auto exact_M_data = - std::array{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 exact_M = - Kokkos::View(exact_M_data.data()); - - auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); - Kokkos::deep_copy(gbl_M_mirror, gbl_M); - CompareWithExpected(gbl_M_mirror, exact_M); -} - -TEST(IntegrateStiffnessMatrixTests, TwoElementsOneNodeOneQP) { - TestIntegrateStiffnessMatrix_2Elements1Node1QP(); -} - void TestIntegrateStiffnessMatrix_1Element2Nodes1QP( const Kokkos::View& qp_Kuu, const Kokkos::View& qp_Puu, @@ -302,7 +213,7 @@ void TestIntegrateStiffnessMatrix_1Element2Nodes1QP( 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"); + auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateStiffnessMatrixElement{0U, @@ -321,7 +232,7 @@ void TestIntegrateStiffnessMatrix_1Element2Nodes1QP( Kokkos::parallel_for(policy, integrator); const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M); @@ -496,7 +407,7 @@ void TestIntegrateStiffnessMatrix_1Element1Node2QPs( 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"); + auto gbl_M = Kokkos::View("global_M"); const auto policy = Kokkos::RangePolicy(0, number_of_nodes * number_of_simd_nodes); const auto integrator = beams::IntegrateStiffnessMatrixElement{0U, @@ -515,7 +426,7 @@ void TestIntegrateStiffnessMatrix_1Element1Node2QPs( Kokkos::parallel_for(policy, integrator); const auto exact_M = - Kokkos::View(exact_M_data.data()); + Kokkos::View::const_type(exact_M_data.data()); auto gbl_M_mirror = Kokkos::create_mirror(gbl_M); Kokkos::deep_copy(gbl_M_mirror, gbl_M);