diff --git a/src/beams/create_beams.hpp b/src/beams/create_beams.hpp index 5aadba35..0476aba4 100644 --- a/src/beams/create_beams.hpp +++ b/src/beams/create_beams.hpp @@ -91,14 +91,16 @@ inline Beams CreateBeams(const BeamsInput& beams_input) { "InterpolateQPPosition", beams.num_elems, InterpolateQPPosition{ beams.num_nodes_per_element, beams.num_qps_per_element, beams.shape_interp, - beams.node_x0, beams.qp_x0} + beams.node_x0, beams.qp_x0 + } ); Kokkos::parallel_for( "InterpolateQPRotation", beams.num_elems, InterpolateQPRotation{ beams.num_nodes_per_element, beams.num_qps_per_element, beams.shape_interp, - beams.node_x0, beams.qp_r0} + beams.node_x0, beams.qp_r0 + } ); Kokkos::parallel_for( @@ -120,7 +122,8 @@ inline Beams CreateBeams(const BeamsInput& beams_input) { beams.num_nodes_per_element, beams.num_qps_per_element, beams.shape_interp, beams.shape_deriv, beams.qp_jacobian, beams.node_u, beams.node_u_dot, beams.node_u_ddot, beams.qp_x0, beams.qp_r0, beams.qp_u, beams.qp_u_prime, beams.qp_r, beams.qp_r_prime, - beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x} + beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x + } ); return beams; } diff --git a/src/beams/interpolate_to_quadrature_points.hpp b/src/beams/interpolate_to_quadrature_points.hpp index 1302b753..ade23d87 100644 --- a/src/beams/interpolate_to_quadrature_points.hpp +++ b/src/beams/interpolate_to_quadrature_points.hpp @@ -55,27 +55,30 @@ struct InterpolateToQuadraturePoints { Kokkos::TeamThreadRange(member, num_qps), InterpolateQPVector{ i_elem, num_nodes, shape_interp, - Kokkos::subview(node_u_dot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(0, 3)), qp_u_dot} + Kokkos::subview(node_u_dot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(0, 3)), qp_u_dot + } ); Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_qps), InterpolateQPVector{ i_elem, num_nodes, shape_interp, - Kokkos::subview(node_u_dot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(3, 6)), qp_omega} + Kokkos::subview(node_u_dot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(3, 6)), qp_omega + } ); Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_qps), InterpolateQPVector{ i_elem, num_nodes, shape_interp, - Kokkos::subview(node_u_ddot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(0, 3)), - qp_u_ddot} + Kokkos::subview(node_u_ddot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(0, 3)), qp_u_ddot + } ); Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_qps), InterpolateQPVector{ i_elem, num_nodes, shape_interp, Kokkos::subview(node_u_ddot, Kokkos::ALL, Kokkos::ALL, Kokkos::pair(3, 6)), - qp_omega_dot} + qp_omega_dot + } ); Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_qps), diff --git a/src/constraints/calculate_constraint_force.hpp b/src/constraints/calculate_constraint_force.hpp index a438c530..8127f78f 100644 --- a/src/constraints/calculate_constraint_force.hpp +++ b/src/constraints/calculate_constraint_force.hpp @@ -23,7 +23,8 @@ struct CalculateConstraintForce { case ConstraintType::kRevoluteJoint: { // Applies the torque from a revolute joint constraint to the system residual CalculateRevoluteJointForce{ - target_node_index, axes, inputs, node_u, system_residual_terms}(i_constraint); + target_node_index, axes, inputs, node_u, system_residual_terms + }(i_constraint); } break; default: { // Do nothing diff --git a/src/constraints/calculate_constraint_output.hpp b/src/constraints/calculate_constraint_output.hpp index 607ee487..80972077 100644 --- a/src/constraints/calculate_constraint_output.hpp +++ b/src/constraints/calculate_constraint_output.hpp @@ -26,7 +26,8 @@ struct CalculateConstraintOutput { case ConstraintType::kRevoluteJoint: { // Axis of rotation unit vector const auto joint_axis0_data = Kokkos::Array{ - axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2)}; + axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2) + }; const auto joint_axis0 = View_3::const_type{joint_axis0_data.data()}; // Target node index @@ -34,12 +35,14 @@ struct CalculateConstraintOutput { // Target node initial rotation const auto R0_data = Kokkos::Array{ - node_u(i_node, 3), node_u(i_node, 4), node_u(i_node, 5), node_u(i_node, 6)}; + node_u(i_node, 3), node_u(i_node, 4), node_u(i_node, 5), node_u(i_node, 6) + }; const auto R0 = View_Quaternion::const_type{R0_data.data()}; // Target node rotational displacement const auto R_data = Kokkos::Array{ - node_u(i_node, 3), node_u(i_node, 4), node_u(i_node, 5), node_u(i_node, 6)}; + node_u(i_node, 3), node_u(i_node, 4), node_u(i_node, 5), node_u(i_node, 6) + }; const auto R = View_Quaternion::const_type{R_data.data()}; // Calculate current orientation @@ -54,12 +57,14 @@ struct CalculateConstraintOutput { // Target node rotational velocity vector auto omega_data = Kokkos::Array{ - node_udot(i_node, 3), node_udot(i_node, 4), node_udot(i_node, 5)}; + node_udot(i_node, 3), node_udot(i_node, 4), node_udot(i_node, 5) + }; auto omega = View_3{omega_data.data()}; // Target node rotational acceleration vector auto omega_dot_data = Kokkos::Array{ - node_uddot(i_node, 3), node_uddot(i_node, 4), node_uddot(i_node, 5)}; + node_uddot(i_node, 3), node_uddot(i_node, 4), node_uddot(i_node, 5) + }; auto omega_dot = View_3{omega_dot_data.data()}; // Calculate joint axis in current configuration diff --git a/src/constraints/calculate_fixed_bc_constraint.hpp b/src/constraints/calculate_fixed_bc_constraint.hpp index 2d0267f1..558d316d 100644 --- a/src/constraints/calculate_fixed_bc_constraint.hpp +++ b/src/constraints/calculate_fixed_bc_constraint.hpp @@ -23,7 +23,8 @@ struct CalculateFixedBCConstraint { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2)}; + X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; // Base node displacement @@ -34,7 +35,8 @@ struct CalculateFixedBCConstraint { // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; const auto u2_data = Kokkos::Array{node_u(i_node2, 0), node_u(i_node2, 1), node_u(i_node2, 2)}; diff --git a/src/constraints/calculate_prescribed_bc_constraint.hpp b/src/constraints/calculate_prescribed_bc_constraint.hpp index b05aefca..33937143 100644 --- a/src/constraints/calculate_prescribed_bc_constraint.hpp +++ b/src/constraints/calculate_prescribed_bc_constraint.hpp @@ -23,23 +23,27 @@ struct CalculatePrescribedBCConstraint { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2)}; + X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; // Base node displacement const auto u1_data = Kokkos::Array{ constraint_inputs(i_constraint, 0), constraint_inputs(i_constraint, 1), - constraint_inputs(i_constraint, 2)}; + constraint_inputs(i_constraint, 2) + }; auto u1 = View_3::const_type{u1_data.data()}; const auto R1_data = Kokkos::Array{ constraint_inputs(i_constraint, 3), constraint_inputs(i_constraint, 4), - constraint_inputs(i_constraint, 5), constraint_inputs(i_constraint, 6)}; + constraint_inputs(i_constraint, 5), constraint_inputs(i_constraint, 6) + }; const auto R1 = Kokkos::View::const_type{R1_data.data()}; // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; const auto u2_data = Kokkos::Array{node_u(i_node2, 0), node_u(i_node2, 1), node_u(i_node2, 2)}; diff --git a/src/constraints/calculate_revolute_joint_constraint.hpp b/src/constraints/calculate_revolute_joint_constraint.hpp index 7a4bf6c4..0ed89ff6 100644 --- a/src/constraints/calculate_revolute_joint_constraint.hpp +++ b/src/constraints/calculate_revolute_joint_constraint.hpp @@ -27,7 +27,8 @@ struct CalculateRevoluteJointConstraint { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2)}; + X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; // Base node displacement @@ -35,12 +36,14 @@ struct CalculateRevoluteJointConstraint { Kokkos::Array{node_u(i_node1, 0), node_u(i_node1, 1), node_u(i_node1, 2)}; const auto u1 = View_3::const_type{u1_data.data()}; const auto R1_data = Kokkos::Array{ - node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6)}; + node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6) + }; const auto R1 = Kokkos::View::const_type{R1_data.data()}; // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; const auto u2_data = Kokkos::Array{node_u(i_node2, 0), node_u(i_node2, 1), node_u(i_node2, 2)}; @@ -55,13 +58,16 @@ struct CalculateRevoluteJointConstraint { // Revolute joint constraint data const auto x0_data = Kokkos::Array{ - axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2)}; + axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2) + }; const auto x0 = View_3::const_type{x0_data.data()}; const auto y0_data = Kokkos::Array{ - axes(i_constraint, 1, 0), axes(i_constraint, 1, 1), axes(i_constraint, 1, 2)}; + axes(i_constraint, 1, 0), axes(i_constraint, 1, 1), axes(i_constraint, 1, 2) + }; const auto y0 = View_3::const_type{y0_data.data()}; const auto z0_data = Kokkos::Array{ - axes(i_constraint, 2, 0), axes(i_constraint, 2, 1), axes(i_constraint, 2, 2)}; + axes(i_constraint, 2, 0), axes(i_constraint, 2, 1), axes(i_constraint, 2, 2) + }; const auto z0 = View_3::const_type{z0_data.data()}; auto x_data = Kokkos::Array{}; const auto x = View_3{x_data.data()}; diff --git a/src/constraints/calculate_revolute_joint_force.hpp b/src/constraints/calculate_revolute_joint_force.hpp index 704c269c..38b53787 100644 --- a/src/constraints/calculate_revolute_joint_force.hpp +++ b/src/constraints/calculate_revolute_joint_force.hpp @@ -23,7 +23,8 @@ struct CalculateRevoluteJointForce { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2)}; + axes(i_constraint, 0, 0), axes(i_constraint, 0, 1), axes(i_constraint, 0, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; auto R2_X0_data = Kokkos::Array{}; @@ -31,7 +32,8 @@ struct CalculateRevoluteJointForce { // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; //---------------------------------------------------------------------- diff --git a/src/constraints/calculate_rigid_joint_constraint.hpp b/src/constraints/calculate_rigid_joint_constraint.hpp index ba1730b9..1b2325a3 100644 --- a/src/constraints/calculate_rigid_joint_constraint.hpp +++ b/src/constraints/calculate_rigid_joint_constraint.hpp @@ -26,7 +26,8 @@ struct CalculateRigidJointConstraint { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2)}; + X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; // Base node displacement @@ -34,12 +35,14 @@ struct CalculateRigidJointConstraint { Kokkos::Array{node_u(i_node1, 0), node_u(i_node1, 1), node_u(i_node1, 2)}; const auto u1 = View_3::const_type{u1_data.data()}; const auto R1_data = Kokkos::Array{ - node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6)}; + node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6) + }; const auto R1 = Kokkos::View::const_type{R1_data.data()}; // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; const auto u2_data = Kokkos::Array{node_u(i_node2, 0), node_u(i_node2, 1), node_u(i_node2, 2)}; diff --git a/src/constraints/calculate_rotation_control_constraint.hpp b/src/constraints/calculate_rotation_control_constraint.hpp index bd4bcb80..e3cf0e7a 100644 --- a/src/constraints/calculate_rotation_control_constraint.hpp +++ b/src/constraints/calculate_rotation_control_constraint.hpp @@ -27,20 +27,23 @@ struct CalculateRotationControlConstraint { // Initial difference between nodes const auto X0_data = Kokkos::Array{ - X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2)}; + X0_(i_constraint, 0), X0_(i_constraint, 1), X0_(i_constraint, 2) + }; const auto X0 = View_3::const_type{X0_data.data()}; // Base node displacement const auto u1_data = Kokkos::Array{node_u(i_node1, 0), node_u(i_node1, 1), node_u(i_node1, 2)}; const auto R1_data = Kokkos::Array{ - node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6)}; + node_u(i_node1, 3), node_u(i_node1, 4), node_u(i_node1, 5), node_u(i_node1, 6) + }; const auto u1 = View_3::const_type{u1_data.data()}; const auto R1 = Kokkos::View::const_type{R1_data.data()}; // Target node displacement const auto R2_data = Kokkos::Array{ - node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6)}; + node_u(i_node2, 3), node_u(i_node2, 4), node_u(i_node2, 5), node_u(i_node2, 6) + }; const auto R2 = Kokkos::View::const_type{R2_data.data()}; const auto u2_data = Kokkos::Array{node_u(i_node2, 0), node_u(i_node2, 1), node_u(i_node2, 2)}; diff --git a/src/constraints/constraint.hpp b/src/constraints/constraint.hpp index cd424bc3..65c65d05 100644 --- a/src/constraints/constraint.hpp +++ b/src/constraints/constraint.hpp @@ -74,7 +74,8 @@ struct Constraint { v[2] * v[0] * k - v[1], v[2] * v[1] * k + v[0], v[2] * v[2] * k + c, - }}}; + }} + }; // Set orthogonal unit vectors from the rotation matrix x_axis = {R[0][0], R[1][0], R[2][0]}; diff --git a/src/model/node.hpp b/src/model/node.hpp index 550abe85..4fe4e00e 100644 --- a/src/model/node.hpp +++ b/src/model/node.hpp @@ -48,7 +48,8 @@ struct Node { void Rotate(const Array_3& axis, double angle) { auto q = Array_4{ cos(angle / 2.), sin(angle / 2.) * axis[0], sin(angle / 2.) * axis[1], - sin(angle / 2.) * axis[2]}; + sin(angle / 2.) * axis[2] + }; Rotate(q); } }; diff --git a/src/solver/solver.hpp b/src/solver/solver.hpp index f61236cc..a6a164e4 100644 --- a/src/solver/solver.hpp +++ b/src/solver/solver.hpp @@ -151,7 +151,8 @@ struct Solver { "PopulateSparseRowPtrsColInds_Constraints", 1, PopulateSparseRowPtrsColInds_Constraints{ constraint_type, constraint_base_node_index, constraint_target_node_index, - constraint_row_range, B_row_ptrs, B_col_ind} + constraint_row_range, B_row_ptrs, B_col_ind + } ); auto B_values = ValuesType("B values", B_num_non_zero); KokkosSparse::sort_crs_matrix(B_row_ptrs, B_col_ind, B_values); @@ -172,7 +173,8 @@ struct Solver { "PopulateSparseRowPtrsColInds_Transpose", 1, PopulateSparseRowPtrsColInds_Transpose{ B_num_rows, B_num_columns, B_row_ptrs, B_col_ind, col_count, tmp_row_ptrs, - B_t_row_ptrs, B_t_col_inds} + B_t_row_ptrs, B_t_col_inds + } ); B_t = CrsMatrixType( "B_t", static_cast(B_t_num_rows), static_cast(B_t_num_columns), @@ -203,7 +205,8 @@ struct Solver { Kokkos::parallel_for( "FillUnshiftedRowPtrs", num_dofs + 1, FillUnshiftedRowPtrs{ - num_system_dofs, system_matrix.graph.row_map, system_matrix_full_row_ptrs} + num_system_dofs, system_matrix.graph.row_map, system_matrix_full_row_ptrs + } ); system_matrix_full = CrsMatrixType( "system_matrix_full", static_cast(num_dofs), static_cast(num_dofs), @@ -230,7 +233,8 @@ struct Solver { Kokkos::parallel_for( "FillUnshiftedRowPtrs", num_dofs + 1, FillUnshiftedRowPtrs{ - num_system_dofs, B_t.graph.row_map, transpose_matrix_full_row_ptrs} + num_system_dofs, B_t.graph.row_map, transpose_matrix_full_row_ptrs + } ); auto transpose_matrix_full_indices = IndicesType("transpose_matrix_full_indices", B_t.nnz()); Kokkos::deep_copy(transpose_matrix_full_indices, static_cast(num_system_dofs)); diff --git a/src/state/calculate_displacement.hpp b/src/state/calculate_displacement.hpp index 5aec741b..f0cfa2ee 100644 --- a/src/state/calculate_displacement.hpp +++ b/src/state/calculate_displacement.hpp @@ -19,7 +19,8 @@ struct CalculateDisplacement { } auto delta_data = Kokkos::Array{ - h * q_delta(i_node, 3), h * q_delta(i_node, 4), h * q_delta(i_node, 5)}; + h * q_delta(i_node, 3), h * q_delta(i_node, 4), h * q_delta(i_node, 5) + }; auto delta = Kokkos::View>{delta_data.data()}; @@ -28,7 +29,8 @@ struct CalculateDisplacement { Kokkos::View>{quat_delta_data.data()}; RotationVectorToQuaternion(delta, quat_delta); auto quat_prev_data = Kokkos::Array{ - q_prev(i_node, 3), q_prev(i_node, 4), q_prev(i_node, 5), q_prev(i_node, 6)}; + q_prev(i_node, 3), q_prev(i_node, 4), q_prev(i_node, 5), q_prev(i_node, 6) + }; auto quat_prev = Kokkos::View>{quat_prev_data.data()}; auto quat_new_data = Kokkos::Array{}; diff --git a/src/step/assemble_constraints_matrix.hpp b/src/step/assemble_constraints_matrix.hpp index 93832da7..d0f71619 100644 --- a/src/step/assemble_constraints_matrix.hpp +++ b/src/step/assemble_constraints_matrix.hpp @@ -26,7 +26,8 @@ inline void AssembleConstraintsMatrix(Solver& solver, Constraints& constraints) CopyConstraintsToSparseMatrix{ constraints.row_range, constraints.base_node_col_range, constraints.target_node_col_range, solver.B, constraints.base_gradient_terms, - constraints.target_gradient_terms} + constraints.target_gradient_terms + } ); } diff --git a/src/step/assemble_constraints_residual.hpp b/src/step/assemble_constraints_residual.hpp index 0f8d4dd3..45191e60 100644 --- a/src/step/assemble_constraints_residual.hpp +++ b/src/step/assemble_constraints_residual.hpp @@ -20,7 +20,8 @@ inline void AssembleConstraintsResidual(Solver& solver, Constraints& constraints Kokkos::parallel_for( "ContributeConstraintsSystemResidualToVector", constraints.num, ContributeConstraintsSystemResidualToVector{ - constraints.target_node_index, solver.R, constraints.system_residual_terms} + constraints.target_node_index, solver.R, constraints.system_residual_terms + } ); auto R = Solver::ValuesType( @@ -44,7 +45,8 @@ inline void AssembleConstraintsResidual(Solver& solver, Constraints& constraints CopyConstraintsResidualToVector{ constraints.row_range, Kokkos::subview(solver.R, Kokkos::make_pair(solver.num_system_dofs, solver.num_dofs)), - constraints.residual_terms} + constraints.residual_terms + } ); } diff --git a/src/step/assemble_inertia_matrix.hpp b/src/step/assemble_inertia_matrix.hpp index 0e268cc1..0c65eee8 100644 --- a/src/step/assemble_inertia_matrix.hpp +++ b/src/step/assemble_inertia_matrix.hpp @@ -20,7 +20,8 @@ inline void AssembleInertiaMatrix(const Beams& beams, double beta_prime, double IntegrateInertiaMatrix{ beams.num_nodes_per_element, beams.num_qps_per_element, beams.qp_weight, beams.qp_jacobian, beams.shape_interp, beams.qp_Muu, beams.qp_Guu, beta_prime, - gamma_prime, beams.inertia_matrix_terms} + gamma_prime, beams.inertia_matrix_terms + } ); } diff --git a/src/step/assemble_residual_vector.hpp b/src/step/assemble_residual_vector.hpp index 4cf1172f..5327ca24 100644 --- a/src/step/assemble_residual_vector.hpp +++ b/src/step/assemble_residual_vector.hpp @@ -25,7 +25,8 @@ inline void AssembleResidualVector(const Beams& beams) { IntegrateResidualVector{ beams.num_nodes_per_element, beams.num_qps_per_element, beams.qp_weight, beams.qp_jacobian, beams.shape_interp, beams.shape_deriv, beams.node_FX, beams.qp_Fc, - beams.qp_Fd, beams.qp_Fi, beams.qp_Fg, beams.residual_vector_terms} + beams.qp_Fd, beams.qp_Fi, beams.qp_Fg, beams.residual_vector_terms + } ); } diff --git a/src/step/assemble_system_matrix.hpp b/src/step/assemble_system_matrix.hpp index 6c6f5405..dcfa7869 100644 --- a/src/step/assemble_system_matrix.hpp +++ b/src/step/assemble_system_matrix.hpp @@ -30,7 +30,8 @@ inline void AssembleSystemMatrix(Solver& solver, Beams& beams) { Kokkos::parallel_for( "ContributeElementsToSparseMatrix", sparse_matrix_policy, ContributeElementsToSparseMatrix{ - solver.K, beams.stiffness_matrix_terms} + solver.K, beams.stiffness_matrix_terms + } ); Kokkos::fence(); diff --git a/src/step/assemble_system_residual.hpp b/src/step/assemble_system_residual.hpp index b08045ee..7edb572d 100644 --- a/src/step/assemble_system_residual.hpp +++ b/src/step/assemble_system_residual.hpp @@ -20,7 +20,8 @@ inline void AssembleSystemResidual(Solver& solver, Beams& beams) { "ContributeElementsToVector", vector_policy, ContributeElementsToVector{ beams.num_nodes_per_element, beams.node_state_indices, beams.residual_vector_terms, - solver.R} + solver.R + } ); } diff --git a/src/step/update_constraint_variables.hpp b/src/step/update_constraint_variables.hpp index ab582ae1..8bb1e653 100644 --- a/src/step/update_constraint_variables.hpp +++ b/src/step/update_constraint_variables.hpp @@ -23,7 +23,8 @@ inline void UpdateConstraintVariables(State& state, Constraints& constraints) { "CalculateConstraintForce", constraints.num, CalculateConstraintForce{ constraints.type, constraints.target_node_index, constraints.axes, constraints.input, - state.q, constraints.system_residual_terms} + state.q, constraints.system_residual_terms + } ); Kokkos::parallel_for( @@ -31,7 +32,8 @@ inline void UpdateConstraintVariables(State& state, Constraints& constraints) { CalculateConstraintResidualGradient{ constraints.type, constraints.base_node_index, constraints.target_node_index, constraints.X0, constraints.axes, constraints.input, state.q, constraints.residual_terms, - constraints.base_gradient_terms, constraints.target_gradient_terms} + constraints.base_gradient_terms, constraints.target_gradient_terms + } ); } diff --git a/src/step/update_system_variables.hpp b/src/step/update_system_variables.hpp index 36150ac1..cdf0763a 100644 --- a/src/step/update_system_variables.hpp +++ b/src/step/update_system_variables.hpp @@ -39,7 +39,8 @@ inline void UpdateSystemVariables(StepParameters& parameters, const Beams& beams beams.num_nodes_per_element, beams.num_qps_per_element, beams.shape_interp, beams.shape_deriv, beams.qp_jacobian, beams.node_u, beams.node_u_dot, beams.node_u_ddot, beams.qp_x0, beams.qp_r0, beams.qp_u, beams.qp_u_prime, beams.qp_r, beams.qp_r_prime, - beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x} + beams.qp_u_dot, beams.qp_omega, beams.qp_u_ddot, beams.qp_omega_dot, beams.qp_x + } ); Kokkos::parallel_for( @@ -80,7 +81,8 @@ inline void UpdateSystemVariables(StepParameters& parameters, const Beams& beams beams.qp_Puu, beams.qp_Quu, beams.qp_Guu, - beams.qp_Kuu} + beams.qp_Kuu + } ); AssembleResidualVector(beams); diff --git a/src/system/calculate_RR0.hpp b/src/system/calculate_RR0.hpp index cc9d7f34..058df25a 100644 --- a/src/system/calculate_RR0.hpp +++ b/src/system/calculate_RR0.hpp @@ -14,7 +14,8 @@ struct CalculateRR0 { KOKKOS_FUNCTION void operator()(const int i_qp) const { auto RR0_quaternion_data = Kokkos::Array{ qp_x_(i_elem, i_qp, 3), qp_x_(i_elem, i_qp, 4), qp_x_(i_elem, i_qp, 5), - qp_x_(i_elem, i_qp, 6)}; + qp_x_(i_elem, i_qp, 6) + }; auto RR0_quaternion = Kokkos::View::const_type(RR0_quaternion_data.data()); auto RR0_data = Kokkos::Array{}; auto RR0 = View_3x3(RR0_data.data()); diff --git a/src/system/calculate_quadrature_point_values.hpp b/src/system/calculate_quadrature_point_values.hpp index b566818a..237d5988 100644 --- a/src/system/calculate_quadrature_point_values.hpp +++ b/src/system/calculate_quadrature_point_values.hpp @@ -99,7 +99,8 @@ struct CalculateQuadraturePointValues { Kokkos::TeamThreadRange(member, 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_} + qp_omega_tilde_, qp_omega_dot_tilde_, qp_rho_, qp_eta_, qp_FI_ + } ); member.team_barrier(); @@ -131,14 +132,16 @@ struct CalculateQuadraturePointValues { Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_qps), CalculateGyroscopicMatrix{ - i_elem, qp_Muu_, qp_omega_, qp_omega_tilde_, qp_rho_, qp_eta_, qp_Guu_} + i_elem, qp_Muu_, qp_omega_, qp_omega_tilde_, qp_rho_, qp_eta_, qp_Guu_ + } ); Kokkos::parallel_for( Kokkos::TeamThreadRange(member, 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_} + qp_omega_dot_tilde_, qp_rho_, qp_eta_, qp_Kuu_ + } ); } }; diff --git a/src/system/calculate_strain.hpp b/src/system/calculate_strain.hpp index 1d5b6bec..923adb03 100644 --- a/src/system/calculate_strain.hpp +++ b/src/system/calculate_strain.hpp @@ -23,15 +23,17 @@ struct CalculateStrain { void operator()(const int i_qp) const { auto x0_prime_data = Kokkos::Array{ qp_x0_prime_(i_elem, i_qp, 0), qp_x0_prime_(i_elem, i_qp, 1), - qp_x0_prime_(i_elem, i_qp, 2)}; + 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_elem, i_qp, 0), qp_u_prime_(i_elem, i_qp, 1), - qp_u_prime_(i_elem, 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_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)}; + qp_r_(i_elem, i_qp, 3) + }; auto R = Kokkos::View(R_data.data()); auto R_x0_prime_data = Kokkos::Array{}; @@ -46,7 +48,8 @@ struct CalculateStrain { QuaternionDerivative(R, E); auto R_prime_data = Kokkos::Array{ 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)}; + 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()}; diff --git a/src/system/calculate_temporary_variables.hpp b/src/system/calculate_temporary_variables.hpp index 04109d79..fde710cc 100644 --- a/src/system/calculate_temporary_variables.hpp +++ b/src/system/calculate_temporary_variables.hpp @@ -17,11 +17,12 @@ struct CalculateTemporaryVariables { void operator()(int i_qp) const { auto x0pup_data = Kokkos::Array{ qp_x0_prime_(i_elem, i_qp, 0), qp_x0_prime_(i_elem, i_qp, 1), - qp_x0_prime_(i_elem, i_qp, 2)}; + 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_elem, i_qp, 0), qp_u_prime_(i_elem, i_qp, 1), - qp_u_prime_(i_elem, 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{}; diff --git a/src/system/integrate_inertia_matrix.hpp b/src/system/integrate_inertia_matrix.hpp index 960bfdd5..9c089347 100644 --- a/src/system/integrate_inertia_matrix.hpp +++ b/src/system/integrate_inertia_matrix.hpp @@ -117,9 +117,10 @@ struct IntegrateInertiaMatrix { member.team_barrier(); const auto node_range = Kokkos::TeamThreadRange(member, num_nodes * simd_nodes); - const auto element_integrator = IntegrateInertiaMatrixElement{ - i_elem, num_nodes, num_qps, qp_weight, qp_jacobian, shape_interp, - qp_Muu, qp_Guu, beta_prime_, gamma_prime_, gbl_M_}; + const auto element_integrator = + IntegrateInertiaMatrixElement{i_elem, num_nodes, num_qps, 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/system/integrate_residual_vector.hpp b/src/system/integrate_residual_vector.hpp index 6a337e06..cd60557e 100644 --- a/src/system/integrate_residual_vector.hpp +++ b/src/system/integrate_residual_vector.hpp @@ -92,7 +92,8 @@ struct IntegrateResidualVector { const auto node_range = Kokkos::TeamThreadRange(member, num_nodes); const auto element_integrator = IntegrateResidualVectorElement{ i_elem, num_qps, qp_weight, qp_jacobian, shape_interp, shape_deriv, - node_FX, qp_Fc, qp_Fd, qp_Fi, qp_Fg, residual_vector_terms_}; + node_FX, qp_Fc, qp_Fd, qp_Fi, qp_Fg, residual_vector_terms_ + }; Kokkos::parallel_for(node_range, element_integrator); } }; diff --git a/src/system/integrate_stiffness_matrix.hpp b/src/system/integrate_stiffness_matrix.hpp index 4ae8f0a6..99f9757b 100644 --- a/src/system/integrate_stiffness_matrix.hpp +++ b/src/system/integrate_stiffness_matrix.hpp @@ -138,7 +138,8 @@ struct IntegrateStiffnessMatrix { const auto node_range = Kokkos::TeamThreadRange(member, num_nodes * simd_nodes); const auto element_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, gbl_M_}; + qp_Kuu, qp_Puu, qp_Cuu, qp_Ouu, qp_Quu, gbl_M_ + }; Kokkos::parallel_for(node_range, element_integrator); } }; diff --git a/src/system/update_node_state.hpp b/src/system/update_node_state.hpp index e78da2cc..6991b7a8 100644 --- a/src/system/update_node_state.hpp +++ b/src/system/update_node_state.hpp @@ -47,7 +47,8 @@ struct UpdateNodeState { Kokkos::parallel_for( Kokkos::TeamThreadRange(member, num_nodes), UpdateNodeStateElement{ - i_elem, node_state_indices, node_u, node_u_dot, node_u_ddot, Q, V, A} + i_elem, node_state_indices, node_u, node_u_dot, node_u_ddot, Q, V, A + } ); } }; diff --git a/src/utilities/scripts/windio_mapped_structs.hpp b/src/utilities/scripts/windio_mapped_structs.hpp index 47629e91..c719b7f5 100644 --- a/src/utilities/scripts/windio_mapped_structs.hpp +++ b/src/utilities/scripts/windio_mapped_structs.hpp @@ -1131,9 +1131,9 @@ struct Drivetrain { // simple generator scaling double generator_mass_user{}; // User input override of generator mass, only used when using // simple generator mass scaling - GeneratorRpmEfficiencyUser - generator_rpm_efficiency_user{}; // User input override of generator rpm-efficiency values, - // with rpm as grid input and eff as values input + GeneratorRpmEfficiencyUser generator_rpm_efficiency_user{ + }; // User input override of generator rpm-efficiency values, + // with rpm as grid input and eff as values input double gear_ratio{}; // Gear ratio of the drivetrain. Set it to 1 for direct drive machines. double gearbox_length_user{}; // User input override of gearbox length along shaft, only used // when using gearbox_mass_user is > 0 @@ -1608,10 +1608,10 @@ struct OuterShape_1 { std::vector side_lengths2; // Polygon side lengths at joint1 std::vector angles; // Polygon angles with the ordering such that angle[i] is between // side_length[i] and side_length[i+1] - double - rotation{}; // Angle between principle axes of the cross-section and the member coordinate - // system. Essentially the rotation of the member if both joints were placed - // on the global x-y axis with the first side length along the z-axis + double rotation{ + }; // Angle between principle axes of the cross-section and the member coordinate + // system. Essentially the rotation of the member if both joints were placed + // on the global x-y axis with the first side length along the z-axis void parse(const YAML::Node& node) { shape = node["shape"].as(""); @@ -1916,9 +1916,9 @@ struct LineTypes { // having the same displacement per unit length std::string type; // Type of material for property lookup double mass_density{}; // mass per unit length (in air) - double - stiffness{}; // axial line stiffness, product of elasticity modulus and cross-sectional area - double cost{}; // cost per unit length + double stiffness{ + }; // axial line stiffness, product of elasticity modulus and cross-sectional area + double cost{}; // cost per unit length double breaking_load{}; // line break tension double damping{}; // internal damping (BA) double transverse_added_mass{}; // transverse added mass coefficient (with respect to line @@ -2171,9 +2171,9 @@ struct Materials { // https://www.nrel.gov/docs/fy19osti/73585.pdf to define the manufacturing // process behind the laminate. 0 - coating, 1 - sandwich filler , 2 - shell // skin, 3 - shear webs, 4 - spar caps, 5 - TE reinf. - double - waste{}; // Fraction of material that ends up wasted during manufacturing. This quantity is - // used in the NREL blade cost model https://www.nrel.gov/docs/fy19osti/73585.pdf + double waste{ + }; // Fraction of material that ends up wasted during manufacturing. This quantity is + // used in the NREL blade cost model https://www.nrel.gov/docs/fy19osti/73585.pdf double roll_mass{}; // Mass of a fabric roll. This quantity is used in the NREL blade cost model // https://www.nrel.gov/docs/fy19osti/73585.pdf double gic{}; // Mode 1 critical energy-release rate. It is used by NuMAD from Sandia National @@ -2408,11 +2408,11 @@ struct Costs { // cost/rating ratio double crane_cost{}; // crane cost if present double electricity_price{}; // Electricity price used to compute value in beyond lcoe metrics - double - reserve_margin_price{}; // Reserve margin price used to compute value in beyond lcoe metrics - double capacity_credit{}; // Capacity credit used to compute value in beyond lcoe metrics - double - benchmark_price{}; // Benchmark price used to nondimensionalize value in beyond lcoe metrics + double reserve_margin_price{ + }; // Reserve margin price used to compute value in beyond lcoe metrics + double capacity_credit{}; // Capacity credit used to compute value in beyond lcoe metrics + double benchmark_price{ + }; // Benchmark price used to nondimensionalize value in beyond lcoe metrics void parse(const YAML::Node& node) { wake_loss_factor = node["wake_loss_factor"].as(0.); diff --git a/src/vendor/dylib/dylib.hpp b/src/vendor/dylib/dylib.hpp index be99f3e2..6fef016b 100644 --- a/src/vendor/dylib/dylib.hpp +++ b/src/vendor/dylib/dylib.hpp @@ -175,22 +175,19 @@ class dylib { #ifdef DYLIB_CPP17 explicit dylib(const std::filesystem::path& lib_path) - : dylib("", lib_path.string().c_str(), no_filename_decorations) { - } + : dylib("", lib_path.string().c_str(), no_filename_decorations) {} dylib( const std::filesystem::path& dir_path, const std::string& lib_name, bool decorations = add_filename_decorations ) - : dylib(dir_path.string().c_str(), lib_name.c_str(), decorations) { - } + : dylib(dir_path.string().c_str(), lib_name.c_str(), decorations) {} dylib( const std::filesystem::path& dir_path, const char* lib_name, bool decorations = add_filename_decorations ) - : dylib(dir_path.string().c_str(), lib_name, decorations) { - } + : dylib(dir_path.string().c_str(), lib_name, decorations) {} #endif ///@} @@ -307,9 +304,7 @@ class dylib { /** * @return the dynamic library handle */ - native_handle_type native_handle() noexcept { - return m_handle; - } + native_handle_type native_handle() noexcept { return m_handle; } protected: native_handle_type m_handle{nullptr};