0.2.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 <cstdint>
18#include <type_traits>
19#include <Eigen/Core>
20#include <gcem.hpp>
21#include <fmt/format.h>
22
23#include "util/Assert.h"
24
25namespace NAV::math
26{
27
31uint64_t factorial(uint64_t n);
32
37template<typename T,
38 typename = std::enable_if_t<std::is_floating_point_v<T>>>
39constexpr T round(const T& value, size_t digits)
40{
41 auto factor = std::pow(10, digits);
42 return std::round(value * factor) / factor;
43}
44
49template<typename T,
50 typename = std::enable_if_t<std::is_floating_point_v<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<typename Out, size_t Bits, typename In,
73 typename = std::enable_if_t<std::is_integral_v<Out>>,
74 typename = std::enable_if_t<std::is_integral_v<In>>>
75constexpr Out interpretAs(In in)
76{
77 static_assert(Bits < sizeof(In) * 8);
78 static_assert(Bits < sizeof(Out) * 8);
79
80 constexpr size_t N = sizeof(Out) * 8 - Bits;
81 return static_cast<Out>(static_cast<Out>((in & static_cast<In>(gcem::pow(2, Bits) - 1)) << N) >> N);
82}
83
90template<typename Derived>
91Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetricMatrix(const Eigen::MatrixBase<Derived>& a)
92{
93 INS_ASSERT_USER_ERROR(a.cols() == 1, "Given Eigen Object must be a vector");
94 INS_ASSERT_USER_ERROR(a.rows() == 3, "Given Vector must have 3 Rows");
95
96 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewMat;
97 skewMat << 0, -a(2), a(1),
98 a(2), 0, -a(0),
99 -a(1), a(0), 0;
100
101 return skewMat;
102}
103
108template<typename Derived>
109Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetricMatrixSquared(const Eigen::MatrixBase<Derived>& a)
110{
111 INS_ASSERT_USER_ERROR(a.cols() == 1, "Given Eigen Object must be a vector");
112 INS_ASSERT_USER_ERROR(a.rows() == 3, "Given Vector must have 3 Rows");
113
114 Eigen::Matrix<typename Derived::Scalar, 3, 3> skewMat2;
115 skewMat2 << std::pow(a(2), 2) + std::pow(a(1), 2), a(0) * a(1), a(0) * a(2),
116 a(0) * a(1), std::pow(a(2), 2) + std::pow(a(0), 2), a(1) * a(2),
117 a(0) * a(2), a(1) * a(2), std::pow(a(0), 2) + std::pow(a(1), 2);
118
119 return skewMat2;
120}
121
123template<typename T,
124 typename = std::enable_if_t<std::is_floating_point_v<T>>>
125T sec(const T& x)
126{
127 return 1.0 / std::cos(x);
128}
129
131template<typename T,
132 typename = std::enable_if_t<std::is_floating_point_v<T>>>
133T csc(const T& x)
134{
135 return 1.0 / std::sin(x);
136}
137
141template<typename T>
142int sgn(const T& val)
143{
144 return (T(0) < val) - (val < T(0));
145}
146
153template<typename Derived>
154std::pair<Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>,
155 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime>>
156 LtDLdecomp_outerProduct(const Eigen::MatrixBase<Derived>& Qmatrix)
157{
158 using Eigen::seq;
159
160 auto n = Qmatrix.rows();
161 Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime> Q = Qmatrix.template triangularView<Eigen::Lower>();
162 Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime> L;
163 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime> D;
164
165 if constexpr (Derived::RowsAtCompileTime == Eigen::Dynamic)
166 {
167 L = Eigen::Matrix<typename Derived::Scalar, Eigen::Dynamic, Eigen::Dynamic>::Zero(n, n);
168 D.setZero(n);
169 }
170 else
171 {
172 L = Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>::Zero();
173 D.setZero();
174 }
175
176 for (Eigen::Index i = n - 1; i >= 0; i--)
177 {
178 D(i) = Q(i, i);
179 L(i, seq(0, i)) = Q(i, seq(0, i)) / std::sqrt(Q(i, i));
180
181 for (Eigen::Index j = 0; j <= i - 1; j++)
182 {
183 Q(j, seq(0, j)) -= L(i, seq(0, j)) * L(i, j);
184 }
185 L(i, seq(0, i)) /= L(i, i);
186 }
187
188 return { L, D };
189}
190
196template<typename Derived>
197std::pair<Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>,
198 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime>>
199 LtDLdecomp_choleskyFact(const Eigen::MatrixBase<Derived>& Q)
200{
201 using Eigen::seq;
202
203 auto n = Q.rows();
204 typename Derived::PlainObject L = Q.template triangularView<Eigen::Lower>();
205 Eigen::Vector<typename Derived::Scalar, Derived::RowsAtCompileTime> D;
206 double cmin = 1;
207
208 if constexpr (Derived::RowsAtCompileTime == Eigen::Dynamic) { D.setZero(n); }
209 else { D.setZero(); }
210
211 for (Eigen::Index j = n - 1; j >= 0; j--)
212 {
213 for (Eigen::Index i = n - 1; i >= j + 1; i--)
214 {
215 L(i, j) = (L(i, j) - L(seq(i + 1, n - 1), j).dot(L(seq(i + 1, n - 1), i))) / L(i, i);
216 }
217 double t = L(j, j) - L(seq(j + 1, n - 1), j).dot(L(seq(j + 1, n - 1), j));
218 double c = t / L(j, j);
219 if (c < cmin)
220 {
221 cmin = c;
222 }
223 L(j, j) = std::sqrt(t);
224 }
225 for (Eigen::Index i = 0; i < n; i++)
226 {
227 L.row(i).leftCols(i) /= L(i, i);
228 D(i) = std::pow(L(i, i), 2.0);
229 L(i, i) = 1;
230 }
231
232 return { L, D };
233}
234
243template<typename DerivedA, typename DerivedQ>
244typename DerivedA::Scalar squaredNormVectorMatrix(const Eigen::MatrixBase<DerivedA>& a, const Eigen::MatrixBase<DerivedQ>& Q)
245{
246 static_assert(DerivedA::ColsAtCompileTime == Eigen::Dynamic || DerivedA::ColsAtCompileTime == 1);
247 INS_ASSERT_USER_ERROR(a.cols() == 1, "Parameter 'a' has to be a vector");
248 INS_ASSERT_USER_ERROR(a.rows() == Q.rows(), "Parameter 'a' and 'Q' need to have same size");
249 INS_ASSERT_USER_ERROR(Q.cols() == Q.rows(), "Parameter 'Q' needs to be quadratic");
250
251 return a.transpose() * Q.inverse() * a;
252}
253
280double normalCDF(double value);
281
286template<typename T>
287T sign(const T& x, const T& y)
288{
289 // similar function 'sign' in fortran
290 if (y >= 0.0)
291 {
292 return fabs(x);
293 }
294 return -1.0 * fabs(x);
295}
296
302template<typename Derived>
303typename Derived::PlainObject lerp(const Eigen::MatrixBase<Derived>& a, const Eigen::MatrixBase<Derived>& b, const typename Derived::Scalar& t)
304{
305 return a + t * (b - a);
306}
307
313double calcEllipticalIntegral(double phi, double m);
314
315} // namespace NAV::math
Assertion helpers.
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
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:199
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:244
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:75
T csc(const T &x)
Calculates the cosecant of a value (csc(x) = sec(pi/2 - x) = 1 / sin(x))
Definition Math.hpp:133
int sgn(const T &val)
Returns the sign of the given value.
Definition Math.hpp:142
T sign(const T &x, const T &y)
Change the sign of x according to the value of y.
Definition Math.hpp:287
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:109
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:91
constexpr T roundSignificantDigits(T value, size_t digits)
Round the number to the specified amount of significant digits.
Definition Math.hpp:51
T sec(const T &x)
Calculates the secant of a value (sec(x) = csc(pi/2 - x) = 1 / cos(x))
Definition Math.hpp:125
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.
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:303
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:156
constexpr T round(const T &value, size_t digits)
Round the number to the specified amount of digits.
Definition Math.hpp:39