OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Classes | Functions
okvis::kinematics Namespace Reference

kinematics Namespace for kinematics functionality, i.e. transformations and stuff. More...

Classes

class  Transformation
 A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of translation r_AB (represented in frame A) and Quaternion q_AB (as an Eigen Quaternion). see also the RSS'13 / IJRR'14 paper or the Thesis. Follows some of the functionality of the SchweizerMesser library by Paul Furgale, but uses Eigen quaternions underneath. More...
 

Functions

__inline__ double sinc (double x)
 Implements sin(x)/x for all x in R. More...
 
__inline__ Eigen::Quaterniond deltaQ (const Eigen::Vector3d &dAlpha)
 Implements the exponential map for quaternions. More...
 
__inline__ Eigen::Matrix3d rightJacobian (const Eigen::Vector3d &PhiVec)
 Right Jacobian, see Forster et al. RSS 2015 eqn. (8) More...
 
template<typename Scalar_T >
Eigen::Matrix< Scalar_T, 3, 3 > crossMx (Scalar_T x, Scalar_T y, Scalar_T z)
 Cross matrix of a vector [x,y,z]. Adopted from Schweizer-Messer by Paul Furgale. More...
 
template<typename Derived_T >
Eigen::Matrix< typename
Eigen::internal::traits
< Derived_T >::Scalar, 3, 3 > 
crossMx (Eigen::MatrixBase< Derived_T > const &v)
 Cross matrix of a vector v. Adopted from Schweizer-Messer by Paul Furgale. More...
 
Eigen::Matrix4d plus (const Eigen::Quaterniond &q_AB)
 Plus matrix of a quaternion, i.e. q_AB*q_BC = plus(q_AB)*q_BC.coeffs(). More...
 
Eigen::Matrix4d oplus (const Eigen::Quaterniond &q_BC)
 Oplus matrix of a quaternion, i.e. q_AB*q_BC = oplus(q_BC)*q_AB.coeffs(). More...
 

Detailed Description

kinematics Namespace for kinematics functionality, i.e. transformations and stuff.

Function Documentation

template<typename Scalar_T >
Eigen::Matrix<Scalar_T, 3, 3> okvis::kinematics::crossMx ( Scalar_T  x,
Scalar_T  y,
Scalar_T  z 
)
inline

Cross matrix of a vector [x,y,z]. Adopted from Schweizer-Messer by Paul Furgale.

Template Parameters
Scalar_TThe scalar type, auto-deducible (typically double).
Parameters
[in]xFirst vector element.
[in]ySecond vector element.
[in]zThird vector element.
template<typename Derived_T >
Eigen::Matrix<typename Eigen::internal::traits<Derived_T>::Scalar, 3, 3> okvis::kinematics::crossMx ( Eigen::MatrixBase< Derived_T > const &  v)
inline

Cross matrix of a vector v. Adopted from Schweizer-Messer by Paul Furgale.

Template Parameters
Derived_TThe vector type, auto-deducible.
Parameters
[in]vThe vector.
Eigen::Quaterniond okvis::kinematics::deltaQ ( const Eigen::Vector3d &  dAlpha)

Implements the exponential map for quaternions.

Parameters
[in]dAlphaa axis*angle (minimal) input in tangent space.
Returns
The corresponding Quaternion.
Eigen::Matrix4d okvis::kinematics::oplus ( const Eigen::Quaterniond &  q_BC)
inline

Oplus matrix of a quaternion, i.e. q_AB*q_BC = oplus(q_BC)*q_AB.coeffs().

Parameters
[in]q_BCA Quaternion.
Eigen::Matrix4d okvis::kinematics::plus ( const Eigen::Quaterniond &  q_AB)
inline

Plus matrix of a quaternion, i.e. q_AB*q_BC = plus(q_AB)*q_BC.coeffs().

Parameters
[in]q_ABA Quaternion.
Eigen::Matrix3d okvis::kinematics::rightJacobian ( const Eigen::Vector3d &  PhiVec)

Right Jacobian, see Forster et al. RSS 2015 eqn. (8)

double okvis::kinematics::sinc ( double  x)

Implements sin(x)/x for all x in R.

Parameters
[in]xThe argument of the sinc function.
Returns
The result.