9#ifndef SE_MATH_UTIL_HPP
10#define SE_MATH_UTIL_HPP
14#include <Eigen/Geometry>
41template<
typename Scalar>
44template<
typename Scalar>
47template<
typename Scalar>
53static inline Eigen::Vector3f
75static inline Eigen::Matrix3f
hat(
const Eigen::Vector3f&
omega);
92static inline Eigen::Matrix4f
exp(
const Eigen::Matrix<float, 6, 1>& a);
101#include "impl/math_util_impl.hpp"
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)
constexpr int log2_const(int n)
constexpr Scalar sq(Scalar a)
static Eigen::Matrix3f exp_and_theta(const Eigen::Vector3f &omega, float &theta)
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