werkzeugkiste::geometry namespace

Math utils for 2D/3D geometry.

Namespaces

namespace constants
Mathematical constants.

Classes

template<typename T>
class Line2d_
Represents a line/segment in 2d Euclidean space.
template<typename T>
class Circle_
Represents a circle.
template<typename T>
class Plane_
Represents a plane in 3d Euclidean space.
template<typename T>
class Line3d_
Represents a line/segment in 3d Euclidean space.
template<typename T, std::size_t Dim>
class Vec
Template class to represent a vector/coordinate.

Typedefs

using Circle = Circle_<double>
using Line2d = Line2d_<double>
using Line3d = Line3d_<double>
using Plane = Plane_<double>
template<typename Tp, int Rows, int Columns>
using Matrix = Eigen::Matrix<Tp, Rows, Columns,(Columns> 1) ? Eigen::RowMajor :0>
template<typename Tp, int Rows>
using MatrixDynWidth = Eigen::Matrix<Tp, Rows, Eigen::Dynamic, Eigen::RowMajor>
using Mat3x3d = Matrix<double, 3, 3>
using Mat3x4d = Matrix<double, 3, 4>
using Vec2f = Vec<float, 2>
using Vec3f = Vec<float, 3>
using Vec4f = Vec<float, 4>
using Vec2d = Vec<double, 2>
using Vec3d = Vec<double, 3>
using Vec4d = Vec<double, 4>
using Vec2i = Vec<int32_t, 2>
using Vec3i = Vec<int32_t, 3>
using Vec4i = Vec<int32_t, 4>

Functions

template<typename Tp>
auto ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 4>& Rt) -> Matrix<Tp, 3, 4>
Returns the pinhole projection matrix P = K * [R | t] = K * Rt.
template<typename Tp>
auto ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Matrix<Tp, 3, 1>& t) -> Matrix<Tp, 3, 4>
Returns the pinhole projection matrix P = K * [R | t].
template<typename Tp>
auto ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t) -> Matrix<Tp, 3, 4>
Returns the projection matrix P = K * [R | t].
template<typename Tp>
auto CameraCenterFromRt(const Matrix<Tp, 3, 3>& R, const Matrix<Tp, 3, 1>& t) -> Vec<Tp, 3>
Returns the optical center ‘C = -R’ * t`.
template<typename Tp>
auto CameraCenterFromRt(const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t) -> Vec<Tp, 3>
Returns the optical center ‘C = -R’ * t`.
template<typename Tp>
auto CameraCenterFromRt(const Matrix<Tp, 3, 4>& Rt) -> Vec<Tp, 3>
Returns the optical center ‘C = -R’ * t`.
template<typename Tp>
auto GroundplaneToImageHomography(const Matrix<Tp, 3, 4>& P) -> Matrix<Tp, 3, 3>
Returns the ground plane-to-image plane homography from the camera's projection matrix.
template<typename Tp>
auto ImageToGroundplaneHomography(const Matrix<Tp, 3, 4>& P) -> Matrix<Tp, 3, 3>
Returns the image plane-to-ground plane homography from the camera's projection matrix.
template<typename Tp>
auto ImagePlaneInCameraCoordinateSystem() -> Plane_<Tp>
template<typename Tp>
auto ImagePlaneInWorldCoordinateSystem(const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t) -> Plane_<Tp>
Returns the image plane in the world reference frame, given the camera's extrinsic parameters.
template<typename Tp>
auto IsInFrontOfImagePlane(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 4>& Rt) -> bool
Returns true if the world point lies in front of the image plane.
template<typename Tp>
auto IsInFrontOfImagePlane(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t) -> bool
Returns true if the world point lies in front of the image plane.
template<typename Tp>
auto GetProjectionOfHorizon(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t, const Vec2i& image_size = {0, 0}) -> Line2d
Returns a the projected line of horizon for the given pinhole camera calibration.
template<typename Tp>
auto IsPointInsideImage(const Vec<Tp, 2>& pt, const Vec2i& img_size) -> bool
template<typename Tp>
auto ProjectsPointOntoImage(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 4>& P, const Vec2i& img_size, Vec<Tp, 2>* projected) -> bool
Returns true if the given world point would be visible if projected into the camera image. If projected is a valid pointer, it will be set to the projected image coordinates.
template<typename T>
auto IsPointInsideRectangle(const Vec<T, 2>& pt, const Vec<T, 2>& top_left, const Vec<T, 2>& size) -> bool
Returns true if the given point is within the rectangle.
template<int Rows, typename V>
auto VecToEigenMat(const V& vec) -> Matrix<typename V::value_type, Rows, 1>
Converts a werkzeugkiste vector to an Eigen vector (single-column matrix).
template<typename Tp, int Rows, int Columns>
auto EigenColToVec(const Matrix<Tp, Rows, Columns>& eig, int col) -> Vec<Tp, static_cast<std::size_t>Rows)>
Returns a vector for the given matrix column.
template<int Dim, typename V, typename... Vs>
auto VecsToEigenMat(const V& vec0, const Vs&... others) -> Matrix<typename V::value_type, Dim, static_cast<int>1+sizeof...(Vs))>
Returns a matrix where each column holds one vector.
template<typename Array, std::size_t... Idx>
auto ArrayToTuple(const Array& arr, std::index_sequence<Idx...>)
template<typename Tp, int Rows, int Columns>
auto EigenMatToVecTuple(const Matrix<Tp, Rows, Columns>& vec_mat)
Returns a tuple of vectors (one vector per matrix column).
template<typename V, typename... Vs, int Rows, int Columns>
auto TransformToVecs(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec0, const Vs&... others) -> std::tuple<Vec<typename V::value_type, static_cast<std::size_t>Rows)>, Vec<typename Vs::value_type, static_cast<std::size_t>Rows)>...>
Computes mat * [vec0, vec1, ...] and returns the result as a tuple of vectors.
template<typename V, typename... Vs, int Rows, int Columns>
auto TransformToVec(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec) -> Vec<typename V::value_type, static_cast<typename V::index_type>Rows)>
Convenience utility to avoid using std::tie() for a single vector. See TransformToVecs.
template<typename V, typename... Vs, int Rows, int Columns>
auto ProjectToVecs(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec0, const Vs&... others) -> std::tuple<Vec<typename V::value_type, static_cast<typename V::index_type>Rows - 1)>, Vec<typename Vs::value_type, static_cast<typename Vs::index_type>Rows - 1)>...>
Returns the (normalized) projection result.
template<typename V, typename... Vs, int Rows, int Columns>
auto ProjectToVec(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec) -> Vec<typename V::value_type, static_cast<std::size_t>Rows - 1)>
Convenience utility to avoid using std::tie() for a single vector. See ProjectToVecs.
template<typename Tp>
auto RotationX(Tp angle, bool angle_in_deg) -> Matrix<Tp, 3, 3> constexpr
Returns the 3x3 rotation matrix, rotating around the x-axis.
template<typename Tp>
auto RotationY(Tp angle, bool angle_in_deg) -> Matrix<Tp, 3, 3> constexpr
Returns the 3x3 rotation matrix, rotating around the y-axis.
template<typename Tp>
auto RotationZ(Tp angle, bool angle_in_deg) -> Matrix<Tp, 3, 3> constexpr
Returns the 3x3 rotation matrix, rotating around the z-axis.
template<typename Tp>
auto RotationMatrix(Tp angle_x, Tp angle_y, Tp angle_z, bool angles_in_deg) -> Matrix<Tp, 3, 3> constexpr
Returns the 3x3 rotation matrix in ZYX order.
auto Deg2Rad(double deg) -> double constexpr
Convert angle from degrees to radians.
auto Deg2Rad(float deg) -> float constexpr
auto Deg2Rad(int deg) -> double constexpr
auto Rad2Deg(double rad) -> double constexpr
Convert angle from radians to degrees.
auto Rad2Deg(float rad) -> float constexpr
template<typename T>
auto IsEpsZero(T x) -> bool constexpr
Uses the machine epsilon to check whether the given number is approximately zero, i.e. computes |x| <= eps for floating point numbers. Integral types will be compared to zero using the default equality check.
template<typename TVal, typename TTol = double>
auto IsClose(TVal x, TVal y, TTol relative_tolerance = 1e-9, TTol absolute_tolerance = 0.0) -> bool constexpr
Epsilon equality check for floating point numbers, similar to Python's math.isclose(), see PEP 485.
template<typename T>
auto IsEpsEqual(T x, T y) -> bool constexpr
Checks if two floating point numbers are "approximately" equal, according to a fixed relative tolerance (1e-9 for double precision, 1e-6 for single precision types), see IsClose. As there is no sane default value for the absolute tolerance, only the relative tolerance is checked.
template<typename T>
auto _util_sign(T x, std::false_type) -> int constexpr
Signum helper for unsigned types (to avoid compiler warnings).
template<typename T>
auto _util_sign(T x, std::true_type) -> int constexpr
Signum helper for signed types (to avoid compiler warnings when using unsigned types).
template<typename T>
auto Sign(T x) -> int constexpr
Signum function which returns +1 (if x is positive), 0 (if x equals 0), or -1 (if x is negative).
template<typename T>
auto RoundBase(T value, T base) -> std::enable_if_t<std::is_floating_point_v<T>, T>
template<typename T>
auto RoundBase(T value, T base) -> std::enable_if_t<std::is_integral_v<T>, T>
template<typename Tp>
auto TypeAbbreviation() -> std::enable_if_t<std::is_same_v<Tp, int16_t>, char> constexpr
template<typename Tp>
auto TypeAbbreviation() -> std::enable_if_t<std::is_same_v<Tp, int32_t>, char> constexpr
template<typename Tp>
auto TypeAbbreviation() -> std::enable_if_t<std::is_same_v<Tp, int64_t>, char> constexpr
template<typename Tp>
auto TypeAbbreviation() -> std::enable_if_t<std::is_same_v<Tp, float>, char> constexpr
template<typename Tp>
auto TypeAbbreviation() -> std::enable_if_t<std::is_same_v<Tp, double>, char> constexpr
template<typename T, std::size_t Dim>
auto LengthPolygon(const std::vector<Vec<T, Dim>>& points) -> double
Returns the length of the given polygon.
template<typename T, std::size_t Dim>
auto ScalarProjection(const Vec<T, Dim>& a, const Vec<T, Dim>& b) -> T
Returns the length of the vector projection.
template<typename T, std::size_t Dim>
auto VectorProjection(const Vec<T, Dim>& a, const Vec<T, Dim>& b) -> Vec<T, Dim>
Returns :math:\operatorname{proj}_{\mathbf{b}} \mathbf{a}, i.e. the projection of a onto b.
template<typename T>
auto AngleRadFromDirectionVec(const Vec<T, 2>& vec) -> double
Computes the angle (in radians) of a 2d direction vector w.r.t. the positive X axis. Result is in [-pi, +pi].
template<typename T>
auto AngleDegFromDirectionVec(const Vec<T, 2>& vec) -> double
Computes the angle (in degrees) of a 2d direction vector w.r.t. the positive X axis. Result is in [-180, +180].
auto DirectionVecFromAngleRad(double rad) -> Vec2d
Returns the unit direction vector given its angle (in radians) w.r.t. the positive X axis.
auto DirectionVecFromAngleDeg(double deg) -> Vec2d
Returns the unit direction vector given its angle (in degrees) w.r.t. the positive X axis.
template<typename T, std::size_t Dim, template<typename...> class Container = std::vector>
void MinMaxCoordinates(const Container<Vec<T, Dim>>& values, Vec<T, Dim>& min, Vec<T, Dim>& max)
Computes the minimum/maximum along each dimension.

Variables

template class WERKZEUGKISTE_GEOMETRY_EXPORT Circle_< double >
Available double-precision specialization for Circle_.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Line2d_< double >
Available specialization for a 2-dimensional line/segment with double precision.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Line3d_< double >
Available 3-dimensional double precision specialization of a line/segment.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Plane_< double >
The default plane type which uses double precision.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< float, 2 >
Single-precision, 2-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< float, 3 >
Single-precision, 3-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< float, 4 >
Single-precision, 4-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< double, 2 >
Double-precision, 2-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< double, 3 >
Double-precision, 3-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< double, 4 >
Double-precision, 4-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< int32_t, 2 >
Integral, 2-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< int32_t, 3 >
Integral, 3-dimensional vector.
template class WERKZEUGKISTE_GEOMETRY_EXPORT Vec< int32_t, 4 >
Integral, 4-dimensional vector.

Typedef documentation

using werkzeugkiste::geometry::Circle = Circle_<double>

using werkzeugkiste::geometry::Line2d = Line2d_<double>

using werkzeugkiste::geometry::Line3d = Line3d_<double>

using werkzeugkiste::geometry::Plane = Plane_<double>

template<typename Tp, int Rows, int Columns>
using werkzeugkiste::geometry::Matrix = Eigen::Matrix<Tp, Rows, Columns,(Columns> 1) ? Eigen::RowMajor :0>

template<typename Tp, int Rows>
using werkzeugkiste::geometry::MatrixDynWidth = Eigen::Matrix<Tp, Rows, Eigen::Dynamic, Eigen::RowMajor>

using werkzeugkiste::geometry::Mat3x3d = Matrix<double, 3, 3>

using werkzeugkiste::geometry::Mat3x4d = Matrix<double, 3, 4>

using werkzeugkiste::geometry::Vec2f = Vec<float, 2>

using werkzeugkiste::geometry::Vec3f = Vec<float, 3>

using werkzeugkiste::geometry::Vec4f = Vec<float, 4>

using werkzeugkiste::geometry::Vec2d = Vec<double, 2>

using werkzeugkiste::geometry::Vec3d = Vec<double, 3>

using werkzeugkiste::geometry::Vec4d = Vec<double, 4>

using werkzeugkiste::geometry::Vec2i = Vec<int32_t, 2>

using werkzeugkiste::geometry::Vec3i = Vec<int32_t, 3>

using werkzeugkiste::geometry::Vec4i = Vec<int32_t, 4>

Function documentation

template<typename Tp>
Matrix<Tp, 3, 4> werkzeugkiste::geometry::ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 4>& Rt)

Returns the pinhole projection matrix P = K * [R | t] = K * Rt.

template<typename Tp>
Matrix<Tp, 3, 4> werkzeugkiste::geometry::ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Matrix<Tp, 3, 1>& t)

Returns the pinhole projection matrix P = K * [R | t].

template<typename Tp>
Matrix<Tp, 3, 4> werkzeugkiste::geometry::ProjectionMatrixFromKRt(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t)

Returns the projection matrix P = K * [R | t].

template<typename Tp>
Vec<Tp, 3> werkzeugkiste::geometry::CameraCenterFromRt(const Matrix<Tp, 3, 3>& R, const Matrix<Tp, 3, 1>& t)

Returns the optical center ‘C = -R’ * t`.

template<typename Tp>
Vec<Tp, 3> werkzeugkiste::geometry::CameraCenterFromRt(const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t)

Returns the optical center ‘C = -R’ * t`.

template<typename Tp>
Vec<Tp, 3> werkzeugkiste::geometry::CameraCenterFromRt(const Matrix<Tp, 3, 4>& Rt)

Returns the optical center ‘C = -R’ * t`.

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::GroundplaneToImageHomography(const Matrix<Tp, 3, 4>& P)

Returns the ground plane-to-image plane homography from the camera's projection matrix.

H_gp2cam = [p_0, p_1, p_3], where p_i is the i-th column of P

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::ImageToGroundplaneHomography(const Matrix<Tp, 3, 4>& P)

Returns the image plane-to-ground plane homography from the camera's projection matrix.

template<typename Tp>
Plane_<Tp> werkzeugkiste::geometry::ImagePlaneInCameraCoordinateSystem()

template<typename Tp>
Plane_<Tp> werkzeugkiste::geometry::ImagePlaneInWorldCoordinateSystem(const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t)

Returns the image plane in the world reference frame, given the camera's extrinsic parameters.

template<typename Tp>
bool werkzeugkiste::geometry::IsInFrontOfImagePlane(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 4>& Rt)

Returns true if the world point lies in front of the image plane.

template<typename Tp>
bool werkzeugkiste::geometry::IsInFrontOfImagePlane(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t)

Returns true if the world point lies in front of the image plane.

template<typename Tp>
Line2d werkzeugkiste::geometry::GetProjectionOfHorizon(const Matrix<Tp, 3, 3>& K, const Matrix<Tp, 3, 3>& R, const Vec<Tp, 3>& t, const Vec2i& image_size = {0, 0})

Returns a the projected line of horizon for the given pinhole camera calibration.

If a valid image size is given, the line will be clipped to the visible region. Check result.IsValid(), as the horizon may lie outside of the image.

template<typename Tp>
bool werkzeugkiste::geometry::IsPointInsideImage(const Vec<Tp, 2>& pt, const Vec2i& img_size)

template<typename Tp>
bool werkzeugkiste::geometry::ProjectsPointOntoImage(const Vec<Tp, 3>& pt_world, const Matrix<Tp, 3, 4>& P, const Vec2i& img_size, Vec<Tp, 2>* projected)

Returns true if the given world point would be visible if projected into the camera image. If projected is a valid pointer, it will be set to the projected image coordinates.

template<typename T>
bool werkzeugkiste::geometry::IsPointInsideRectangle(const Vec<T, 2>& pt, const Vec<T, 2>& top_left, const Vec<T, 2>& size)

Returns true if the given point is within the rectangle.

template<int Rows, typename V>
Matrix<typename V::value_type, Rows, 1> werkzeugkiste::geometry::VecToEigenMat(const V& vec)

Converts a werkzeugkiste vector to an Eigen vector (single-column matrix).

template<typename Tp, int Rows, int Columns>
Vec<Tp, static_cast<std::size_t>Rows)> werkzeugkiste::geometry::EigenColToVec(const Matrix<Tp, Rows, Columns>& eig, int col)

Returns a vector for the given matrix column.

template<int Dim, typename V, typename... Vs>
Matrix<typename V::value_type, Dim, static_cast<int>1+sizeof...(Vs))> werkzeugkiste::geometry::VecsToEigenMat(const V& vec0, const Vs&... others)

Returns a matrix where each column holds one vector.

Note that the matrix size is fixed at compile time, thus it will be created on the stack. This function should only be used for a maximum of up to 32 vectors. Refer to the Eigen3 docs for details: https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html

template<typename Array, std::size_t... Idx>
auto werkzeugkiste::geometry::ArrayToTuple(const Array& arr, std::index_sequence<Idx...>)

template<typename Tp, int Rows, int Columns>
auto werkzeugkiste::geometry::EigenMatToVecTuple(const Matrix<Tp, Rows, Columns>& vec_mat)

Returns a tuple of vectors (one vector per matrix column).

template<typename V, typename... Vs, int Rows, int Columns>
std::tuple<Vec<typename V::value_type, static_cast<std::size_t>Rows)>, Vec<typename Vs::value_type, static_cast<std::size_t>Rows)>...> werkzeugkiste::geometry::TransformToVecs(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec0, const Vs&... others)

Computes mat * [vec0, vec1, ...] and returns the result as a tuple of vectors.

The vector dimensionality D must be either equal to or 1 less than the number of projection matrix columns C. If D == C - 1, a homogeneous coordinate will be implicitly added to each vector, i.e. [vec0.X(), vec0.Y(), ..., 1].

Example:

wkg::Vec2d v1{17, 42}, v2{9, -3}, v3{0, 0.01};
wkg::Matrix<double, 4, 2> M;
M << 1, 2, 3, 4, 5, 6, 7, 8;
wkg::Vec4d a, b, c;
std::tie(out1, out2, out3) = TransformToVecs(T_matrix, in1, in2, in3);
// Or with padded homogeneous coordinate:
wkg::Matrix<double, 4, 3> M;
M << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12;
wkg::Vec4d a, b, c;
std::tie(out1, out2, out3) = TransformToVecs(T_matrix, in1, in2, in3);

template<typename V, typename... Vs, int Rows, int Columns>
Vec<typename V::value_type, static_cast<typename V::index_type>Rows)> werkzeugkiste::geometry::TransformToVec(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec)

Convenience utility to avoid using std::tie() for a single vector. See TransformToVecs.

template<typename V, typename... Vs, int Rows, int Columns>
std::tuple<Vec<typename V::value_type, static_cast<typename V::index_type>Rows - 1)>, Vec<typename Vs::value_type, static_cast<typename Vs::index_type>Rows - 1)>...> werkzeugkiste::geometry::ProjectToVecs(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec0, const Vs&... others)

Returns the (normalized) projection result.

Returns A tuple of vectors.

Computes mat * [vec0, vec1, ...], divides the result by the homogeneous coordinate (i.e. last row) and strips the homogeneous coordinate.

The vector dimensionality must be either equal to or 1 less than the number of projection matrix columns. If not equal, a homogeneous coordinate will be implicitly added to each vector, i.e. [vec0.x(), vec0.y(), ..., 1].

Example:

wkg::Vec3d v1{17, 42, 1}, v2{9, -3, 1};
wkg::Matrix<double, 3, 3> H;
H << 1, 2, 3,
     4, 5, 6,
     7, 8, 9;
wkg::Vec2d out1, out2;
std::tie(out1, out2) = ProjectToVecs(H, v1, v2);

template<typename V, typename... Vs, int Rows, int Columns>
Vec<typename V::value_type, static_cast<std::size_t>Rows - 1)> werkzeugkiste::geometry::ProjectToVec(const Matrix<typename V::value_type, Rows, Columns>& mat, const V& vec)

Convenience utility to avoid using std::tie() for a single vector. See ProjectToVecs.

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::RotationX(Tp angle, bool angle_in_deg) constexpr

Returns the 3x3 rotation matrix, rotating around the x-axis.

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::RotationY(Tp angle, bool angle_in_deg) constexpr

Returns the 3x3 rotation matrix, rotating around the y-axis.

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::RotationZ(Tp angle, bool angle_in_deg) constexpr

Returns the 3x3 rotation matrix, rotating around the z-axis.

template<typename Tp>
Matrix<Tp, 3, 3> werkzeugkiste::geometry::RotationMatrix(Tp angle_x, Tp angle_y, Tp angle_z, bool angles_in_deg) constexpr

Returns the 3x3 rotation matrix in ZYX order.

double werkzeugkiste::geometry::Deg2Rad(double deg) constexpr

Convert angle from degrees to radians.

float werkzeugkiste::geometry::Deg2Rad(float deg) constexpr

double werkzeugkiste::geometry::Deg2Rad(int deg) constexpr

double werkzeugkiste::geometry::Rad2Deg(double rad) constexpr

Convert angle from radians to degrees.

float werkzeugkiste::geometry::Rad2Deg(float rad) constexpr

template<typename T>
bool werkzeugkiste::geometry::IsEpsZero(T x) constexpr

Uses the machine epsilon to check whether the given number is approximately zero, i.e. computes |x| <= eps for floating point numbers. Integral types will be compared to zero using the default equality check.

template<typename TVal, typename TTol = double>
bool werkzeugkiste::geometry::IsClose(TVal x, TVal y, TTol relative_tolerance = 1e-9, TTol absolute_tolerance = 0.0) constexpr

Epsilon equality check for floating point numbers, similar to Python's math.isclose(), see PEP 485.

Modulo special case handling, this function returns:

  • (|x-y| <= rel_tol * |x|)
  • or (|x-y| <= rel_tol * |y|)
  • or (|x-y| <= abs_tol)

template<typename T>
bool werkzeugkiste::geometry::IsEpsEqual(T x, T y) constexpr

Checks if two floating point numbers are "approximately" equal, according to a fixed relative tolerance (1e-9 for double precision, 1e-6 for single precision types), see IsClose. As there is no sane default value for the absolute tolerance, only the relative tolerance is checked.

template<typename T>
int werkzeugkiste::geometry::_util_sign(T x, std::false_type) constexpr

Signum helper for unsigned types (to avoid compiler warnings).

template<typename T>
int werkzeugkiste::geometry::_util_sign(T x, std::true_type) constexpr

Signum helper for signed types (to avoid compiler warnings when using unsigned types).

template<typename T>
int werkzeugkiste::geometry::Sign(T x) constexpr

Signum function which returns +1 (if x is positive), 0 (if x equals 0), or -1 (if x is negative).

This type-safe implementation is based on https://stackoverflow.com/a/4609795 by user79758 (CC BY-SA 4.0).

template<typename T>
std::enable_if_t<std::is_floating_point_v<T>, T> werkzeugkiste::geometry::RoundBase(T value, T base)

template<typename T>
std::enable_if_t<std::is_integral_v<T>, T> werkzeugkiste::geometry::RoundBase(T value, T base)

template<typename Tp>
std::enable_if_t<std::is_same_v<Tp, int16_t>, char> werkzeugkiste::geometry::TypeAbbreviation() constexpr

template<typename Tp>
std::enable_if_t<std::is_same_v<Tp, int32_t>, char> werkzeugkiste::geometry::TypeAbbreviation() constexpr

template<typename Tp>
std::enable_if_t<std::is_same_v<Tp, int64_t>, char> werkzeugkiste::geometry::TypeAbbreviation() constexpr

template<typename Tp>
std::enable_if_t<std::is_same_v<Tp, float>, char> werkzeugkiste::geometry::TypeAbbreviation() constexpr

template<typename Tp>
std::enable_if_t<std::is_same_v<Tp, double>, char> werkzeugkiste::geometry::TypeAbbreviation() constexpr

template<typename T, std::size_t Dim>
double werkzeugkiste::geometry::LengthPolygon(const std::vector<Vec<T, Dim>>& points)

Returns the length of the given polygon.

template<typename T, std::size_t Dim>
T werkzeugkiste::geometry::ScalarProjection(const Vec<T, Dim>& a, const Vec<T, Dim>& b)

Returns the length of the vector projection.

Scalar projection is the length of the vector projection, which is the vector component of a in the direction of b. See also: https://en.wikipedia.org/wiki/Vector_projection

template<typename T, std::size_t Dim>
Vec<T, Dim> werkzeugkiste::geometry::VectorProjection(const Vec<T, Dim>& a, const Vec<T, Dim>& b)

Returns :math:\operatorname{proj}_{\mathbf{b}} \mathbf{a}, i.e. the projection of a onto b.

See also: https://en.wikipedia.org/wiki/Vector_projection

template<typename T>
double werkzeugkiste::geometry::AngleRadFromDirectionVec(const Vec<T, 2>& vec)

Computes the angle (in radians) of a 2d direction vector w.r.t. the positive X axis. Result is in [-pi, +pi].

template<typename T>
double werkzeugkiste::geometry::AngleDegFromDirectionVec(const Vec<T, 2>& vec)

Computes the angle (in degrees) of a 2d direction vector w.r.t. the positive X axis. Result is in [-180, +180].

Vec2d werkzeugkiste::geometry::DirectionVecFromAngleRad(double rad)

Returns the unit direction vector given its angle (in radians) w.r.t. the positive X axis.

Vec2d werkzeugkiste::geometry::DirectionVecFromAngleDeg(double deg)

Returns the unit direction vector given its angle (in degrees) w.r.t. the positive X axis.

template<typename T, std::size_t Dim, template<typename...> class Container = std::vector>
void werkzeugkiste::geometry::MinMaxCoordinates(const Container<Vec<T, Dim>>& values, Vec<T, Dim>& min, Vec<T, Dim>& max)

Computes the minimum/maximum along each dimension.

Useful to get axis-aligned bounding boxes, a starting point for hull computations, etc.

Variable documentation

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Circle_< double >

Available double-precision specialization for Circle_.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Line2d_< double >

Available specialization for a 2-dimensional line/segment with double precision.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Line3d_< double >

Available 3-dimensional double precision specialization of a line/segment.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Plane_< double >

The default plane type which uses double precision.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< float, 2 >

Single-precision, 2-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< float, 3 >

Single-precision, 3-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< float, 4 >

Single-precision, 4-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< double, 2 >

Double-precision, 2-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< double, 3 >

Double-precision, 3-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< double, 4 >

Double-precision, 4-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< int32_t, 2 >

Integral, 2-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< int32_t, 3 >

Integral, 3-dimensional vector.

template class WERKZEUGKISTE_GEOMETRY_EXPORT werkzeugkiste::geometry::Vec< int32_t, 4 >

Integral, 4-dimensional vector.