Robotics Library  0.7.0
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
rl::math Namespace Reference

Common mathematical functions. More...

Namespaces

 metrics
 
 spatial
 Spatial vector algebra.
 

Classes

class  Circular
 Circular segment function that maps from a time x to a point on a circular trajectory. More...
 
class  Circular< Vector2 >
 Circular segment function that maps from a time x to a point in 2D on a circular trajectory. More...
 
class  Circular< Vector3 >
 Circular segment function that maps from a time x to a point in 3D on a circular trajectory. More...
 
class  Function
 A mathematical mapping from Real -> ArrayX. More...
 
class  GnatNearestNeighbors
 Geometric Near-Neighbor Access Tree (GNAT). More...
 
class  Kalman
 Kalman filter. More...
 
class  KdtreeBoundingBoxNearestNeighbors
 k-d tree. More...
 
class  KdtreeNearestNeighbors
 k-d tree. More...
 
class  LinearNearestNeighbors
 Linear nearest neighbor search. More...
 
class  LowPass
 Low-pass filter. More...
 
class  NestedFunction
 
class  Pid
 Proportional-Integral-Derivative controller. More...
 
class  Polynomial
 A vector-valued polynomial function from Real -> T. More...
 
class  Polynomial< Quaternion >
 
class  Spline
 A piecewise Function of Polynomial functions. More...
 
class  Spline< Quaternion >
 
class  TrapezoidalVelocity
 
class  TypeTraits
 
class  TypeTraits< ::Eigen::Array< Scalar, Rows, Cols, Options, MaxRows, MaxCols > >
 
class  TypeTraits< ::Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > >
 

Typedefs

typedef ::Eigen::Array< Real, ::Eigen::Dynamic, 1 > ArrayX
 
typedef ::Eigen::Array< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > ArrayXX
 
typedef ::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
 
typedef ::Eigen::Matrix< Real, 2, 2 > Matrix22
 
typedef ::Eigen::Matrix< Real, 3, 3 > Matrix33
 
typedef ::Eigen::Matrix< Real, 4, 4 > Matrix44
 
typedef ::Eigen::Matrix< Real, 6, 6 > Matrix66
 
typedef ::Eigen::Block< MatrixMatrixBlock
 
typedef ::Eigen::Block< Matrix22Matrix22Block
 
typedef ::Eigen::Block< Matrix33Matrix33Block
 
typedef ::Eigen::Block< Matrix44Matrix44Block
 
typedef ::Eigen::Block< Matrix66Matrix66Block
 
typedef Matrix::ColXpr MatrixColumn
 
typedef Matrix22::ColXpr Matrix22Column
 
typedef Matrix33::ColXpr Matrix33Column
 
typedef Matrix44::ColXpr Matrix44Column
 
typedef Matrix66::ColXpr Matrix66Column
 
typedef Matrix::RowXpr MatrixRow
 
typedef Matrix22::RowXpr Matrix22Row
 
typedef Matrix33::RowXpr Matrix33Row
 
typedef Matrix44::RowXpr Matrix44Row
 
typedef Matrix66::RowXpr Matrix66Row
 
typedef ::Eigen::Block< const MatrixConstMatrixBlock
 
typedef ::Eigen::Block< const Matrix22ConstMatrix22Block
 
typedef ::Eigen::Block< const Matrix33ConstMatrix33Block
 
typedef ::Eigen::Block< const Matrix44ConstMatrix44Block
 
typedef ::Eigen::Block< const Matrix66ConstMatrix66Block
 
typedef Matrix::ConstColXpr ConstMatrixColumn
 
typedef Matrix22::ConstColXpr ConstMatrix22Column
 
typedef Matrix33::ConstColXpr ConstMatrix33Column
 
typedef Matrix44::ConstColXpr ConstMatrix44Column
 
typedef Matrix66::ConstColXpr ConstMatrix66Column
 
typedef Matrix::ConstRowXpr ConstMatrixRow
 
typedef Matrix22::ConstRowXpr ConstMatrix22Row
 
typedef Matrix33::ConstRowXpr ConstMatrix33Row
 
typedef Matrix44::ConstRowXpr ConstMatrix44Row
 
typedef Matrix66::ConstRowXpr ConstMatrix66Row
 
typedef ::Eigen::Ref< MatrixMatrixRef
 
typedef ::Eigen::Ref< const MatrixConstMatrixRef
 
typedef ::Eigen::Quaternion< RealQuaternion
 
typedef double Real
 
typedef Matrix33 Rotation
 
typedef Matrix33Block RotationBlock
 
typedef Matrix33Column RotationColumn
 
typedef Matrix33Row RotationRow
 
typedef ConstMatrix33Block ConstRotationBlock
 
typedef ConstMatrix33Column ConstRotationColumn
 
typedef ConstMatrix33Row ConstRotationRow
 
typedef ::Eigen::AngleAxis< RealAngleAxis
 
typedef spatial::ArticulatedBodyInertia< RealArticulatedBodyInertia
 
typedef spatial::ForceVector< RealForceVector
 
typedef spatial::MotionVector< RealMotionVector
 
typedef spatial::PlueckerTransform< RealPlueckerTransform
 
typedef spatial::RigidBodyInertia< RealRigidBodyInertia
 
typedef ::Eigen::Transform< Real, 3, ::Eigen::Affine > Transform
 Rigid transformation in 3D. More...
 
typedef ::Eigen::Translation< Real, 3 > Translation
 Translation in 3D. More...
 
typedef ::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
 
typedef ::Eigen::Matrix< Real, 2, 1 > Vector2
 
typedef ::Eigen::Matrix< Real, 3, 1 > Vector3
 
typedef ::Eigen::Matrix< Real, 4, 1 > Vector4
 
typedef ::Eigen::Matrix< Real, 6, 1 > Vector6
 
typedef ::Eigen::VectorBlock< Vector, ::Eigen::Dynamic > VectorBlock
 
typedef ::Eigen::VectorBlock< Vector2, ::Eigen::Dynamic > Vector2Block
 
typedef ::Eigen::VectorBlock< Vector3, ::Eigen::Dynamic > Vector3Block
 
typedef ::Eigen::VectorBlock< Vector4, ::Eigen::Dynamic > Vector4Block
 
typedef ::Eigen::VectorBlock< Vector6, ::Eigen::Dynamic > Vector6Block
 
typedef ::Eigen::VectorBlock< const Vector, ::Eigen::Dynamic > ConstVectorBlock
 
typedef ::Eigen::VectorBlock< const Vector2, ::Eigen::Dynamic > ConstVector2Block
 
typedef ::Eigen::VectorBlock< const Vector3, ::Eigen::Dynamic > ConstVector3Block
 
typedef ::Eigen::VectorBlock< const Vector4, ::Eigen::Dynamic > ConstVector4Block
 
typedef ::Eigen::VectorBlock< const Vector6, ::Eigen::Dynamic > ConstVector6Block
 
typedef ::Eigen::Ref< VectorVectorRef
 
typedef ::Eigen::Ref< const VectorConstVectorRef
 

Enumerations

enum  Unit {
  UNIT_NONE, UNIT_METER, UNIT_KILOGRAM, UNIT_SECOND,
  UNIT_AMPERE, UNIT_KELVIN, UNIT_MOLE, UNIT_CANDELA,
  UNIT_RADIAN, UNIT_HERTZ, UNIT_NEWTON, UNIT_VOLT,
  UNIT_CELSIUS, UNIT_METER_PER_SECOND, UNIT_METER_PER_SECOND_SQUARED, UNIT_RADIAN_PER_SECOND,
  UNIT_RADIAN_PER_SECOND_SQUARED, UNIT_NEWTON_SECOND, UNIT_NEWTON_METER_SECOND, UNIT_NEWTON_METER
}
 

Functions

template<typename T >
cbrt (const T &arg)
 
template<typename T >
sign (const T &arg)
 
void cartesianToPolar (const Real &x, const Real &y, Real &r, Real &theta)
 
void cartesianToSpherical (const Real &x, const Real &y, const Real &z, Real &rho, Real &psi, Real &theta)
 
void polarToCartesian (const Real &r, const Real &theta, Real &x, Real &y)
 
void sphericalToCartesian (const Real &rho, const Real &psi, const Real &theta, Real &x, Real &y, Real &z)
 

Variables

static const Real FUNCTION_BOUNDARY = 1.0e-8f
 
static const Real DEG2RAD = static_cast<Real>(M_PI) / 180.0f
 
static const Real GIGA2UNIT = 1.0e+9f
 
static const Real GRAVITY = 9.80665f
 [m · s-2] More...
 
static const Real KILO2UNIT = 1.0e+3f
 
static const Real MEGA2UNIT = 1.0e+6f
 
static const Real MICRO2UNIT = 1.0e-6f
 
static const Real MILLI2UNIT = 1.0e-3f
 
static const Real NANO2UNIT = 1.0e-9f
 
static const Real RAD2DEG = 180.0f / static_cast<Real>(M_PI)
 
static const Real UNIT2GIGA = 1.0e-9f
 
static const Real UNIT2KILO = 1.0e-3f
 
static const Real UNIT2MEGA = 1.0e-6f
 
static const Real UNIT2MICRO = 1.0e+6f
 
static const Real UNIT2MILLI = 1.0e+3f
 
static const Real UNIT2NANO = 1.0e+9f
 

Detailed Description

Common mathematical functions.

Typedef Documentation

◆ AngleAxis

typedef ::Eigen::AngleAxis<Real> rl::math::AngleAxis

◆ ArrayX

typedef ::Eigen::Array<Real, ::Eigen::Dynamic, 1> rl::math::ArrayX

◆ ArrayXX

typedef ::Eigen::Array<Real, ::Eigen::Dynamic, ::Eigen::Dynamic> rl::math::ArrayXX

◆ ArticulatedBodyInertia

◆ ConstMatrix22Block

typedef ::Eigen::Block<const Matrix22> rl::math::ConstMatrix22Block

◆ ConstMatrix22Column

typedef Matrix22::ConstColXpr rl::math::ConstMatrix22Column

◆ ConstMatrix22Row

typedef Matrix22::ConstRowXpr rl::math::ConstMatrix22Row

◆ ConstMatrix33Block

typedef ::Eigen::Block<const Matrix33> rl::math::ConstMatrix33Block

◆ ConstMatrix33Column

typedef Matrix33::ConstColXpr rl::math::ConstMatrix33Column

◆ ConstMatrix33Row

typedef Matrix33::ConstRowXpr rl::math::ConstMatrix33Row

◆ ConstMatrix44Block

typedef ::Eigen::Block<const Matrix44> rl::math::ConstMatrix44Block

◆ ConstMatrix44Column

typedef Matrix44::ConstColXpr rl::math::ConstMatrix44Column

◆ ConstMatrix44Row

typedef Matrix44::ConstRowXpr rl::math::ConstMatrix44Row

◆ ConstMatrix66Block

typedef ::Eigen::Block<const Matrix66> rl::math::ConstMatrix66Block

◆ ConstMatrix66Column

typedef Matrix66::ConstColXpr rl::math::ConstMatrix66Column

◆ ConstMatrix66Row

typedef Matrix66::ConstRowXpr rl::math::ConstMatrix66Row

◆ ConstMatrixBlock

typedef ::Eigen::Block<const Matrix> rl::math::ConstMatrixBlock

◆ ConstMatrixColumn

typedef Matrix::ConstColXpr rl::math::ConstMatrixColumn

◆ ConstMatrixRef

typedef ::Eigen::Ref<const Matrix> rl::math::ConstMatrixRef

◆ ConstMatrixRow

typedef Matrix::ConstRowXpr rl::math::ConstMatrixRow

◆ ConstRotationBlock

◆ ConstRotationColumn

◆ ConstRotationRow

◆ ConstVector2Block

typedef ::Eigen::VectorBlock<const Vector2, ::Eigen::Dynamic> rl::math::ConstVector2Block

◆ ConstVector3Block

typedef ::Eigen::VectorBlock<const Vector3, ::Eigen::Dynamic> rl::math::ConstVector3Block

◆ ConstVector4Block

typedef ::Eigen::VectorBlock<const Vector4, ::Eigen::Dynamic> rl::math::ConstVector4Block

◆ ConstVector6Block

typedef ::Eigen::VectorBlock<const Vector6, ::Eigen::Dynamic> rl::math::ConstVector6Block

◆ ConstVectorBlock

typedef ::Eigen::VectorBlock<const Vector, ::Eigen::Dynamic> rl::math::ConstVectorBlock

◆ ConstVectorRef

typedef ::Eigen::Ref<const Vector> rl::math::ConstVectorRef

◆ ForceVector

◆ Matrix

typedef ::Eigen::Matrix<Real, ::Eigen::Dynamic, ::Eigen::Dynamic> rl::math::Matrix

◆ Matrix22

typedef ::Eigen::Matrix<Real, 2, 2> rl::math::Matrix22

◆ Matrix22Block

typedef ::Eigen::Block<Matrix22> rl::math::Matrix22Block

◆ Matrix22Column

typedef Matrix22::ColXpr rl::math::Matrix22Column

◆ Matrix22Row

typedef Matrix22::RowXpr rl::math::Matrix22Row

◆ Matrix33

typedef ::Eigen::Matrix<Real, 3, 3> rl::math::Matrix33

◆ Matrix33Block

typedef ::Eigen::Block<Matrix33> rl::math::Matrix33Block

◆ Matrix33Column

typedef Matrix33::ColXpr rl::math::Matrix33Column

◆ Matrix33Row

typedef Matrix33::RowXpr rl::math::Matrix33Row

◆ Matrix44

typedef ::Eigen::Matrix<Real, 4, 4> rl::math::Matrix44

◆ Matrix44Block

typedef ::Eigen::Block<Matrix44> rl::math::Matrix44Block

◆ Matrix44Column

typedef Matrix44::ColXpr rl::math::Matrix44Column

◆ Matrix44Row

typedef Matrix44::RowXpr rl::math::Matrix44Row

◆ Matrix66

typedef ::Eigen::Matrix<Real, 6, 6> rl::math::Matrix66

◆ Matrix66Block

typedef ::Eigen::Block<Matrix66> rl::math::Matrix66Block

◆ Matrix66Column

typedef Matrix66::ColXpr rl::math::Matrix66Column

◆ Matrix66Row

typedef Matrix66::RowXpr rl::math::Matrix66Row

◆ MatrixBlock

typedef ::Eigen::Block<Matrix> rl::math::MatrixBlock

◆ MatrixColumn

typedef Matrix::ColXpr rl::math::MatrixColumn

◆ MatrixRef

typedef ::Eigen::Ref<Matrix> rl::math::MatrixRef

◆ MatrixRow

typedef Matrix::RowXpr rl::math::MatrixRow

◆ MotionVector

◆ PlueckerTransform

◆ Quaternion

typedef ::Eigen::Quaternion<Real> rl::math::Quaternion

◆ Real

typedef double rl::math::Real

◆ RigidBodyInertia

◆ Rotation

◆ RotationBlock

◆ RotationColumn

◆ RotationRow

◆ Transform

typedef ::Eigen::Transform<Real, 3, ::Eigen::Affine> rl::math::Transform

Rigid transformation in 3D.

◆ Translation

typedef ::Eigen::Translation<Real, 3> rl::math::Translation

Translation in 3D.

◆ Vector

typedef ::Eigen::Matrix<Real, ::Eigen::Dynamic, 1> rl::math::Vector

◆ Vector2

typedef ::Eigen::Matrix<Real, 2, 1> rl::math::Vector2

◆ Vector2Block

typedef ::Eigen::VectorBlock<Vector2, ::Eigen::Dynamic> rl::math::Vector2Block

◆ Vector3

typedef ::Eigen::Matrix<Real, 3, 1> rl::math::Vector3

◆ Vector3Block

typedef ::Eigen::VectorBlock<Vector3, ::Eigen::Dynamic> rl::math::Vector3Block

◆ Vector4

typedef ::Eigen::Matrix<Real, 4, 1> rl::math::Vector4

◆ Vector4Block

typedef ::Eigen::VectorBlock<Vector4, ::Eigen::Dynamic> rl::math::Vector4Block

◆ Vector6

typedef ::Eigen::Matrix<Real, 6, 1> rl::math::Vector6

◆ Vector6Block

typedef ::Eigen::VectorBlock<Vector6, ::Eigen::Dynamic> rl::math::Vector6Block

◆ VectorBlock

typedef ::Eigen::VectorBlock<Vector, ::Eigen::Dynamic> rl::math::VectorBlock

◆ VectorRef

typedef ::Eigen::Ref<Vector> rl::math::VectorRef

Enumeration Type Documentation

◆ Unit

SI base units

Name Symbol Measure
meter m length
kilogram kg mass
second s time
ampere A electric current
kelvin K thermodynamic temperature
mole mol quantity of matter (mass/mass)
candela cd luminous intensity

SI derived units

Name Symbol Quantity Expression in terms of SI base units
radian rad Angle
hertz Hz frequency s-1
newton N Force, Weight m · kg · s-2
volt V Electrical potential difference, Electromotive force m2 · kg · s-3 · A-1
degree Celsius °C Thermodynamic temperature TºC = TK - 273.16
meter per second m · s-1 speed, velocity m · s-1
meter per second squared m · s-2 acceleration m · s-2
radian per second rad · s-1 angular velocity s-1
newton second N · s momentum, impulse kg · m · s-1
newton meter second N · m · s angular momentum kg · m2 · s-1
newton meter N · m Torque, moment of force kg · m2 · s-2
Enumerator
UNIT_NONE 
UNIT_METER 
UNIT_KILOGRAM 
UNIT_SECOND 
UNIT_AMPERE 
UNIT_KELVIN 
UNIT_MOLE 
UNIT_CANDELA 
UNIT_RADIAN 
UNIT_HERTZ 
UNIT_NEWTON 
UNIT_VOLT 
UNIT_CELSIUS 
UNIT_METER_PER_SECOND 
UNIT_METER_PER_SECOND_SQUARED 
UNIT_RADIAN_PER_SECOND 
UNIT_RADIAN_PER_SECOND_SQUARED 
UNIT_NEWTON_SECOND 
UNIT_NEWTON_METER_SECOND 
UNIT_NEWTON_METER 

Function Documentation

◆ cartesianToPolar()

void rl::math::cartesianToPolar ( const Real x,
const Real y,
Real r,
Real theta 
)
inline

◆ cartesianToSpherical()

void rl::math::cartesianToSpherical ( const Real x,
const Real y,
const Real z,
Real rho,
Real psi,
Real theta 
)
inline

◆ cbrt()

template<typename T >
T rl::math::cbrt ( const T &  arg)
inline

◆ polarToCartesian()

void rl::math::polarToCartesian ( const Real r,
const Real theta,
Real x,
Real y 
)
inline

◆ sign()

template<typename T >
T rl::math::sign ( const T &  arg)
inline

◆ sphericalToCartesian()

void rl::math::sphericalToCartesian ( const Real rho,
const Real psi,
const Real theta,
Real x,
Real y,
Real z 
)
inline

Variable Documentation

◆ DEG2RAD

const Real rl::math::DEG2RAD = static_cast<Real>(M_PI) / 180.0f
static

◆ FUNCTION_BOUNDARY

const Real rl::math::FUNCTION_BOUNDARY = 1.0e-8f
static

◆ GIGA2UNIT

const Real rl::math::GIGA2UNIT = 1.0e+9f
static

◆ GRAVITY

const Real rl::math::GRAVITY = 9.80665f
static

[m · s-2]

◆ KILO2UNIT

const Real rl::math::KILO2UNIT = 1.0e+3f
static

◆ MEGA2UNIT

const Real rl::math::MEGA2UNIT = 1.0e+6f
static

◆ MICRO2UNIT

const Real rl::math::MICRO2UNIT = 1.0e-6f
static

◆ MILLI2UNIT

const Real rl::math::MILLI2UNIT = 1.0e-3f
static

◆ NANO2UNIT

const Real rl::math::NANO2UNIT = 1.0e-9f
static

◆ RAD2DEG

const Real rl::math::RAD2DEG = 180.0f / static_cast<Real>(M_PI)
static

◆ UNIT2GIGA

const Real rl::math::UNIT2GIGA = 1.0e-9f
static

◆ UNIT2KILO

const Real rl::math::UNIT2KILO = 1.0e-3f
static

◆ UNIT2MEGA

const Real rl::math::UNIT2MEGA = 1.0e-6f
static

◆ UNIT2MICRO

const Real rl::math::UNIT2MICRO = 1.0e+6f
static

◆ UNIT2MILLI

const Real rl::math::UNIT2MILLI = 1.0e+3f
static

◆ UNIT2NANO

const Real rl::math::UNIT2NANO = 1.0e+9f
static