Skip to content

Commit

Permalink
Fix clang-tidy checks in .cpp files
Browse files Browse the repository at this point in the history
  • Loading branch information
ddement committed Jul 31, 2024
1 parent 4656815 commit 8afd8c1
Show file tree
Hide file tree
Showing 37 changed files with 2,398 additions and 2,389 deletions.
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ Checks: "bugprone*,
portability*,
readability*,
-cppcoreguidelines-avoid-magic-numbers,
-cppcoreguidelines-pro-bounds-constant-array-index,
-modernize-use-trailing-return-type,
-readability-else-after-return,
-readability-magic-numbers,
Expand Down
83 changes: 50 additions & 33 deletions src/restruct_poc/system/integrate_inertia_matrix.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,51 +7,68 @@

namespace openturbine {

struct IntegrateInertiaMatrixElement {
const int i_elem;
const size_t num_qps;
const size_t first_node;
const size_t first_qp;
View_N::const_type qp_weight_;
View_N::const_type qp_jacobian_;
View_NxN::const_type shape_interp_;
View_Nx6x6::const_type qp_Muu_;
View_Nx6x6::const_type qp_Guu_;
double beta_prime_;
double gamma_prime_;
Kokkos::View<double***> 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<double, 36>{};
const auto local_M = Kokkos::View<double[6][6]>(local_M_data.data());
for (auto k = 0u; k < num_qps; ++k) {
const auto k_qp = first_qp + k;
const auto w = qp_weight_(k_qp);
const auto jacobian = qp_jacobian_(k_qp);
const auto phi_i = shape_interp_(i, k);
const auto phi_j = shape_interp_(j, 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);
}
}
}
for (auto m = 0u; m < 6u; ++m) {
for (auto n = 0u; n < 6u; ++n) {
gbl_M_(i_elem, i_index * 6u + m, j_index * 6u + n) = local_M(m, n);
}
}
}
};
struct IntegrateInertiaMatrix {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices;
View_N::const_type qp_weight_;
View_N::const_type qp_jacobian_;
Kokkos::View<const double**, Kokkos::MemoryTraits<Kokkos::RandomAccess>> shape_interp_;
View_NxN::const_type shape_interp_;
View_Nx6x6::const_type qp_Muu_;
View_Nx6x6::const_type qp_Guu_;
double beta_prime_;
double gamma_prime_;
Kokkos::View<double***> gbl_M_;

KOKKOS_FUNCTION
void operator()(Kokkos::TeamPolicy<>::member_type member) const {
auto i_elem = member.league_rank();
void operator()(const Kokkos::TeamPolicy<>::member_type& member) const {
const auto i_elem = member.league_rank();
const auto idx = elem_indices(i_elem);
Kokkos::parallel_for(
Kokkos::TeamThreadMDRange(member, idx.num_nodes, idx.num_nodes),
[&](size_t i_index, size_t j_index) {
const auto i = i_index + idx.node_range.first;
const auto j = j_index + idx.node_range.first;
auto local_M_data = Kokkos::Array<double, 36>{};
auto local_M = Kokkos::View<double[6][6], Kokkos::MemoryTraits<Kokkos::Unmanaged>>(
local_M_data.data()
);
for (auto k = 0u; k < idx.num_qps; ++k) {
const auto k_qp = idx.qp_range.first + k;
const auto w = qp_weight_(k_qp);
const auto jacobian = qp_jacobian_(k_qp);
const auto phi_i = shape_interp_(i, k);
const auto phi_j = shape_interp_(j, 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);
}
}
}
for (auto m = 0u; m < 6u; ++m) {
for (auto n = 0u; n < 6u; ++n) {
gbl_M_(i_elem, i_index * 6u + m, j_index * 6u + n) = local_M(m, n);
}
}
}
);
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_};
Kokkos::parallel_for(node_range, element_integrator);
}
};
} // namespace openturbine
110 changes: 71 additions & 39 deletions src/restruct_poc/system/integrate_stiffness_matrix.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,63 @@

namespace openturbine {

struct IntegrateStiffnessMatrixElement {
const int i_elem;
const size_t num_qps;
const size_t first_node;
const size_t first_qp;
View_N::const_type qp_weight_;
View_N::const_type qp_jacobian_;
View_NxN::const_type shape_interp_;
View_NxN::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<double***> gbl_M_;

KOKKOS_FUNCTION
void operator()(size_t i_index, size_t j_index) const {
auto local_M_data = Kokkos::Array<double, 36>{};
const auto local_M = Kokkos::View<double[6][6]>(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_(k_qp);
const auto jacobian = qp_jacobian_(k_qp);
const auto phi_i = shape_interp_(i, k);
const auto phi_j = shape_interp_(j, k);
const auto phi_prime_i = shape_deriv_(i, k);
const auto phi_prime_j = shape_deriv_(j, 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);
}
}
}
for (auto m = 0u; m < 6u; ++m) {
for (auto n = 0u; n < 6u; ++n) {
gbl_M_(i_elem, i_index * 6u + m, j_index * 6u + n) = local_M(m, n);
}
}
}
};

struct IntegrateStiffnessMatrix {
Kokkos::View<Beams::ElemIndices*>::const_type elem_indices;
View_N::const_type qp_weight_;
View_N::const_type qp_jacobian_;
Kokkos::View<const double**, Kokkos::MemoryTraits<Kokkos::RandomAccess>> shape_interp_;
Kokkos::View<const double**, Kokkos::MemoryTraits<Kokkos::RandomAccess>> shape_deriv_;
View_NxN::const_type shape_interp_;
View_NxN::const_type shape_deriv_;
View_Nx6x6::const_type qp_Kuu_;
View_Nx6x6::const_type qp_Puu_;
View_Nx6x6::const_type qp_Cuu_;
Expand All @@ -24,43 +75,24 @@ struct IntegrateStiffnessMatrix {
void operator()(Kokkos::TeamPolicy<>::member_type member) const {
const auto i_elem = member.league_rank();
const auto idx = elem_indices(i_elem);
Kokkos::parallel_for(
Kokkos::TeamThreadMDRange(member, idx.num_nodes, idx.num_nodes),
[&](size_t i_index, size_t j_index) {
auto local_M_data = Kokkos::Array<double, 36>{};
auto local_M = Kokkos::View<double[6][6], Kokkos::MemoryTraits<Kokkos::Unmanaged>>(
local_M_data.data()
);
const auto i = i_index + idx.node_range.first;
const auto j = j_index + idx.node_range.first;
for (auto k = 0u; k < idx.num_qps; ++k) {
const auto k_qp = idx.qp_range.first + k;
const auto w = qp_weight_(k_qp);
const auto jacobian = qp_jacobian_(k_qp);
const auto phi_i = shape_interp_(i, k);
const auto phi_j = shape_interp_(j, k);
const auto phi_prime_i = shape_deriv_(i, k);
const auto phi_prime_j = shape_deriv_(j, 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);
}
}
}
for (auto m = 0u; m < 6u; ++m) {
for (auto n = 0u; n < 6u; ++n) {
gbl_M_(i_elem, i_index * 6u + m, j_index * 6u + n) = local_M(m, n);
}
}
}
);

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_,
gbl_M_};
Kokkos::parallel_for(node_range, element_integrator);
}
};

Expand Down
37 changes: 0 additions & 37 deletions tests/unit_tests/OpenTurbineTestEnv.hpp

This file was deleted.

64 changes: 30 additions & 34 deletions tests/unit_tests/restruct_poc/iea15_rotor_data.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,54 +6,50 @@
namespace openturbine::restruct_poc::tests {

// Node location from [-1, 1]
static std::vector<double> node_xi = {
-1, -0.93400143040805916, -0.78448347366314441, -0.56523532699620493, -0.29575813558693936,
0, 0.29575813558693936, 0.56523532699620493, 0.78448347366314441, 0.93400143040805916,
1};
static constexpr auto node_xi = std::array{
-1., -0.93400143040805916, -0.78448347366314441, -0.56523532699620493, -0.29575813558693936,
0., 0.29575813558693936, 0.56523532699620493, 0.78448347366314441, 0.93400143040805916,
1.};

// Node Coordinates
static std::vector<std::array<double, 3>> node_coords = {
std::array<double, 3>{0.0, 0.0, 0.0},
std::array<double, 3>{3.860916321128559, 0.0, -0.05469664173133543},
std::array<double, 3>{12.607716790706057, 0.0, -0.1464345809622239},
std::array<double, 3>{25.433733370721974, 0.0, -0.23918824799640123},
std::array<double, 3>{41.19814906816406, 0.0, -0.24301416634938658},
std::array<double, 3>{58.50000000000004, 0.0, 0.054037571255432564},
std::array<double, 3>{75.80185093183596, 0.0, 0.785406045211315},
std::array<double, 3>{91.56626662927795, 0.0, 1.8044719127555426},
std::array<double, 3>{104.39228320929396, 0.0, 2.8241493860344002},
std::array<double, 3>{113.13908367887151, 0.0, 3.6162361535819865},
std::array<double, 3>{117.0, 0.0, 4.000000000000026},
static constexpr auto node_coords = std::array{
std::array{0.0, 0.0, 0.0},
std::array{3.860916321128559, 0.0, -0.05469664173133543},
std::array{12.607716790706057, 0.0, -0.1464345809622239},
std::array{25.433733370721974, 0.0, -0.23918824799640123},
std::array{41.19814906816406, 0.0, -0.24301416634938658},
std::array{58.50000000000004, 0.0, 0.054037571255432564},
std::array{75.80185093183596, 0.0, 0.785406045211315},
std::array{91.56626662927795, 0.0, 1.8044719127555426},
std::array{104.39228320929396, 0.0, 2.8241493860344002},
std::array{113.13908367887151, 0.0, 3.6162361535819865},
std::array{117.0, 0.0, 4.000000000000026},
};

// Node Rotation
static std::vector<std::array<double, 4>> node_rotation = {
std::array<double, 4>{
static constexpr auto node_rotation = std::array{
std::array{
0.9907227443578874, -0.13566457224703346, 0.007899216411874178, 0.0010816788266006607},
std::array<double, 4>{
std::array{
0.9909252982620628, -0.13426519082440538, 0.006260373215503113, 0.0008482478001981521},
std::array<double, 4>{
0.9935167796154206, -0.11359784336864302, 0.00443636138538857, 0.0005072496973620513},
std::array<double, 4>{
0.9974116582281851, -0.0718560788024431, 0.002579425796743258, 0.0001858284107537662},
std::array<double, 4>{
std::array{0.9935167796154206, -0.11359784336864302, 0.00443636138538857, 0.0005072496973620513},
std::array{0.9974116582281851, -0.0718560788024431, 0.002579425796743258, 0.0001858284107537662},
std::array{
0.9993668285851437, -0.035436934270507724, -0.0031863532939427376, -0.00011298613182902174},
std::array<double, 4>{
std::array{
0.9997694376789568, -0.01571896564353078, -0.014626439008272178, -0.00022996551364081713},
std::array<double, 4>{
std::array{
0.9996244263618369, -0.00011737820053802088, -0.027404241145705933, -3.21786905958282e-06},
std::array<double, 4>{
std::array{
0.9992258769980531, 0.014354416057417973, -0.03662404497855903, 0.0005261240640677012},
std::array<double, 4>{
0.998912306432686, 0.018760692766230495, -0.04268018194796855, 0.000801581655943506},
std::array<double, 4>{
0.9987446969974336, 0.014486925484536069, -0.0479445051145804, 0.0006954414627441799},
std::array<double, 4>{
std::array{0.998912306432686, 0.018760692766230495, -0.04268018194796855, 0.000801581655943506},
std::array{0.9987446969974336, 0.014486925484536069, -0.0479445051145804, 0.0006954414627441799},
std::array{
0.9986289781304243, 0.010827457815091479, -0.051211540599741034, 0.000555252058204468},
};

// Element quadrature
static BeamQuadrature trapz_quadrature{
static const BeamQuadrature trapz_quadrature{
{-1.0, 0.005}, {-0.99, 0.01}, {-0.98, 0.01}, {-0.97, 0.01}, {-0.96, 0.01}, {-0.95, 0.01},
{-0.94, 0.01}, {-0.93, 0.01}, {-0.92, 0.01}, {-0.91, 0.01}, {-0.9, 0.0175}, {-0.875, 0.025},
{-0.85, 0.025}, {-0.825, 0.025}, {-0.8, 0.0375}, {-0.75, 0.05}, {-0.7, 0.05}, {-0.65, 0.05},
Expand All @@ -65,7 +61,7 @@ static BeamQuadrature trapz_quadrature{
{0.9, 0.05}, {0.95, 0.05}, {1.0, 0.025},
};

static std::vector<BeamSection> material_sections = {
static const std::vector<BeamSection> material_sections = {
BeamSection{
0.0,
{{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ TEST(ComputeNumberOfNonZeros, SingleElement) {

elem_indices_host(0).num_nodes = 5;
Kokkos::deep_copy(elem_indices, elem_indices_host);
auto num_non_zero = size_t{0u};
auto num_non_zero = size_t{0U};
Kokkos::parallel_reduce(1, ComputeNumberOfNonZeros{elem_indices}, num_non_zero);
constexpr auto num_dof = 5 * 6;
constexpr auto expected_num_non_zero = num_dof * num_dof;
Expand All @@ -27,7 +27,7 @@ TEST(ComputeNumberOfNonZeros, TwoElements) {
elem_indices_host(0).num_nodes = 5;
elem_indices_host(1).num_nodes = 3;
Kokkos::deep_copy(elem_indices, elem_indices_host);
auto num_non_zero = size_t{0u};
auto num_non_zero = size_t{0U};
Kokkos::parallel_reduce(2, ComputeNumberOfNonZeros{elem_indices}, num_non_zero);
constexpr auto num_dof_elem1 = 5 * 6;
constexpr auto num_dof_elem2 = 3 * 6;
Expand Down
Loading

0 comments on commit 8afd8c1

Please sign in to comment.