INSTINCT Code Coverage Report


Directory: src/
File: Navigation/Math/Math.hpp
Date: 2025-02-07 16:54:41
Exec Total Coverage
Lines: 44 46 95.7%
Functions: 10 11 90.9%
Branches: 34 56 60.7%

Line Branch Exec Source
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
9 /// @file Math.hpp
10 /// @brief Simple Math functions
11 /// @author T. Topp (topp@ins.uni-stuttgart.de)
12 /// @author N. Stahl (HiWi: Elliptical integral)
13 /// @date 2023-07-04
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
27 namespace NAV::math
28 {
29
30 /// @brief Calculates the factorial of an unsigned integer
31 /// @param[in] n Unsigned integer
32 /// @return The factorial of 'n'
33 uint64_t factorial(uint64_t n);
34
35 /// @brief Round the number to the specified amount of digits
36 /// @param[in] value Value to round
37 /// @param[in] digits Amount of digits
38 /// @return The rounded value
39 template<std::floating_point T>
40 343402 constexpr T round(const T& value, size_t digits)
41 {
42 343402 auto factor = std::pow(10, digits);
43 343402 return std::round(value * factor) / factor;
44 }
45
46 /// @brief Round the number to the specified amount of significant digits
47 /// @param[in] value Value to round
48 /// @param[in] digits Amount of digits
49 /// @return The rounded value
50 template<std::floating_point T>
51 40 constexpr T roundSignificantDigits(T value, size_t digits)
52 {
53
2/2
✓ Branch 0 taken 1 times.
✓ Branch 1 taken 39 times.
40 if (value == 0.0) { return 0.0; }
54 // LOG_DEBUG("value = {:.13e} --> Round to {} digits", value, digits);
55 39 auto absVal = gcem::abs(value);
56 39 auto log10 = static_cast<int32_t>(gcem::log10(absVal));
57
6/6
✓ Branch 0 taken 33 times.
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 18 times.
✓ Branch 3 taken 15 times.
✓ Branch 4 taken 6 times.
✓ Branch 5 taken 12 times.
39 auto exp = log10 + (log10 > 0 || (log10 == 0 && absVal >= 1.0));
58 39 auto fac = static_cast<T>(digits) - static_cast<T>(exp);
59 // LOG_DEBUG(" log10 = {}, exp = {}, fac = {}", log10, exp, fac);
60 39 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 39 return static_cast<T>(gcem::round(value * factor) / factor);
64 }
65
66 /// @brief Interprets the input integer with certain amount of Bits as Output type. Takes care of sign extension
67 /// @tparam Out Output type
68 /// @tparam Bits Size of the input data
69 /// @tparam In Input data type (needs to be bigger than the amount of Bits)
70 /// @param[in] in Number as two's complement, with the sign bit (+ or -) occupying the MSB
71 /// @return Output type
72 template<std::integral Out, size_t Bits, std::integral In>
73 3099 constexpr Out interpretAs(In in)
74 {
75 static_assert(Bits < sizeof(In) * 8);
76 static_assert(Bits < sizeof(Out) * 8);
77
78 3099 constexpr size_t N = sizeof(Out) * 8 - Bits;
79 3099 return static_cast<Out>(static_cast<Out>((in & static_cast<In>(gcem::pow(2, Bits) - 1)) << N) >> N);
80 }
81
82 /// @brief Calculates the skew symmetric matrix of the given vector.
83 /// This is needed to perform the cross product with a scalar product operation
84 /// @tparam Derived Derived Eigen Type
85 /// @param[in] a The vector
86 /// @return Skew symmetric matrix
87 /// @note See Groves (2013) equation (2.50)
88 template<typename Derived>
89 3013918 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetricMatrix(const Eigen::MatrixBase<Derived>& a)
90 {
91
1/2
✓ Branch 1 taken 2959619 times.
✗ Branch 2 not taken.
3013918 INS_ASSERT_USER_ERROR(a.cols() == 1, "Given Eigen Object must be a vector");
92
2/2
✓ Branch 1 taken 2960241 times.
✓ Branch 2 taken 309 times.
3013245 INS_ASSERT_USER_ERROR(a.rows() == 3, "Given Vector must have 3 Rows");
93
94 3013867 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewMat;
95
5/10
✓ Branch 1 taken 2955855 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2955060 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2957976 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2957163 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2961218 times.
✗ Branch 14 not taken.
3005786 skewMat << 0, -a(2), a(1),
96
5/10
✓ Branch 1 taken 2959130 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2962842 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2961796 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2959193 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2962367 times.
✗ Branch 14 not taken.
3014844 a(2), 0, -a(0),
97
5/10
✓ Branch 1 taken 2960371 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2962844 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2960998 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2963750 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2963033 times.
✗ Branch 14 not taken.
3015993 -a(1), a(0), 0;
98
99 3015366 return skewMat;
100 }
101
102 /// @brief Calculates the square of a skew symmetric matrix of the given vector.
103 /// @tparam Derived Derived Eigen Type
104 /// @param[in] a The vector
105 /// @return Square of skew symmetric matrix
106 template<typename Derived>
107 Eigen::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
120 /// @brief Calculates the secant of a value (sec(x) = csc(pi/2 - x) = 1 / cos(x))
121 template<std::floating_point T>
122 T sec(const T& x)
123 {
124 return 1.0 / std::cos(x);
125 }
126
127 /// @brief Calculates the cosecant of a value (csc(x) = sec(pi/2 - x) = 1 / sin(x))
128 template<std::floating_point T>
129 31113 T csc(const T& x)
130 {
131 31113 return 1.0 / std::sin(x);
132 }
133
134 /// @brief Returns the sign of the given value
135 /// @param[in] val Value to get the sign from
136 /// @return Sign of the given value
137 template<typename T>
138 1343753 int sgn(const T& val)
139 {
140 1343753 return (T(0) < val) - (val < T(0));
141 }
142
143 /// @brief Find (L^T D L)-decomposition of Q-matrix via outer product method
144 /// @param[in] Qmatrix Symmetric positive definite matrix to be factored
145 /// @return L - Factor matrix (strict lower triangular)
146 /// @return D - Vector with entries of the diagonal matrix
147 /// @note See \cite deJonge1996 de Jonge 1996, Algorithm FMFAC5
148 /// @attention Consider using NAV::math::LtDLdecomp_choleskyFact() because it is faster by up to a factor 10
149 template<typename Derived>
150 std::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
188 /// @brief Find (L^T D L)-decomposition of Q-matrix via a backward Cholesky factorization in a bordering method formulation
189 /// @param[in] Q Symmetric positive definite matrix to be factored
190 /// @return L - Factor matrix (strict lower triangular)
191 /// @return D - Vector with entries of the diagonal matrix
192 /// @note See \cite deJonge1996 de Jonge 1996, Algorithm FMFAC6
193 template<typename Derived>
194 std::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
230 /// @brief Calculates the squared norm of the vector and matrix
231 ///
232 /// \anchor eq-squaredNorm \f{equation}{ \label{eq:eq-squaredNorm}
233 /// ||\mathbf{\dots}||^2_{\mathbf{Q}} = (\dots)^T \mathbf{Q}^{-1} (\dots)
234 /// \f}
235 /// @param a Vector
236 /// @param Q Covariance matrix of the vector
237 /// @return Squared norm
238 template<typename DerivedA, typename DerivedQ>
239 typename 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
249 /// @brief Calculates the cumulative distribution function (CDF) of the standard normal distribution
250 ///
251 /// \anchor eq-normalDistCDF \f{equation}{ \label{eq:eq-normalDistCDF}
252 /// \Phi(x) = \int\displaylimits_{-\infty}^x \frac{1}{\sqrt{2\pi}} \exp{\left(-\frac{1}{2} v^2\right)} \text{d}v
253 /// \f}
254 /// which can be expressed with the error function
255 /// \anchor eq-normalDistCDF-erf \f{equation}{ \label{eq:eq-normalDistCDF-erf}
256 /// \Phi(x) = \frac{1}{2} \left[ 1 + \text{erf}{\left(\frac{x}{\sqrt{2}}\right)} \right]
257 /// \f}
258 /// Using the property
259 /// \anchor eq-erf-minus \f{equation}{ \label{eq:eq-erf-minus}
260 /// \text{erf}{\left( -x \right)} = -\text{erf}{\left( x \right)}
261 /// \f}
262 /// and the complementary error function
263 /// \anchor eq-erfc \f{equation}{ \label{eq:eq-erfc}
264 /// \text{erfc}{\left( x \right)} = 1 - \text{erf}{\left( x \right)}
265 /// \f}
266 /// we can simplify equation \ref eq-normalDistCDF-erf to
267 /// \anchor eq-normalDistCDF-erfc \f{equation}{ \label{eq:eq-normalDistCDF-erfc}
268 /// \begin{aligned}
269 /// \Phi(x) &= \frac{1}{2} \left[ 1 - \text{erf}{\left(-\frac{x}{\sqrt{2}}\right)} \right] \\
270 /// &= \frac{1}{2} \text{erfc}{\left(-\frac{x}{\sqrt{2}}\right)}
271 /// \end{aligned}
272 /// \f}
273 ///
274 /// @param value Value to calculate the CDF for
275 double normalCDF(double value);
276
277 /// @brief Change the sign of x according to the value of y
278 /// @param[in] x input value
279 /// @param[in] y input value
280 /// @return -x or +x
281 template<typename T>
282 2612 T sign(const T& x, const T& y)
283 {
284 // similar function 'sign' in fortran
285
2/2
✓ Branch 0 taken 498 times.
✓ Branch 1 taken 2114 times.
2612 if (y >= 0.0)
286 {
287 498 return fabs(x);
288 }
289 2114 return -1.0 * fabs(x);
290 }
291
292 /// @brief Linear interpolation between vectors
293 /// @param a Left value
294 /// @param b Right value
295 /// @param t Multiplier. [0, 1] for interpolation
296 /// @return a + t * (b - a)
297 template<typename Derived>
298 101564 typename Derived::PlainObject lerp(const Eigen::MatrixBase<Derived>& a, const Eigen::MatrixBase<Derived>& b, const typename Derived::Scalar& t)
299 {
300
4/8
✓ Branch 1 taken 101564 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 101564 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 101564 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 101564 times.
✗ Branch 11 not taken.
101564 return a + t * (b - a);
301 }
302
303 /// Lerp Search Result
304 struct LerpSearchResult
305 {
306 size_t l; ///< Lower bound index
307 size_t u; ///< Upper bound index (l + 1)
308 double t; ///< [0, 1] for Interpolation, otherwise Extrapolation
309 };
310
311 /// @brief Searches the value in the data container
312 /// @param[in] data Data container
313 /// @param[in] value Value to search
314 3 LerpSearchResult lerpSearch(const auto& data, const auto& value)
315 {
316 3 auto i = static_cast<size_t>(std::distance(data.begin(), std::upper_bound(data.begin(), data.end(), value)));
317
1/2
✓ Branch 0 taken 3 times.
✗ Branch 1 not taken.
3 if (i > 0) { i--; }
318
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 3 times.
3 if (i == data.size() - 1) { i--; }
319 3 const auto& lb = data.at(i);
320 3 const auto& ub = data.at(i + 1);
321 3 double t = (value - lb) / (ub - lb);
322
323 3 return { .l = i, .u = i + 1, .t = t };
324 }
325
326 /// @brief Bilinear interpolation
327 /// @param[in] tx Distance in x component to interpolate [0, 1]
328 /// @param[in] ty Distance in y component to interpolate [0, 1]
329 /// @param[in] c00 Value for tx = ty = 0
330 /// @param[in] c10 Value for tx = 1 and ty = 0
331 /// @param[in] c01 Value for tx = 0 and ty = 1
332 /// @param[in] c11 Value for tx = ty = 1
333 ///
334 /// c01 ------ c11
335 /// | |
336 /// | |
337 /// | |
338 /// c00 ------ c10
339 ///
340 /// @note See https://www.scratchapixel.com/lessons/mathematics-physics-for-computer-graphics/interpolation/bilinear-filtering.html
341 9 auto bilinearInterpolation(const double& tx, const double& ty,
342 const auto& c00, const auto& c10,
343 const auto& c01, const auto& c11)
344 {
345 9 auto a = c00 * (1 - tx) + c10 * tx;
346 9 auto b = c01 * (1 - tx) + c11 * tx;
347 9 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
352 /// @brief Calculates the incomplete elliptical integral of the second kind
353 /// @param[in] phi Interval bound the integration uses from 0 to phi
354 /// @param[in] m Function parameter that is integrated 1-m*sin(t)^2
355 /// @return Incomplete elliptical integral of the second kind
356 /// @note See http://www2.iap.fr/users/pichon/doc/html_xref/elliptic-es.html
357 double calcEllipticalIntegral(double phi, double m);
358
359 } // namespace NAV::math
360