/home/runner/work/kynema/kynema/kynema/src/constraints/calculate_rigid_joint_constraint.hpp Source File

Kynema API: /home/runner/work/kynema/kynema/kynema/src/constraints/calculate_rigid_joint_constraint.hpp Source File
Kynema API
A flexible multibody structural dynamics code for wind turbines
Loading...
Searching...
No Matches
calculate_rigid_joint_constraint.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <KokkosBatched_Copy_Decl.hpp>
4#include <Kokkos_Core.hpp>
5
9
10namespace kynema::constraints {
11
16template <typename DeviceType>
18 template <typename ValueType>
19 using View = Kokkos::View<ValueType, DeviceType>;
20 template <typename ValueType>
22
24 const ConstView<double[3]>& X0, const ConstView<double[7]>& base_node_u,
25 const ConstView<double[7]>& target_node_u, const View<double[6]>& residual_terms,
26 const View<double[6][6]>& base_gradient_terms,
27 const View<double[6][6]>& target_gradient_terms
28 ) {
29 using Kokkos::Array;
30 using Kokkos::make_pair;
31 using Kokkos::subview;
32 using CopyMatrixTranspose = KokkosBatched::SerialCopy<KokkosBatched::Trans::Transpose>;
33 using CopyMatrix = KokkosBatched::SerialCopy<>;
34
36 const auto R1_data =
39 const auto R2_data =
42 auto C_data = Array<double, 9>{};
46 auto A_data = Array<double, 9>{};
47
48 const auto u1 = ConstView<double[3]>{u1_data.data()};
49 const auto R1 = ConstView<double[4]>{R1_data.data()};
50 const auto u2 = ConstView<double[3]>{u2_data.data()};
51 const auto R2 = ConstView<double[4]>{R2_data.data()};
52 const auto R1_X0 = View<double[3]>{R1_X0_data.data()};
53 const auto C = View<double[3][3]>{C_data.data()};
54 const auto R1t = View<double[4]>{R1t_data.data()};
55 const auto R2_R1t = View<double[4]>{R2_R1t_data.data()};
56 const auto V3 = View<double[3]>{V3_data.data()};
57 const auto A = View<double[3][3]>{A_data.data()};
58
59 //----------------------------------------------------------------------
60 // Residual Vector
61 //----------------------------------------------------------------------
62
63 // Phi(0:3) = u2 + X0 - u1 - R1*X0
66 for (auto component = 0; component < 3; ++component) {
67 residual_terms(component) =
69 }
70
71 // Phi(3:6) = axial(R2*inv(RC)*inv(R1))
75 for (auto component = 0; component < 3; ++component) {
76 residual_terms(component + 3) = V3(component);
77 }
78
79 //----------------------------------------------------------------------
80 // Constraint Gradient Matrix
81 //----------------------------------------------------------------------
82
83 // Target Node gradients
84 // B(0:3,0:3) = I
85 for (auto component = 0; component < 3; ++component) {
86 target_gradient_terms(component, component) = 1.;
87 }
88
89 // B(3:6,3:6) = AX(R1*RC*inv(R2)) = transpose(AX(R2*inv(RC)*inv(R1)))
91 CopyMatrixTranspose::invoke(
92 A, subview(target_gradient_terms, make_pair(3, 6), make_pair(3, 6))
93 );
94
95 // Base Node gradients
96 // B(0:3,0:3) = -I
97 for (auto component = 0; component < 3; ++component) {
98 base_gradient_terms(component, component) = -1.;
99 }
100
101 // B(0:3,3:6) = tilde(R1*X0)
103 CopyMatrix::invoke(A, subview(base_gradient_terms, make_pair(0, 3), make_pair(3, 6)));
104
105 // B(3:6,3:6) = -AX(R2*inv(RC)*inv(R1))
106 math::AX_Matrix(C, A);
107 for (auto component_1 = 0; component_1 < 3; ++component_1) {
108 for (auto component_2 = 0; component_2 < 3; ++component_2) {
109 base_gradient_terms(component_1 + 3, component_2 + 3) = -A(component_1, component_2);
110 }
111 }
112 }
113};
114} // namespace kynema::constraints
Definition calculate_constraint_output.hpp:8
KOKKOS_INLINE_FUNCTION void AX_Matrix(const Matrix &A, const Matrix &AX_A)
Computes AX(A) of a square matrix.
Definition matrix_operations.hpp:19
KOKKOS_INLINE_FUNCTION void QuaternionCompose(const Quaternion1 &q1, const Quaternion2 &q2, QuaternionN &qn)
Composes (i.e. multiplies) two quaternions and stores the result in a third quaternion.
Definition quaternion_operations.hpp:204
KOKKOS_INLINE_FUNCTION void VecTilde(const VectorType &vector, const MatrixType &matrix)
Converts a 3x1 vector to a 3x3 skew-symmetric matrix and returns the result.
Definition vector_operations.hpp:11
KOKKOS_INLINE_FUNCTION void RotateVectorByQuaternion(const Quaternion &q, const View1 &v, const View2 &v_rot)
Rotates provided vector by provided unit quaternion and returns the result.
Definition quaternion_operations.hpp:120
KOKKOS_INLINE_FUNCTION void QuaternionToRotationMatrix(const Quaternion &q, const RotationMatrix &R)
Converts a 4x1 quaternion to a 3x3 rotation matrix and returns the result.
Definition quaternion_operations.hpp:20
KOKKOS_INLINE_FUNCTION void QuaternionInverse(const QuaternionInput &q_in, const QuaternionOutput &q_out)
Computes the inverse of a quaternion.
Definition quaternion_operations.hpp:172
KOKKOS_INLINE_FUNCTION void AxialVectorOfMatrix(const Matrix &m, const Vector &v)
Computes the axial vector (also known as the vector representation) of a 3x3 skew-symmetric matrix.
Definition matrix_operations.hpp:47
Kernel for calculating the residual and system gradient for a rigid joint constraint with six degrees...
Definition calculate_rigid_joint_constraint.hpp:17
typename View< ValueType >::const_type ConstView
Definition calculate_rigid_joint_constraint.hpp:21
Kokkos::View< ValueType, DeviceType > View
Definition calculate_rigid_joint_constraint.hpp:19
static KOKKOS_FUNCTION void invoke(const ConstView< double[3]> &X0, const ConstView< double[7]> &base_node_u, const ConstView< double[7]> &target_node_u, const View< double[6]> &residual_terms, const View< double[6][6]> &base_gradient_terms, const View< double[6][6]> &target_gradient_terms)
Definition calculate_rigid_joint_constraint.hpp:23