Skip to content

Commit

Permalink
clang-tidy and format
Browse files Browse the repository at this point in the history
  • Loading branch information
ddement committed Feb 12, 2025
1 parent 6e71432 commit 6bcf77e
Show file tree
Hide file tree
Showing 11 changed files with 24 additions and 55 deletions.
40 changes: 0 additions & 40 deletions src/elements/masses/masses.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,30 +25,7 @@ struct Masses {
View_3 gravity;

Kokkos::View<double* [7]> node_x0; //< Initial position/rotation
// Kokkos::View<double* [7]> node_u; //< State: translation/rotation displacement
// Kokkos::View<double* [6]> node_u_dot; //< State: translation/rotation velocity
// Kokkos::View<double* [6]> node_u_ddot; //< State: translation/rotation acceleration
//
Kokkos::View<double* [6][6]> qp_Mstar; //< Mass matrix in material frame
// Kokkos::View<double* [7]> qp_x; //< Current position/orientation
// Kokkos::View<double* [3]> qp_x0;
// Kokkos::View<double* [4]> qp_r0;
// Kokkos::View<double* [3]> qp_u;
// Kokkos::View<double* [3]> qp_u_ddot;
// Kokkos::View<double* [4]> qp_r;
// Kokkos::View<double* [3]> qp_omega;
// Kokkos::View<double* [3]> qp_omega_dot;
// Kokkos::View<double* [3][3]> qp_eta_tilde;
// Kokkos::View<double* [3][3]> qp_omega_tilde;
// Kokkos::View<double* [3][3]> qp_omega_dot_tilde;
// Kokkos::View<double* [3]> qp_eta; //< Offset between mass center and elastic axis
// Kokkos::View<double* [3][3]> qp_rho; //< Rotational inertia part of mass matrix
// Kokkos::View<double* [6]> qp_Fi; //< Inertial force
// Kokkos::View<double* [6]> qp_Fg; //< Gravity force
// Kokkos::View<double* [6][6]> qp_RR0; //< Global rotation
// Kokkos::View<double* [6][6]> qp_Muu; //< Mass matrix in global/inertial frame
// Kokkos::View<double* [6][6]> qp_Guu; //< Gyroscopic/inertial damping matrix
// Kokkos::View<double* [6][6]> qp_Kuu; //< Inertia stiffness matrix

Kokkos::View<double* [6]> residual_vector_terms;
Kokkos::View<double* [6][6]> stiffness_matrix_terms;
Expand All @@ -62,24 +39,7 @@ struct Masses {
element_freedom_table("element_freedom_table", num_elems),
gravity("gravity"),
node_x0("node_x0", num_elems),
// node_u("node_u", num_elems),
// node_u_dot("node_u_dot", num_elems),
// node_u_ddot("node_u_ddot", num_elems),
qp_Mstar("qp_Mstar", num_elems),
// qp_r("qp_r", num_elems),
// qp_omega("qp_omega", num_elems),
// qp_omega_dot("qp_omega_dot", num_elems),
// qp_eta_tilde("qp_eta_tilde", num_elems),
// qp_omega_tilde("qp_omega_tilde", num_elems),
// qp_omega_dot_tilde("qp_omega_dot_tilde", num_elems),
// qp_eta("qp_eta", num_elems),
// qp_rho("qp_rho", num_elems),
// qp_Fi("qp_Fi", num_elems),
// qp_Fg("qp_Fg", num_elems),
// qp_RR0("qp_RR0", num_elems),
// qp_Muu("qp_Muu", num_elems),
// qp_Guu("qp_Guu", num_elems),
// qp_Kuu("qp_Kuu", 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) {
Expand Down
6 changes: 3 additions & 3 deletions src/elements/springs/springs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@ struct Springs {
Kokkos::View<FreedomSignature* [2]> element_freedom_signature;
Kokkos::View<size_t* [2][3]> element_freedom_table; //< Only translational DOFs for springs

Kokkos::View<double* [3]> x0; //< Initial distance vector between nodes
Kokkos::View<double*> l_ref; //< Initial length of springs
Kokkos::View<double*> k; //< Spring stiffness coefficients
Kokkos::View<double* [3]> x0; //< Initial distance vector between nodes
Kokkos::View<double*> l_ref; //< Initial length of springs
Kokkos::View<double*> k; //< Spring stiffness coefficients

Kokkos::View<double* [2][3]> residual_vector_terms;
Kokkos::View<double* [2][2][3][3]> stiffness_matrix_terms;
Expand Down
3 changes: 2 additions & 1 deletion src/step/update_system_variables_masses.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@ inline void UpdateSystemVariablesMasses(
masses::CalculateQuadraturePointValues{
parameters.beta_prime, parameters.gamma_prime, state.q, state.v, state.vd,
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.stiffness_matrix_terms, masses.inertia_matrix_terms
}
);
}

Expand Down
3 changes: 2 additions & 1 deletion src/step/update_system_variables_springs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@ inline void UpdateSystemVariablesSprings(const Springs& springs, State& state) {
"Calculate System Variables Springs", springs.num_elems,
springs::CalculateQuadraturePointValues{
state.q, springs.node_state_indices, springs.x0, springs.l_ref, springs.k,
springs.residual_vector_terms, springs.stiffness_matrix_terms}
springs.residual_vector_terms, springs.stiffness_matrix_terms
}
);
}

Expand Down
3 changes: 2 additions & 1 deletion src/system/masses/calculate_gyroscopic_matrix.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@ namespace openturbine::masses {
KOKKOS_FUNCTION
inline void CalculateGyroscopicMatrix(
double mass, const Kokkos::View<double[3]>::const_type& omega,
const Kokkos::View<double[3]>::const_type& eta, const Kokkos::View<double[3][3]>::const_type rho,
const Kokkos::View<double[3]>::const_type& eta,
const Kokkos::View<double[3][3]>::const_type& rho,
const Kokkos::View<double[3][3]>::const_type& omega_tilde, const Kokkos::View<double[6][6]>& Guu
) {
using NoTranspose = KokkosBatched::Trans::NoTranspose;
Expand Down
3 changes: 2 additions & 1 deletion src/system/masses/calculate_quadrature_point_values.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ struct CalculateQuadraturePointValues {
const auto x0_data =
Kokkos::Array<double, 3>{node_x0(i_elem, 0), node_x0(i_elem, 1), node_x0(i_elem, 2)};
const auto r0_data = Kokkos::Array<double, 4>{
node_x0(i_elem, 3), node_x0(i_elem, 4), node_x0(i_elem, 5), node_x0(i_elem, 6)};
node_x0(i_elem, 3), node_x0(i_elem, 4), node_x0(i_elem, 5), node_x0(i_elem, 6)
};
const auto u_data = Kokkos::Array<double, 3>{Q(index, 0), Q(index, 1), Q(index, 2)};
const auto r_data =
Kokkos::Array<double, 4>{Q(index, 3), Q(index, 4), Q(index, 5), Q(index, 6)};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ int main() {
constexpr auto rho_inf = 0.0; // Time stepping damping factor
constexpr auto max_iter = 5; // Maximum number of nonlinear steps per time ste[
const auto n_steps{
static_cast<size_t>(ceil(t_end / time_step)) + 1}; // Number of time steps
static_cast<size_t>(ceil(t_end / time_step)) + 1
}; // Number of time steps

// Define gravity vector
constexpr auto gravity = std::array{0., 0., -9.8124}; // m/s/s
Expand Down
3 changes: 2 additions & 1 deletion tests/unit_tests/math/test_quaternion_operations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -418,7 +418,8 @@ TEST(QuaternionTest, CheckTangentTwistToQuaternion) {
45.,
{0., 0., 1.},
{0.65328148243818829, 0.27059805007309845, -0.65328148243818818,
0.27059805007309851},
0.27059805007309851
},
},
}) {
const auto q_act = TangentTwistToQuaternion(td.tan, td.twist);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,8 @@ TEST(CalculateInertiaStiffnessMatrixMassesTests, OneNode) {
Kokkos::parallel_for(
"CalculateInertiaStiffnessMatrix", 1,
ExecuteCalculateInertiaStiffnessMatrix{
mass, u_ddot, omega, omega_dot, omega_tilde, omega_dot_tilde, rho, eta, Kuu}
mass, u_ddot, omega, omega_dot, omega_tilde, omega_dot_tilde, rho, eta, Kuu
}
);

constexpr auto Kuu_exact_data = std::array<double, 36>{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,8 @@ TEST(CalculateInertialForcesTestsMasses, OneNode) {
Kokkos::parallel_for(
"CalculateInertialForces", 1,
ExecuteCalculateInertialForces{
mass, u_ddot, omega, omega_dot, eta_tilde, omega_tilde, omega_dot_tilde, rho, eta, FI}
mass, u_ddot, omega, omega_dot, eta_tilde, omega_tilde, omega_dot_tilde, rho, eta, FI
}
);

constexpr auto FI_exact_data = std::array{-2984., 32., 2922., 20624., -2248., 22100.};
Expand Down
9 changes: 5 additions & 4 deletions tests/unit_tests/system/masses/test_rotate_section_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,11 @@ TEST(RotateSectionMatrixMassesTests, OneNode) {

Kokkos::parallel_for("RotateSectionMatrix", 1, ExecuteRotateSectionMatrix{xr, Cstar, Cuu});

constexpr auto Cuu_exact_data = std::array{
2052., 9000., 12564., 2160., 9540., 13320., 2700., 7200., 9900., 3240., 9900., 13680.,
3564., 9000., 12348., 4320., 12780., 17640., 2700., 12240., 17100., 2808., 12780., 17856.,
5940., 23400., 32580., 6480., 26100., 36360., 8100., 31680., 44100., 8856., 35460., 49392.};
constexpr auto Cuu_exact_data =
std::array{2052., 9000., 12564., 2160., 9540., 13320., 2700., 7200., 9900.,
3240., 9900., 13680., 3564., 9000., 12348., 4320., 12780., 17640.,
2700., 12240., 17100., 2808., 12780., 17856., 5940., 23400., 32580.,
6480., 26100., 36360., 8100., 31680., 44100., 8856., 35460., 49392.};
const auto Cuu_exact =
Kokkos::View<const double[6][6], Kokkos::HostSpace>(Cuu_exact_data.data());

Expand Down

0 comments on commit 6bcf77e

Please sign in to comment.