RobWorkProject  23.9.11-
Classes | Typedefs | Functions | Variables
rw::math Namespace Reference

Matrices, vectors, configurations, and more. More...

Classes

class  CameraMatrix
 The PerspectiveTransform2D is a perspective transform in 2D. The homographic transform can be used to map one arbitrary 2D quadrilateral into another. More...
 
class  EigenDecomposition
 Type representing a set of eigen values and eigen vectors. More...
 
class  EAA
 A class for representing an equivalent angle-axis rotation. More...
 
class  Function
 Interface for functions. More...
 
class  InertiaMatrix
 A 3x3 inertia matrix. More...
 
class  Metric
 Template interface for metrics on type T. More...
 
class  ManhattanMetric
 Manhattan distance metric for vector types. More...
 
class  WeightedManhattanMetric
 Weighted Manhattan distance metric for vector types. More...
 
class  EuclideanMetric
 Euclidean distance metric for vector types. More...
 
class  WeightedEuclideanMetric
 Weighted Euclidean metric for vector types. More...
 
class  InfinityMetric
 Infinity norm distance metric for vector types. More...
 
class  WeightedInfinityMetric
 Weighted infinity norm metric for vector types. More...
 
class  MahalanobisMetric
 Mahalanobis distance metric for vector types. More...
 
class  Rotation3DAngleMetric
 a distance metric over rotations. The distance between two rotations is the smalles angle that rotates the one into the other. More...
 
class  Transform3DAngleMetric
 distance metrics between points in SE3. More...
 
class  PerspectiveTransform2D
 The PerspectiveTransform2D is a perspective transform in 2D. More...
 
class  Polynomial
 Representation of an ordinary polynomial with scalar coefficients (that can be both real and complex). More...
 
class  Pose2D
 A Pose3D \( \mathbf{x}\in \mathbb{R}^6 \) describes a position and orientation in 3-dimensions. More...
 
class  Pose6D
 A Pose6D \( \mathbf{x}\in \mathbb{R}^6 \) describes a position and orientation in 3-dimensions. More...
 
class  Quaternion
 A Quaternion \( \mathbf{q}\in \mathbb{R}^4 \) a complex number used to describe rotations in 3-dimensional space. \( q_w+{\bf i}\ q_x+ {\bf j} q_y+ {\bf k}\ q_z \). More...
 
class  Rotation2D
 A 2x2 rotation matrix \( \mathbf{R}\in SO(2) \). More...
 
class  Rotation3D
 A 3x3 rotation matrix \( \mathbf{R}\in SO(3) \). More...
 
class  Rotation3DVector
 An abstract base class for Rotation3D parameterisations. More...
 
class  RPY
 A class for representing Roll-Pitch-Yaw Euler angle rotations. More...
 
class  Statistics
 Class for collecting data and calculating simple statistics. More...
 
class  Transform2D
 
class  Transform3D
 A 4x4 homogeneous transform matrix \( \mathbf{T}\in SE(3) \). More...
 
class  Vector
 Configuration vector. More...
 
class  Vector2D
 A 2D vector \( \mathbf{v}\in \mathbb{R}^2 \). More...
 
class  Vector3D
 A 3D vector \( \mathbf{v}\in \mathbb{R}^3 \). More...
 
class  VectorND
 A N-Dimensional Vector. More...
 
class  VelocityScrew6D
 Class for representing 6 degrees of freedom velocity screws. More...
 
class  Wrench6D
 Class for representing 6 degrees of freedom wrenches. More...
 
class  Function1Diff
 Interface for functions which are 1 time differentiable. More...
 
class  Jacobian
 A Jacobian class. A jacobian with m rows and n columns. More...
 
class  Line2D
 Describes a line segment in 2D. More...
 
class  Line2DPolar
 Describes a line in 2D in polar coordinates. More...
 
class  LinearAlgebra
 Collection of Linear Algebra functions. More...
 
class  Math
 Utility functions for the rw::math module. More...
 
class  MetricFactory
 Metric constructor functions. More...
 
class  MetricUtil
 Various metrics and other distance measures. More...
 
class  PolynomialND
 Representation of a polynomial that can have non-scalar coefficients (polynomial matrix). More...
 
class  PolynomialSolver
 Find solutions for roots of real and complex polynomial equations. More...
 
class  ProjectionMatrix
 projection matrix More...
 
class  Q
 Configuration vector. More...
 
class  Random
 Generation of random numbers. More...
 
class  Rotation2DVector
 
struct  Transform2DIdentity
 A 3x3 homogeneous transform matrix \( \mathbf{T}\in SE(2) \). More...
 
struct  Transform2DIdentity< double >
 
struct  Transform2DIdentity< float >
 
class  Transform3DVector
 this class is a interpolatable Transform3D, consisting of a Vecor3D and a Quaternion. It is implemented to be very Interconvertable with a Transform3D, and allow operations souch as Transform * scalar and Transform + Transform. More...
 

Typedefs

using CameraMatrixd = CameraMatrix< double >
 
using CameraMatrixf = CameraMatrix< float >
 
using EAAd = EAA< double >
 
using EAAf = EAA< float >
 
using EigenDecompositiond = EigenDecomposition< double >
 
using EigenDecompositionf = EigenDecomposition< float >
 
using InertiaMatrixd = InertiaMatrix< double >
 
using InertiaMatrixf = InertiaMatrix< float >
 
typedef Metric< rw::math::QQMetric
 Metrics on configurations.
 
typedef Metric< rw::math::Transform3D< double > > Transform3DMetric
 Metric on Transdform3D.
 
using PerspectiveTransform2Dd = PerspectiveTransform2D< double >
 
using PerspectiveTransform2Df = PerspectiveTransform2D< float >
 
using Pose2Dd = Pose2D< double >
 
using Pose2Df = Pose2D< float >
 
using Pose6Dd = Pose6D< double >
 
using Pose6Df = Pose6D< float >
 
using Quaterniond = Quaternion< double >
 
using Quaternionf = Quaternion< float >
 
using Rotation2Dd = Rotation2D< double >
 
using Rotation2Df = Rotation2D< float >
 
using Rotation3Dd = Rotation3D< double >
 
using Rotation3Df = Rotation3D< float >
 
using RPYd = RPY< double >
 
using RPYf = RPY< float >
 
using Transform2Dd = Transform2D< double >
 
using Transform2Df = Transform2D< float >
 
using Transform3Dd = Transform3D< double >
 
using Transform3Df = Transform3D< float >
 
using Transform3DVectord = Transform3DVector< double >
 
using Transform3DVectorf = Transform3DVector< float >
 
using Vectord = Vector< double >
 
using Vectorf = Vector< float >
 
using Vector2Dd = Vector2D< double >
 
using Vector2Df = Vector2D< float >
 
using Vector3Dd = Vector3D< double >
 
using Vector3Df = Vector3D< float >
 
template<class T >
using Vector6D = VectorND< 6, T >
 
using VelocityScrew6Dd = VelocityScrew6D< double >
 
using VelocityScrew6Df = VelocityScrew6D< float >
 
using Wrench6Dd = Wrench6D< double >
 
using Wrench6Df = Wrench6D< float >
 

Functions

template<class T >
rw::math::Vector3D< T > cross (const rw::math::Vector3D< T > &v1, const EAA< T > &v2)
 
template<class Q , class T >
const EAA< Qcast (const EAA< T > &eaa)
 Casts EAA<T> to EAA<Q> More...
 
template<class Q >
InertiaMatrix< Qinverse (const InertiaMatrix< Q > &aRb)
 Calculates the inverse \( \robabx{b}{a}{\mathbf{R}} = \robabx{a}{b}{\mathbf{R}}^{-1} \) of a rotation matrix. More...
 
template<class Q , class T >
InertiaMatrix< Qcast (const InertiaMatrix< T > &rot)
 Casts InertiaMatrix<T> to InertiaMatrix<Q> More...
 
Polynomial operator* (const PolynomialND< Eigen::Matrix< double, 1, 3 >> &a, const PolynomialND< Eigen::Matrix< double, 3, 1 >> &b)
 Multiply 3D polynomial vector with 3D polynomial vector. More...
 
PolynomialND< Eigen::Vector3d > operator* (const PolynomialND< Eigen::Vector3d > &polynomial, const Polynomial<> &p)
 Multiply 3D polynomial vector with a polynomial with scalar coefficients. More...
 
PolynomialND< Eigen::Matrix< double, 1, 3 > > operator* (const PolynomialND< Eigen::Matrix< double, 1, 3 >> &polynomial, const Polynomial<> &p)
 Multiply 3D polynomial vector with a polynomial with scalar coefficients. More...
 
PolynomialND< Eigen::Matrix3d > operator* (const PolynomialND< Eigen::Matrix3d > &polynomial, const Polynomial<> &p)
 Multiply 3D polynomial matrix with a polynomial with scalar coefficients. More...
 
Polynomial< float > operator* (const PolynomialND< Eigen::Matrix< float, 1, 3 >, float > &a, const PolynomialND< Eigen::Matrix< float, 3, 1 >, float > &b)
 
PolynomialND< Eigen::Vector3f, float > operator* (const PolynomialND< Eigen::Vector3f, float > &polynomial, const Polynomial< float > &p)
 Multiply 3D polynomial vector with a polynomial with scalar coefficients. More...
 
PolynomialND< Eigen::Matrix< float, 1, 3 >, float > operator* (const PolynomialND< Eigen::Matrix< float, 1, 3 >, float > &polynomial, const Polynomial< float > &p)
 
PolynomialND< Eigen::Matrix3f, float > operator* (const PolynomialND< Eigen::Matrix3f, float > &polynomial, const Polynomial< float > &p)
 Multiply 3D polynomial matrix with a polynomial with scalar coefficients. More...
 
PolynomialND< Eigen::Vector3d > operator* (const PolynomialND< Eigen::Matrix3d > &A, const PolynomialND< Eigen::Vector3d > &b)
 Multiply 3D polynomial matrix with 3D polynomial vector. More...
 
PolynomialND< Eigen::Matrix< double, 1, 3 > > operator* (const PolynomialND< Eigen::Matrix< double, 1, 3 >> &a, const PolynomialND< Eigen::Matrix3d > &A)
 Multiply 3D polynomial vector with 3D polynomial matrix. More...
 
PolynomialND< Eigen::Vector3d > operator* (const PolynomialND< Eigen::Matrix3d > &A, const Eigen::Vector3d &b)
 
PolynomialND< Eigen::Matrix< double, 1, 3 > > operator* (const PolynomialND< Eigen::Matrix< double, 1, 3 >> &a, const Eigen::Matrix3d &A)
 
PolynomialND< Eigen::Vector3f, float > operator* (const PolynomialND< Eigen::Matrix3f, float > &A, const PolynomialND< Eigen::Vector3f, float > &b)
 
PolynomialND< Eigen::Matrix< float, 1, 3 >, float > operator* (const PolynomialND< Eigen::Matrix< float, 1, 3 >, float > &a, const PolynomialND< Eigen::Matrix3f, float > &A)
 
PolynomialND< Eigen::Vector3f, float > operator* (const PolynomialND< Eigen::Matrix3f, float > &A, const Eigen::Vector3f &b)
 
PolynomialND< Eigen::Matrix< float, 1, 3 >, float > operator* (const PolynomialND< Eigen::Matrix< float, 1, 3 >, float > &a, const Eigen::Matrix3f &A)
 
template<class Q , class T >
const Pose6D< Qcast (const Pose6D< T > &pose)
 Casts Pose6D<T> to Pose6D<Q> More...
 
rw::math::Q concat (const Q &q1, const Q &q2)
 concatenates q1 onto q2 such that the returned q has the configurations of q1 in [0;q1.size()[ and has q2 in [q1.size();q1.size()+q2.size()[ More...
 
template<class T >
Quaternion< T > ln (const Quaternion< T > &q)
 calculates the natural logerithm of this quaternion More...
 
template<class T >
Quaternion< T > exp (const Quaternion< T > &q)
 this will return the exponential of this quaternion \( e^Quaternion \) More...
 
template<class T >
Quaternion< T > inverse (const Quaternion< T > &q)
 Calculate the inverse Quaternion. More...
 
template<class T >
Quaternion< T > pow (const Quaternion< T > &q, double power)
 calculates the quaternion lifted to the power of power More...
 
template<class Q , class T >
const Quaternion< Qcast (const Quaternion< T > &quaternion)
 Casts Quaternion<T> to Quaternion<Q> More...
 
template<class T >
const Rotation2D< T > Rotation2DIdentity ()
 
template<class R , class T >
const Rotation2D< R > cast (const Rotation2D< T > &rot)
 Casts Rotation2D<T> to Rotation2D<Q> More...
 
template<class T >
const Rotation2D< T > transpose (const Rotation2D< T > &aRb)
 Find the transpose of aRb. More...
 
template<class T >
const Rotation3D< T > Rotation3DIdentity ()
 
template<class Q , class T >
const RPY< Qcast (const RPY< T > &rpy)
 Casts RPY<T> to RPY<Q> More...
 
template<class Q , class T >
const Transform2D< Qcast (const Transform2D< T > &trans)
 Cast Transform2D<T> to Transform2D<Q> More...
 
template<class Q , class T >
const Transform3D< Qcast (const Transform3D< T > &trans)
 Cast Transform3D<T> to Transform3D<Q> More...
 
template<class A >
bool operator!= (const Vector< A > &q1, const Vector< A > &q2)
 Inequality operator. More...
 
template<class A >
rw::math::Vector< A > concat (const Vector< A > &q1, const Vector< A > &q2)
 concatenates q1 onto q2 such that the returned q has the configurations of q1 in [0;q1.size()[ and has q2 in [q1.size();q1.size()+q2.size()[ More...
 
template<class T >
cross (const Vector2D< T > &v1, const Vector2D< T > &v2)
 Calculates the 2D vector cross product \( \mathbf{v1} \times \mathbf{v2} \). More...
 
template<class T >
double dot (const Vector2D< T > &v1, const Vector2D< T > &v2)
 Calculates the dot product \( \mathbf{v1} . \mathbf{v2} \). More...
 
template<class T >
double angle (const Vector2D< T > &v1, const Vector2D< T > &v2)
 calculates the counter clock-wise angle from v1 to v2. the value returned will be in the interval [-2Pi,2Pi]
 
template<class T >
const Vector2D< T > normalize (const Vector2D< T > &v)
 Returns the normalized vector \(\mathbf{n}=\frac{\mathbf{v}}{\|\mathbf{v}\|} \). More...
 
template<class Q , class T >
const Vector2D< Qcast (const Vector2D< T > &v)
 Casts Vector2D<T> to Vector2D<Q> More...
 
template<class T >
norm1 (const VelocityScrew6D< T > &screw)
 Takes the 1-norm of the velocity screw. All elements both angular and linear are given the same weight. More...
 
template<class T >
norm2 (const VelocityScrew6D< T > &screw)
 Takes the 2-norm of the velocity screw. All elements both angular and linear are given the same weight. More...
 
template<class T >
normInf (const VelocityScrew6D< T > &screw)
 Takes the infinite norm of the velocity screw. All elements both angular and linear are given the same weight. More...
 
template<class Q , class T >
const VelocityScrew6D< Qcast (const VelocityScrew6D< T > &vs)
 Casts VelocityScrew6D<T> to VelocityScrew6D<Q> More...
 
template<class T >
norm1 (const Wrench6D< T > &wrench)
 Takes the 1-norm of the wrench. All elements both force and torque are given the same weight. More...
 
template<class T >
norm2 (const Wrench6D< T > &wrench)
 Takes the 2-norm of the wrench. All elements both force and tporque are given the same weight. More...
 
template<class T >
normInf (const Wrench6D< T > &wrench)
 Takes the infinite norm of the wrench. All elements both force and torque are given the same weight. More...
 
template<class Q , class T >
const Wrench6D< Qcast (const Wrench6D< T > &vs)
 Casts Wrench6D<T> to Wrench6D<Q> More...
 

Variables

const double Pi = 3.1415926535897932384626433832795
 
const double Inch2Meter = 0.0254
 
const double Meter2Inch = 1 / Inch2Meter
 
const double Deg2Rad = Pi / 180
 
const double Rad2Deg = 180 / Pi
 
const Transform2D< double > Transform2DDoubleIdentity
 
const Transform2D< float > Transform2DFloatIdentity
 

Detailed Description

Matrices, vectors, configurations, and more.

Function Documentation

◆ cast() [1/11]

const EAA<Q> rw::math::cast ( const EAA< T > &  eaa)

Casts EAA<T> to EAA<Q>

Parameters
eaa[in] EAA with type T
Returns
EAA with type Q

◆ cast() [2/11]

InertiaMatrix<Q> rw::math::cast ( const InertiaMatrix< T > &  rot)

Casts InertiaMatrix<T> to InertiaMatrix<Q>

Parameters
rot[in] InertiaMatrix with type T
Returns
InertiaMatrix with type Q

◆ cast() [3/11]

const Pose6D<Q> rw::math::cast ( const Pose6D< T > &  pose)

Casts Pose6D<T> to Pose6D<Q>

Parameters
pose[in] Pose6D with type T
Returns
Pose6D with type Q

◆ cast() [4/11]

const Quaternion<Q> rw::math::cast ( const Quaternion< T > &  quaternion)
inline

Casts Quaternion<T> to Quaternion<Q>

Parameters
quaternion[in] Quarternion with type T
Returns
Quaternion with type Q

◆ cast() [5/11]

const Rotation2D<R> rw::math::cast ( const Rotation2D< T > &  rot)

Casts Rotation2D<T> to Rotation2D<Q>

Parameters
rot[in] Rotation2D with type T
Returns
Rotation2D with type R

◆ cast() [6/11]

const RPY<Q> rw::math::cast ( const RPY< T > &  rpy)

Casts RPY<T> to RPY<Q>

Parameters
rpy[in] RPY with type T
Returns
RPY with type Q

◆ cast() [7/11]

const Transform2D<Q> rw::math::cast ( const Transform2D< T > &  trans)

Cast Transform2D<T> to Transform2D<Q>

Parameters
trans[in] Transform2D with type T
Returns
Transform2D with type Q

◆ cast() [8/11]

const Transform3D<Q> rw::math::cast ( const Transform3D< T > &  trans)

Cast Transform3D<T> to Transform3D<Q>

Parameters
trans[in] Transform3D with type T
Returns
Transform3D with type Q

◆ cast() [9/11]

const Vector2D<Q> rw::math::cast ( const Vector2D< T > &  v)

Casts Vector2D<T> to Vector2D<Q>

Parameters
v[in] Vector2D with type T
Returns
Vector2D with type Q

◆ cast() [10/11]

const VelocityScrew6D<Q> rw::math::cast ( const VelocityScrew6D< T > &  vs)

Casts VelocityScrew6D<T> to VelocityScrew6D<Q>

Parameters
vs[in] VelocityScrew6D with type T
Returns
VelocityScrew6D with type Q

◆ cast() [11/11]

const Wrench6D<Q> rw::math::cast ( const Wrench6D< T > &  vs)

Casts Wrench6D<T> to Wrench6D<Q>

Parameters
vs[in] Wrench6D with type T
Returns
Wrench6D with type Q

◆ concat() [1/2]

rw::math::Q rw::math::concat ( const Q q1,
const Q q2 
)

concatenates q1 onto q2 such that the returned q has the configurations of q1 in [0;q1.size()[ and has q2 in [q1.size();q1.size()+q2.size()[

Parameters
q1[in] the first Q
q2[in] the second Q
Returns
the concatenation of q1 and q2

◆ concat() [2/2]

rw::math::Vector<A> rw::math::concat ( const Vector< A > &  q1,
const Vector< A > &  q2 
)

concatenates q1 onto q2 such that the returned q has the configurations of q1 in [0;q1.size()[ and has q2 in [q1.size();q1.size()+q2.size()[

Parameters
q1[in] the first Vector
q2[in] the second Vector
Returns
the concatenation of q1 and q2

◆ cross()

T rw::math::cross ( const Vector2D< T > &  v1,
const Vector2D< T > &  v2 
)

Calculates the 2D vector cross product \( \mathbf{v1} \times \mathbf{v2} \).

Parameters
v1[in] \( \mathbf{v1} \)
v2[in] \( \mathbf{v2} \)
Returns
the cross product \( \mathbf{v1} \times \mathbf{v2} \)

The 2D vector cross product is defined as:

\( \mathbf{v1} \times \mathbf{v2} = v1_x * v2_y - v1_y * v2_x \)

◆ dot()

double rw::math::dot ( const Vector2D< T > &  v1,
const Vector2D< T > &  v2 
)

Calculates the dot product \( \mathbf{v1} . \mathbf{v2} \).

Parameters
v1[in] \( \mathbf{v1} \)
v2[in] \( \mathbf{v2} \)
Returns
the dot product \( \mathbf{v1} . \mathbf{v2} \)

◆ exp()

Quaternion<T> rw::math::exp ( const Quaternion< T > &  q)

this will return the exponential of this quaternion \( e^Quaternion \)

Parameters
q[in] the quaternion being operated on
Returns
the exponential of this quaternion

◆ inverse() [1/2]

InertiaMatrix<Q> rw::math::inverse ( const InertiaMatrix< Q > &  aRb)

Calculates the inverse \( \robabx{b}{a}{\mathbf{R}} = \robabx{a}{b}{\mathbf{R}}^{-1} \) of a rotation matrix.

Parameters
aRb[in] the rotation matrix \( \robabx{a}{b}{\mathbf{R}} \)
Returns
the matrix inverse \( \robabx{b}{a}{\mathbf{R}} = \robabx{a}{b}{\mathbf{R}}^{-1} \)

\( \robabx{b}{a}{\mathbf{R}} = \robabx{a}{b}{\mathbf{R}}^{-1} = \robabx{a}{b}{\mathbf{R}}^T \)

◆ inverse() [2/2]

Quaternion<T> rw::math::inverse ( const Quaternion< T > &  q)

Calculate the inverse Quaternion.

Parameters
q[in] the quaternion being operated on
Returns
the inverse quaternion

◆ ln()

Quaternion<T> rw::math::ln ( const Quaternion< T > &  q)

calculates the natural logerithm of this quaternion

Parameters
q[in] the quaternion being operated on
Returns
natural logetihm

◆ norm1() [1/2]

T rw::math::norm1 ( const VelocityScrew6D< T > &  screw)

Takes the 1-norm of the velocity screw. All elements both angular and linear are given the same weight.

Parameters
screw[in] the velocity screw
Returns
the 1-norm

◆ norm1() [2/2]

T rw::math::norm1 ( const Wrench6D< T > &  wrench)

Takes the 1-norm of the wrench. All elements both force and torque are given the same weight.

Parameters
wrench[in] the wrench
Returns
the 1-norm

◆ norm2() [1/2]

T rw::math::norm2 ( const VelocityScrew6D< T > &  screw)

Takes the 2-norm of the velocity screw. All elements both angular and linear are given the same weight.

Parameters
screw[in] the velocity screw
Returns
the 2-norm

◆ norm2() [2/2]

T rw::math::norm2 ( const Wrench6D< T > &  wrench)

Takes the 2-norm of the wrench. All elements both force and tporque are given the same weight.

Parameters
wrench[in] the wrench
Returns
the 2-norm

◆ normalize()

const Vector2D<T> rw::math::normalize ( const Vector2D< T > &  v)

Returns the normalized vector \(\mathbf{n}=\frac{\mathbf{v}}{\|\mathbf{v}\|} \).

If \( \| \mathbf{v} \| = 0\) then the zero vector is returned.

Parameters
v[in] \( \mathbf{v} \) which should be normalized
Returns
the normalized vector \( \mathbf{n} \)

◆ normInf() [1/2]

T rw::math::normInf ( const VelocityScrew6D< T > &  screw)

Takes the infinite norm of the velocity screw. All elements both angular and linear are given the same weight.

Parameters
screw[in] the velocity screw
Returns
the infinite norm

◆ normInf() [2/2]

T rw::math::normInf ( const Wrench6D< T > &  wrench)

Takes the infinite norm of the wrench. All elements both force and torque are given the same weight.

Parameters
wrench[in] the wrench
Returns
the infinite norm

◆ operator!=()

bool rw::math::operator!= ( const Vector< A > &  q1,
const Vector< A > &  q2 
)
inline

Inequality operator.

The inverse of operator==().

◆ pow()

Quaternion<T> rw::math::pow ( const Quaternion< T > &  q,
double  power 
)

calculates the quaternion lifted to the power of power

Parameters
q[in] the quaternion being operated on
power[in] the power the quaternion is lifted to
Returns
\( Quaternion^power \)

◆ transpose()

const Rotation2D<T> rw::math::transpose ( const Rotation2D< T > &  aRb)

Find the transpose of aRb.

The transpose of a rotation matrix is the same as the inverse.

Variable Documentation

◆ Deg2Rad

const double Deg2Rad = Pi / 180

Convert degrees to radians

◆ Inch2Meter

const double Inch2Meter = 0.0254

Converts inch to meter

◆ Meter2Inch

const double Meter2Inch = 1 / Inch2Meter

Converts meter to inch

◆ Pi

const double Pi = 3.1415926535897932384626433832795

Definition of Pi

◆ Rad2Deg

const double Rad2Deg = 180 / Pi

Converts radians to degrees