/home/runner/work/kynema/kynema/kynema/src/math/matrix_operations.hpp Source File

Kynema API: /home/runner/work/kynema/kynema/kynema/src/math/matrix_operations.hpp Source File
Kynema API
A flexible multibody structural dynamics code for wind turbines
Loading...
Searching...
No Matches
matrix_operations.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <array>
4#include <ranges>
5
6#include <Kokkos_Core.hpp>
7
9
10namespace kynema::math {
11
18template <typename Matrix>
19KOKKOS_INLINE_FUNCTION void AX_Matrix(const Matrix& A, const Matrix& AX_A) {
20 double trace{0.};
21 for (auto i = 0; i < A.extent_int(0); ++i) {
22 trace += A(i, i);
23 }
24
25 trace /= 2.;
26
27 for (auto i = 0; i < A.extent_int(0); ++i) {
28 for (auto j = 0; j < A.extent_int(1); ++j) {
29 AX_A(i, j) = -A(i, j) / 2.;
30 }
31 AX_A(i, i) += trace;
32 }
33}
34
46template <typename Matrix, typename Vector>
47KOKKOS_INLINE_FUNCTION void AxialVectorOfMatrix(const Matrix& m, const Vector& v) {
48 v(0) = (m(2, 1) - m(1, 2)) / 2.;
49 v(1) = (m(0, 2) - m(2, 0)) / 2.;
50 v(2) = (m(1, 0) - m(0, 1)) / 2.;
51}
52
53inline std::array<std::array<double, 6>, 6> RotateMatrix6(
54 const std::array<std::array<double, 6>, 6>& m, const std::array<double, 4>& q
55) {
56 const auto rm = QuaternionToRotationMatrix(q);
57 std::array<std::array<double, 6>, 6> r{{
58 {rm[0][0], rm[0][1], rm[0][2], 0., 0., 0.},
59 {rm[1][0], rm[1][1], rm[1][2], 0., 0., 0.},
60 {rm[2][0], rm[2][1], rm[2][2], 0., 0., 0.},
61 {0., 0., 0., rm[0][0], rm[0][1], rm[0][2]},
62 {0., 0., 0., rm[1][0], rm[1][1], rm[1][2]},
63 {0., 0., 0., rm[2][0], rm[2][1], rm[2][2]},
64 }};
65
66 // matmul(r,m)
67 std::array<std::array<double, 6>, 6> mt{};
68 for (auto i : std::views::iota(0U, 6U)) {
69 for (auto j : std::views::iota(0U, 6U)) {
70 mt[i][j] = 0.;
71 for (auto k : std::views::iota(0U, 6U)) {
72 mt[i][j] += r[i][k] * m[k][j];
73 }
74 }
75 }
76
77 // matmul(matmul(r,m),r^T)
78 std::array<std::array<double, 6>, 6> mo{};
79 for (auto i : std::views::iota(0U, 6U)) {
80 for (auto j : std::views::iota(0U, 6U)) {
81 mo[i][j] = 0.;
82 for (auto k : std::views::iota(0U, 6U)) {
83 mo[i][j] += mt[i][k] * r[j][k];
84 }
85 }
86 }
87
88 return mo;
89}
90
91} // namespace kynema::math
Definition gll_quadrature.hpp:7
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
std::array< std::array< double, 6 >, 6 > RotateMatrix6(const std::array< std::array< double, 6 >, 6 > &m, const std::array< double, 4 > &q)
Definition matrix_operations.hpp:53
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 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