0.3.0
Loading...
Searching...
No Matches
Math.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
14
15#pragma once
16
17#include <concepts>
18#include <cstdint>
19#include <optional>
20#include <type_traits>
21#include <Eigen/Core>
22#include <gcem.hpp>
23#include <fmt/format.h>
24
25#include "util/Assert.h"
26
27namespace NAV::math
28{
29
33uint64_t factorial(uint64_t n);
34
39template<std::floating_point T>
40constexpr T round(const T& value, size_t digits)
41{
42 auto factor = std::pow(10, digits);
43 return std::round(value * factor) / factor;
44}
45
50template<std::floating_point T>
51constexpr T roundSignificantDigits(T value, size_t digits)
52{
53 if (value == 0.0) { return 0.0; }
54 // LOG_DEBUG("value = {:.13e} --> Round to {} digits", value, digits);
55 auto absVal = gcem::abs(value);
56 auto log10 = static_cast<int32_t>(gcem::log10(absVal));
57 auto exp = log10 + (log10 > 0 || (log10 == 0 && absVal >= 1.0));
58 auto fac = static_cast<T>(digits) - static_cast<T>(exp);
59 // LOG_DEBUG(" log10 = {}, exp = {}, fac = {}", log10, exp, fac);
60 auto factor = static_cast<T>(gcem::pow(10.0, fac));
61 // LOG_DEBUG(" factor = {:.0e} --> value * factor = {}", factor, value * factor);
62 // LOG_DEBUG(" round = {} --> ... / factor = {}", gcem::round(value * factor), gcem::round(value * factor) / factor);
63 return static_cast<T>(gcem::round(value * factor) / factor);
64}
65
72template<std::integral Out, size_t Bits, std::integral In>
73constexpr Out interpretAs(In in)
74{
75 static_assert(Bits < sizeof(In) * 8);
76 static_assert(Bits < sizeof(Out) * 8);
77
78 constexpr size_t N = sizeof(Out) * 8 - Bits;
79 return static_cast<Out>(static_cast<Out>((in & static_cast<In>(gcem::pow(2, Bits) - 1)) << N) >> N);
80}
81
88template<typename Derived>
89Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetricMatrix(const Eigen::MatrixBase<Derived>& a)
90{
91 INS_ASSERT_USER_ERROR(a.cols() == 1, "Given Eigen Object must be a vector");
92 INS_ASSERT_USER_ERROR(a.rows() == 3, "Given Vector must have 3 Rows");
93
94 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewMat;
95 skewMat << 0, -a(2), a(1),
96 a(2), 0, -a(0),
97 -a(1), a(0), 0;
98
99 return skewMat;
100}
101
106template<typename Derived>
107Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetricMatrixSquared(const Eigen::MatrixBase<Derived>& a)
108{
109 INS_ASSERT_USER_ERROR(a.cols() == 1, "Given Eigen Object must be a vector");
110 INS_ASSERT_USER_ERROR(a.rows() == 3, "Given Vector must have 3 Rows");
111
112 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewMat2;
113 skewMat2 << std::pow(a(2), 2) + std::pow(a(1), 2), a(0) * a(1), a(0) * a(2),
114 a(0) * a(1), std::pow(a(2), 2) + std::pow(a(0), 2), a(1) * a(2),
115 a(0) * a(2), a(1) * a(2), std::pow(a(0), 2) + std::pow(a(1), 2);
116
117 return skewMat2;
118}
119
121template<std::floating_point T>
122T sec(const T& x)
123{
124 return 1.0 / std::cos(x);
125}
126
128template<std::floating_point T>
129T csc(const T& x)
130{
131 return 1.0 / std::sin(x);
132}
133
137template<typename T>
138int sgn(const T& val)
139{
140 return (T(0) < val) - (val < T(0));
141}
142
149template<typename Derived>
150std::optional<std::pair<Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>,
151 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime>>>
152 LtDLdecomp_outerProduct(const Eigen::MatrixBase<Derived>& Qmatrix)
153{
154 using Eigen::seq;
155
156 auto n = Qmatrix.rows();
157 Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime> Q = Qmatrix.template triangularView<Eigen::Lower>();
158 Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime> L;
159 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime> D;
160
161 if constexpr (Derived::RowsAtCompileTime == Eigen::Dynamic)
162 {
163 L = Eigen::Matrix<typename Derived::Scalar, Eigen::Dynamic, Eigen::Dynamic>::Zero(n, n);
164 D.setZero(n);
165 }
166 else
167 {
168 L = Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>::Zero();
169 D.setZero();
170 }
171
172 for (Eigen::Index i = n - 1; i >= 0; i--)
173 {
174 D(i) = Q(i, i);
175 if (Q(i, i) <= 0.0) { return {}; }
176 L(i, seq(0, i)) = Q(i, seq(0, i)) / std::sqrt(Q(i, i));
177
178 for (Eigen::Index j = 0; j <= i - 1; j++)
179 {
180 Q(j, seq(0, j)) -= L(i, seq(0, j)) * L(i, j);
181 }
182 L(i, seq(0, i)) /= L(i, i);
183 }
184
185 return std::make_pair(L, D);
186}
187
193template<typename Derived>
194std::optional<std::pair<Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>,
195 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime>>>
196 LtDLdecomp_choleskyFact(const Eigen::MatrixBase<Derived>& Q)
197{
198 using Eigen::seq;
199
200 auto n = Q.rows();
201 typename Derived::PlainObject L = Q.template triangularView<Eigen::Lower>();
202 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime> D;
203 double cmin = 1;
204
205 if constexpr (Derived::RowsAtCompileTime == Eigen::Dynamic) { D.setZero(n); }
206 else { D.setZero(); }
207
208 for (Eigen::Index j = n - 1; j >= 0; j--)
209 {
210 for (Eigen::Index i = n - 1; i >= j + 1; i--)
211 {
212 L(i, j) = (L(i, j) - L(seq(i + 1, n - 1), j).dot(L(seq(i + 1, n - 1), i))) / L(i, i);
213 }
214 double t = L(j, j) - L(seq(j + 1, n - 1), j).dot(L(seq(j + 1, n - 1), j));
215 if (t <= 0.0) { return {}; }
216 double c = t / L(j, j);
217 cmin = std::min(c, cmin);
218 L(j, j) = std::sqrt(t);
219 }
220 for (Eigen::Index i = 0; i < n; i++)
221 {
222 L.row(i).leftCols(i) /= L(i, i);
223 D(i) = std::pow(L(i, i), 2.0);
224 L(i, i) = 1;
225 }
226
227 return std::make_pair(L, D);
228}
229
238template<typename DerivedA, typename DerivedQ>
239typename DerivedA::Scalar squaredNormVectorMatrix(const Eigen::MatrixBase<DerivedA>& a, const Eigen::MatrixBase<DerivedQ>& Q)
240{
241 static_assert(DerivedA::ColsAtCompileTime == Eigen::Dynamic || DerivedA::ColsAtCompileTime == 1);
242 INS_ASSERT_USER_ERROR(a.cols() == 1, "Parameter 'a' has to be a vector");
243 INS_ASSERT_USER_ERROR(a.rows() == Q.rows(), "Parameter 'a' and 'Q' need to have same size");
244 INS_ASSERT_USER_ERROR(Q.cols() == Q.rows(), "Parameter 'Q' needs to be quadratic");
245
246 return a.transpose() * Q.inverse() * a;
247}
248
275double normalCDF(double value);
276
281template<typename T>
282T sign(const T& x, const T& y)
283{
284 // similar function 'sign' in fortran
285 if (y >= 0.0)
286 {
287 return fabs(x);
288 }
289 return -1.0 * fabs(x);
290}
291
297template<typename Derived>
298typename Derived::PlainObject lerp(const Eigen::MatrixBase<Derived>& a, const Eigen::MatrixBase<Derived>& b, const typename Derived::Scalar& t)
299{
300 return a + t * (b - a);
301}
302
305{
306 size_t l;
307 size_t u;
308 double t;
309};
310
314LerpSearchResult lerpSearch(const auto& data, const auto& value)
315{
316 auto i = static_cast<size_t>(std::distance(data.begin(), std::upper_bound(data.begin(), data.end(), value)));
317 if (i > 0) { i--; }
318 if (i == data.size() - 1) { i--; }
319 const auto& lb = data.at(i);
320 const auto& ub = data.at(i + 1);
321 double t = (value - lb) / (ub - lb);
322
323 return { .l = i, .u = i + 1, .t = t };
324}
325
341auto bilinearInterpolation(const double& tx, const double& ty,
342 const auto& c00, const auto& c10,
343 const auto& c01, const auto& c11)
344{
345 auto a = c00 * (1 - tx) + c10 * tx;
346 auto b = c01 * (1 - tx) + c11 * tx;
347 return a * (1 - ty) + b * ty;
348 // Alternative implementation:
349 // return (1 - tx) * (1 - ty) * c00 + tx * (1 - ty) * c10 + (1 - tx) * ty * c01 + tx * ty * c11;
350}
351
357double calcEllipticalIntegral(double phi, double m);
358
359} // namespace NAV::math
Assertion helpers.
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
T sec(const T &x)
Calculates the secant of a value (sec(x) = csc(pi/2 - x) = 1 / cos(x))
Definition Math.hpp:122
LerpSearchResult lerpSearch(const auto &data, const auto &value)
Searches the value in the data container.
Definition Math.hpp:314
T csc(const T &x)
Calculates the cosecant of a value (csc(x) = sec(pi/2 - x) = 1 / sin(x))
Definition Math.hpp:129
DerivedA::Scalar squaredNormVectorMatrix(const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedQ > &Q)
Calculates the squared norm of the vector and matrix.
Definition Math.hpp:239
int sgn(const T &val)
Returns the sign of the given value.
Definition Math.hpp:138
std::optional< std::pair< Eigen::Matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime >, Eigen::Vector< typename Derived::Scalar, Derived::RowsAtCompileTime > > > LtDLdecomp_outerProduct(const Eigen::MatrixBase< Derived > &Qmatrix)
Find (L^T D L)-decomposition of Q-matrix via outer product method.
Definition Math.hpp:152
T sign(const T &x, const T &y)
Change the sign of x according to the value of y.
Definition Math.hpp:282
Eigen::Matrix< typename Derived::Scalar, 3, 3 > skewSymmetricMatrixSquared(const Eigen::MatrixBase< Derived > &a)
Calculates the square of a skew symmetric matrix of the given vector.
Definition Math.hpp:107
auto bilinearInterpolation(const double &tx, const double &ty, const auto &c00, const auto &c10, const auto &c01, const auto &c11)
Bilinear interpolation.
Definition Math.hpp:341
constexpr T roundSignificantDigits(T value, size_t digits)
Round the number to the specified amount of significant digits.
Definition Math.hpp:51
double calcEllipticalIntegral(double phi, double m)
Calculates the incomplete elliptical integral of the second kind.
Eigen::Matrix< typename Derived::Scalar, 3, 3 > skewSymmetricMatrix(const Eigen::MatrixBase< Derived > &a)
Calculates the skew symmetric matrix of the given vector. This is needed to perform the cross product...
Definition Math.hpp:89
uint64_t factorial(uint64_t n)
Calculates the factorial of an unsigned integer.
double normalCDF(double value)
Calculates the cumulative distribution function (CDF) of the standard normal distribution.
constexpr T round(const T &value, size_t digits)
Round the number to the specified amount of digits.
Definition Math.hpp:40
Derived::PlainObject lerp(const Eigen::MatrixBase< Derived > &a, const Eigen::MatrixBase< Derived > &b, const typename Derived::Scalar &t)
Linear interpolation between vectors.
Definition Math.hpp:298
constexpr Out interpretAs(In in)
Interprets the input integer with certain amount of Bits as Output type. Takes care of sign extension...
Definition Math.hpp:73
std::optional< std::pair< Eigen::Matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime >, Eigen::Vector< typename Derived::Scalar, Derived::RowsAtCompileTime > > > LtDLdecomp_choleskyFact(const Eigen::MatrixBase< Derived > &Q)
Find (L^T D L)-decomposition of Q-matrix via a backward Cholesky factorization in a bordering method ...
Definition Math.hpp:196
Lerp Search Result.
Definition Math.hpp:305
size_t u
Upper bound index (l + 1)
Definition Math.hpp:307
double t
[0, 1] for Interpolation, otherwise Extrapolation
Definition Math.hpp:308
size_t l
Lower bound index.
Definition Math.hpp:306