Calico
A visual-inertial calibration library designed for rapid problem construction and debugging.
Namespaces | Classes | Typedefs | Functions | Variables
calico Namespace Reference

Primary calico namespace. More...

Namespaces

 sensors
 Sensors namespace.
 
 utils
 Utils namespace.
 

Classes

class  BatchOptimizer
 
class  BSpline
 
class  Profiler
 
class  DefaultSyntheticTest
 
struct  TrajectoryEvaluationParams
 
class  Trajectory
 
class  Pose3
 
struct  Landmark
 
struct  RigidBody
 
class  WorldModel
 

Typedefs

using Pose3d = Pose3< double >
 

Functions

ceres::Solver::Options DefaultSolverOptions ()
 Default solver options.
 
template<typename T >
Eigen::Matrix3< T > Skew (const Eigen::Vector3< T > &v)
 Convert a 3-vector to a skew-symmetric cross-product matrix.
 
template<typename T >
Eigen::Vector3< T > iSkew (const Eigen::Matrix3< T > &V)
 Converts a skew symmetric matrix back into a vector.
 
template<typename T >
SmallAngleSin (const T theta)
 Fourth order Taylor expansion of sin(theta).
 
template<typename T >
SmallAngleCos (const T theta)
 Fourth order Taylor expansion of cos(theta).
 
template<typename T >
Eigen::Matrix3< T > ExpSO3 (const Eigen::Vector3< T > &phi)
 Convert axis-angle to rotation matrix.
 
template<typename T >
Eigen::Vector3< T > LnSO3 (const Eigen::Matrix3< T > &R)
 
template<typename T >
Eigen::Matrix3< T > ExpSO3Jacobian (const Eigen::Vector3< T > &phi)
 
template<typename T >
std::vector< Eigen::Matrix3< T > > ExpSO3Hessian (const Eigen::Vector3< T > &phi)
 
template<typename T >
Eigen::Matrix3< T > ExpSO3JacobianDot (const Eigen::Vector3< T > &phi, const Eigen::Vector3< T > &phi_dot)
 Compute the time derivative of the Rodrigues formula manifold Jacobian.
 
 MATCHER_P2 (PoseIsApprox, expected_pose, tolerance, "")
 
 MATCHER_P (PoseEq, expected_pose, "")
 
 MATCHER_P (EigenEq, expected_vector, "")
 
 MATCHER_P2 (EigenIsApprox, expected_vector, tolerance, "")
 
 MATCHER_P (StatusIs, status, "")
 
 MATCHER_P (StatusCodeIs, status, "")
 

Variables

constexpr int kLandmarkFrameId = -1
 Default frame id for a landmark (i.e. World frame).
 

Detailed Description

Primary calico namespace.

Function Documentation

◆ ExpSO3Hessian()

template<typename T >
std::vector<Eigen::Matrix3<T> > calico::ExpSO3Hessian ( const Eigen::Vector3< T > &  phi)
inline

Compute the manifold Hessian matrix of the Rodrigues formula, i.e.:

\[ \mathbf{R}(\boldsymbol{\Phi}) = \exp\left(\left[\boldsymbol{\Phi}\right]_\times\right) = \mathbf{I} + \frac{\sin(\theta)}{\theta}\left[\boldsymbol{\Phi}\right]_\times + \frac{1-\cos(\theta)}{\theta^2} {\left[\boldsymbol{\Phi}\right]_\times}^2\\ \mathbf{H} = \frac{\partial^2 \exp\left(\left[\boldsymbol{\Phi}\right]_\times\right)} {\partial \boldsymbol{\Phi}^2} \]

◆ ExpSO3Jacobian()

template<typename T >
Eigen::Matrix3<T> calico::ExpSO3Jacobian ( const Eigen::Vector3< T > &  phi)
inline

Compute the manifold Jacobian matrix of the Rodrigues formula, i.e.:

\[ \mathbf{R}\left(\boldsymbol{\Phi}\right) = \exp\left( \mathbf{I} + \frac{\sin(\theta)}{\theta} \left[\boldsymbol{\Phi}\right]_\times + \frac{1 - \cos(\theta)}{\theta^2}{\left[\boldsymbol{\Phi}\right]_\times}^2 \right)\\ \frac{\partial \exp\left(\left[\boldsymbol{\Phi}\right]_\times\right)}{\partial \boldsymbol{\Phi}} = \mathbf{I} + \frac{1-\cos(\theta)}{\theta^2} \left[\boldsymbol{\Phi}\right]_\times + \frac{\theta-\sin(\theta)}{\theta^3} {\left[\boldsymbol{\Phi}\right]_\times}^2\\ \theta = \boldsymbol{\Phi}^T\boldsymbol{\Phi} \]

◆ LnSO3()

template<typename T >
Eigen::Vector3<T> calico::LnSO3 ( const Eigen::Matrix3< T > &  R)
inline