supereight
Loading...
Searching...
No Matches
math_util.hpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2016-2019 Emanuele Vespa
3 * SPDX-FileCopyrightText: 2021-2023 Smart Robotics Lab, Imperial College London, Technical University of Munich
4 * SPDX-FileCopyrightText: 2021 Nils Funk
5 * SPDX-FileCopyrightText: 2021-2023 Sotiris Papatheodorou
6 * SPDX-License-Identifier: BSD-3-Clause
7 */
8
9#ifndef SE_MATH_UTIL_HPP
10#define SE_MATH_UTIL_HPP
11
12
13
14#include <Eigen/Geometry>
15#include <cmath>
16
17
18
19namespace se {
20namespace math {
21
23inline const Eigen::Vector3f g_invalid_normal = Eigen::Vector3f::Zero();
24
25template<typename T>
26constexpr bool is_power_of_two(const T x);
27
28constexpr int log2_const(int n);
29
30static inline unsigned power_two_up(const float x);
31
32template<typename T>
33T fracf(const T& v);
34
35template<typename T>
36T floorf(const T& v);
37
38template<typename T>
39T fabs(const T& v);
40
41template<typename Scalar>
42constexpr Scalar sq(Scalar a);
43
44template<typename Scalar>
45constexpr Scalar cu(Scalar a);
46
47template<typename Scalar>
48bool in(const Scalar v, const Scalar a, const Scalar b);
49
53static inline Eigen::Vector3f
54plane_normal(const Eigen::Vector3f& p1, const Eigen::Vector3f& p2, const Eigen::Vector3f& p3);
55
75static inline Eigen::Matrix3f hat(const Eigen::Vector3f& omega);
76
77static inline Eigen::Matrix3f exp_and_theta(const Eigen::Vector3f& omega, float& theta);
78
92static inline Eigen::Matrix4f exp(const Eigen::Matrix<float, 6, 1>& a);
93
94
95
96} // namespace math
97} // namespace se
98
99
100
101#include "impl/math_util_impl.hpp"
102
103
104
105#endif // SE_MATH_UTIL_HPP
Definition image.hpp:19
static Eigen::Matrix3f hat(const Eigen::Vector3f &omega)
hat-operator
static Eigen::Matrix4f exp(const Eigen::Matrix< float, 6, 1 > &a)
Group exponential.
const Eigen::Vector3f g_invalid_normal
The value used for a normal vector that can't be computed.
Definition math_util.hpp:23
constexpr Scalar cu(Scalar a)
static unsigned power_two_up(const float x)
constexpr bool is_power_of_two(const T x)
T floorf(const T &v)
T fracf(const T &v)
constexpr int log2_const(int n)
constexpr Scalar sq(Scalar a)
static Eigen::Matrix3f exp_and_theta(const Eigen::Vector3f &omega, float &theta)
T fabs(const T &v)
static Eigen::Vector3f plane_normal(const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3)
Compute the normal vector of a plane defined by 3 points.
bool in(const Scalar v, const Scalar a, const Scalar b)
Helper wrapper to allocate and de-allocate octants in the octree.
Definition bounded_vector.hpp:14