OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Attributes | List of all members
okvis::ceres::ImuError Class Reference

Implements a nonlinear IMU factor. More...

#include <ImuError.hpp>

Inheritance diagram for okvis::ceres::ImuError:
okvis::ceres::ErrorInterface

Public Types

typedef Eigen::Matrix< double, 15, 15 > covariance_t
 The type of the covariance. More...
 
typedef covariance_t information_t
 The type of the information (same matrix dimension as covariance). More...
 
typedef Eigen::Matrix< double, 15, 15 > jacobian_t
 The type of hte overall Jacobian. More...
 
typedef Eigen::Matrix< double, 15, 7 > jacobian0_t
 The type of the Jacobian w.r.t. poses –. More...
 
typedef Eigen::Matrix< double, 15, 9 > jacobian1_t
 The type of Jacobian w.r.t. Speed and biases. More...
 

Public Member Functions

 ImuError ()
 Default constructor – assumes information recomputation. More...
 
virtual ~ImuError ()
 Trivial destructor. More...
 
 ImuError (const okvis::ImuMeasurementDeque &imuMeasurements, const okvis::ImuParameters &imuParameters, const okvis::Time &t_0, const okvis::Time &t_1)
 Construct with measurements and parameters. @param[in] imuMeasurements All the IMU measurements. @param[in] imuParameters The parameters to be used. @param[in] t_0 Start time. @param[in] t_1 End time. More...
 
int redoPreintegration (const okvis::kinematics::Transformation &T_WS, const okvis::SpeedAndBias &speedAndBiases) const
 Propagates pose, speeds and biases with given IMU measurements. More...
 
void setImuParameters (const okvis::ImuParameters &imuParameters)
 (Re)set the parameters. @param[in] imuParameters The parameters to be used. More...
 
void setImuMeasurements (const okvis::ImuMeasurementDeque &imuMeasurements)
 (Re)set the measurements @param[in] imuMeasurements All the IMU measurements. More...
 
void setT0 (const okvis::Time &t_0)
 (Re)set the start time. @param[in] t_0 Start time. More...
 
void setT1 (const okvis::Time &t_1)
 (Re)set the start time. @param[in] t_1 End time. More...
 
const okvis::ImuParametersimuParameters () const
 Get the IMU Parameters. More...
 
const okvis::ImuMeasurementDequeimuMeasurements () const
 Get the IMU measurements. More...
 
okvis::Time t0 () const
 Get the start time. More...
 
okvis::Time t1 () const
 Get the end time. More...
 
virtual bool Evaluate (double const *const *parameters, double *residuals, double **jacobians) const
 This evaluates the error term and additionally computes the Jacobians. More...
 
bool EvaluateWithMinimalJacobians (double const *const *parameters, double *residuals, double **jacobians, double **jacobiansMinimal) const
 This evaluates the error term and additionally computes the Jacobians in the minimal internal representation. More...
 
size_t residualDim () const
 Residual dimension. More...
 
virtual size_t parameterBlocks () const
 Number of parameter blocks. More...
 
size_t parameterBlockDim (size_t parameterBlockId) const
 Dimension of an individual parameter block. More...
 
virtual std::string typeInfo () const
 Return parameter block type as string. More...
 
- Public Member Functions inherited from okvis::ceres::ErrorInterface
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ErrorInterface ()
 Constructor. More...
 
virtual ~ErrorInterface ()
 Destructor (does nothing). More...
 

Static Public Member Functions

static int propagation (const okvis::ImuMeasurementDeque &imuMeasurements, const okvis::ImuParameters &imuParams, okvis::kinematics::Transformation &T_WS, okvis::SpeedAndBias &speedAndBiases, const okvis::Time &t_start, const okvis::Time &t_end, covariance_t *covariance=0, jacobian_t *jacobian=0)
 Propagates pose, speeds and biases with given IMU measurements. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef::ceres::SizedCostFunction< 15, 7, 9, 7, 9 > 
base_t
 The base in ceres we derive from. More...
 

Static Public Attributes

static const int kNumResiduals = 15
 The number of residuals. More...
 

Protected Attributes

okvis::ImuParameters imuParameters_
 The IMU parameters. More...
 
okvis::ImuMeasurementDeque imuMeasurements_
 The IMU measurements used. Must be spanning t0_ - t1_. More...
 
okvis::Time t0_
 The start time (i.e. time of the first set of states). More...
 
okvis::Time t1_
 The end time (i.e. time of the sedond set of states). More...
 
std::mutex preintegrationMutex_
 
Eigen::Quaterniond Delta_q_ = Eigen::Quaterniond(1,0,0,0)
 Intermediate result. More...
 
Eigen::Matrix3d C_integral_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix3d C_doubleintegral_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Vector3d acc_integral_ = Eigen::Vector3d::Zero()
 Intermediate result. More...
 
Eigen::Vector3d acc_doubleintegral_ = Eigen::Vector3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix3d cross_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix3d dalpha_db_g_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix3d dv_db_g_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix3d dp_db_g_ = Eigen::Matrix3d::Zero()
 Intermediate result. More...
 
Eigen::Matrix< double, 15, 15 > P_delta_ = Eigen::Matrix<double,15,15>::Zero()
 The Jacobian of the increment (w/o biases). More...
 
SpeedAndBiases speedAndBiases_ref_ = SpeedAndBiases::Zero()
 Reference biases that are updated when called redoPreintegration. More...
 
bool redo_ = true
 Keeps track of whether or not this redoPreintegration() needs to be called. More...
 
int redoCounter_ = 0
 Counts the number of preintegrations for statistics. More...
 
information_t information_
 The information matrix for this error term. More...
 
information_t squareRootInformation_
 The square root information matrix for this error term. More...
 

Detailed Description

Implements a nonlinear IMU factor.

Member Typedef Documentation

typedef Eigen::Matrix<double, 15, 15> okvis::ceres::ImuError::covariance_t

The type of the covariance.

The type of the information (same matrix dimension as covariance).

typedef Eigen::Matrix<double, 15, 7> okvis::ceres::ImuError::jacobian0_t

The type of the Jacobian w.r.t. poses –.

Warning
This is w.r.t. minimal tangential space coordinates...
typedef Eigen::Matrix<double, 15, 9> okvis::ceres::ImuError::jacobian1_t

The type of Jacobian w.r.t. Speed and biases.

typedef Eigen::Matrix<double, 15, 15> okvis::ceres::ImuError::jacobian_t

The type of hte overall Jacobian.

Constructor & Destructor Documentation

okvis::ceres::ImuError::ImuError ( )
inline

Default constructor – assumes information recomputation.

virtual okvis::ceres::ImuError::~ImuError ( )
inlinevirtual

Trivial destructor.

okvis::ceres::ImuError::ImuError ( const okvis::ImuMeasurementDeque imuMeasurements,
const okvis::ImuParameters imuParameters,
const okvis::Time t_0,
const okvis::Time t_1 
)

Construct with measurements and parameters. @param[in] imuMeasurements All the IMU measurements. @param[in] imuParameters The parameters to be used. @param[in] t_0 Start time. @param[in] t_1 End time.

Member Function Documentation

bool okvis::ceres::ImuError::Evaluate ( double const *const *  parameters,
double *  residuals,
double **  jacobians 
) const
virtual

This evaluates the error term and additionally computes the Jacobians.

Parameters
parametersPointer to the parameters (see ceres)
residualsPointer to the residual vector (see ceres)
jacobiansPointer to the Jacobians (see ceres)
Returns
success of th evaluation.
bool okvis::ceres::ImuError::EvaluateWithMinimalJacobians ( double const *const *  parameters,
double *  residuals,
double **  jacobians,
double **  jacobiansMinimal 
) const
virtual

This evaluates the error term and additionally computes the Jacobians in the minimal internal representation.

Parameters
parametersPointer to the parameters (see ceres)
residualsPointer to the residual vector (see ceres)
jacobiansPointer to the Jacobians (see ceres)
jacobiansMinimalPointer to the minimal Jacobians (equivalent to jacobians).
Returns
Success of the evaluation.

Implements okvis::ceres::ErrorInterface.

const okvis::ImuMeasurementDeque& okvis::ceres::ImuError::imuMeasurements ( ) const
inline

Get the IMU measurements.

const okvis::ImuParameters& okvis::ceres::ImuError::imuParameters ( ) const
inline

Get the IMU Parameters.

Returns
the IMU parameters.
size_t okvis::ceres::ImuError::parameterBlockDim ( size_t  parameterBlockId) const
inlinevirtual

Dimension of an individual parameter block.

Parameters
[in]parameterBlockIdID of the parameter block of interest.
Returns
The dimension.

Implements okvis::ceres::ErrorInterface.

virtual size_t okvis::ceres::ImuError::parameterBlocks ( ) const
inlinevirtual

Number of parameter blocks.

Implements okvis::ceres::ErrorInterface.

int okvis::ceres::ImuError::propagation ( const okvis::ImuMeasurementDeque imuMeasurements,
const okvis::ImuParameters imuParams,
okvis::kinematics::Transformation T_WS,
okvis::SpeedAndBias speedAndBiases,
const okvis::Time t_start,
const okvis::Time t_end,
covariance_t covariance = 0,
jacobian_t jacobian = 0 
)
static

Propagates pose, speeds and biases with given IMU measurements.

Remarks
This can be used externally to perform propagation
Parameters
[in]imuMeasurementsAll the IMU measurements.
[in]imuParamsThe parameters to be used.
[in,out]T_WSStart pose.
[in,out]speedAndBiasesStart speed and biases.
[in]t_startStart time.
[in]t_endEnd time.
[out]covarianceCovariance for GIVEN start states.
[out]jacobianJacobian w.r.t. start states.
Returns
Number of integration steps.
int okvis::ceres::ImuError::redoPreintegration ( const okvis::kinematics::Transformation T_WS,
const okvis::SpeedAndBias speedAndBiases 
) const

Propagates pose, speeds and biases with given IMU measurements.

Warning
This is not actually const, since the re-propagation must somehow be stored...
Parameters
[in]T_WSStart pose.
[in]speedAndBiasesStart speed and biases.
Returns
Number of integration steps.
size_t okvis::ceres::ImuError::residualDim ( ) const
inlinevirtual

Residual dimension.

Implements okvis::ceres::ErrorInterface.

void okvis::ceres::ImuError::setImuMeasurements ( const okvis::ImuMeasurementDeque imuMeasurements)
inline

(Re)set the measurements @param[in] imuMeasurements All the IMU measurements.

void okvis::ceres::ImuError::setImuParameters ( const okvis::ImuParameters imuParameters)
inline

(Re)set the parameters. @param[in] imuParameters The parameters to be used.

void okvis::ceres::ImuError::setT0 ( const okvis::Time t_0)
inline

(Re)set the start time. @param[in] t_0 Start time.

void okvis::ceres::ImuError::setT1 ( const okvis::Time t_1)
inline

(Re)set the start time. @param[in] t_1 End time.

okvis::Time okvis::ceres::ImuError::t0 ( ) const
inline

Get the start time.

okvis::Time okvis::ceres::ImuError::t1 ( ) const
inline

Get the end time.

virtual std::string okvis::ceres::ImuError::typeInfo ( ) const
inlinevirtual

Return parameter block type as string.

Implements okvis::ceres::ErrorInterface.

Member Data Documentation

Eigen::Vector3d okvis::ceres::ImuError::acc_doubleintegral_ = Eigen::Vector3d::Zero()
mutableprotected

Intermediate result.

Eigen::Vector3d okvis::ceres::ImuError::acc_integral_ = Eigen::Vector3d::Zero()
mutableprotected

Intermediate result.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ::ceres::SizedCostFunction<15, 7, 9, 7, 9> okvis::ceres::ImuError::base_t

The base in ceres we derive from.

Eigen::Matrix3d okvis::ceres::ImuError::C_doubleintegral_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

Eigen::Matrix3d okvis::ceres::ImuError::C_integral_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

Eigen::Matrix3d okvis::ceres::ImuError::cross_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

Eigen::Matrix3d okvis::ceres::ImuError::dalpha_db_g_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

Eigen::Quaterniond okvis::ceres::ImuError::Delta_q_ = Eigen::Quaterniond(1,0,0,0)
mutableprotected

Intermediate result.

Eigen::Matrix3d okvis::ceres::ImuError::dp_db_g_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

Eigen::Matrix3d okvis::ceres::ImuError::dv_db_g_ = Eigen::Matrix3d::Zero()
mutableprotected

Intermediate result.

okvis::ImuMeasurementDeque okvis::ceres::ImuError::imuMeasurements_
protected

The IMU measurements used. Must be spanning t0_ - t1_.

okvis::ImuParameters okvis::ceres::ImuError::imuParameters_
protected

The IMU parameters.

information_t okvis::ceres::ImuError::information_
mutableprotected

The information matrix for this error term.

const int okvis::ceres::ImuError::kNumResiduals = 15
static

The number of residuals.

Eigen::Matrix<double,15,15> okvis::ceres::ImuError::P_delta_ = Eigen::Matrix<double,15,15>::Zero()
mutableprotected

The Jacobian of the increment (w/o biases).

std::mutex okvis::ceres::ImuError::preintegrationMutex_
mutableprotected
bool okvis::ceres::ImuError::redo_ = true
mutableprotected

Keeps track of whether or not this redoPreintegration() needs to be called.

int okvis::ceres::ImuError::redoCounter_ = 0
mutableprotected

Counts the number of preintegrations for statistics.

SpeedAndBiases okvis::ceres::ImuError::speedAndBiases_ref_ = SpeedAndBiases::Zero()
mutableprotected

Reference biases that are updated when called redoPreintegration.

information_t okvis::ceres::ImuError::squareRootInformation_
mutableprotected

The square root information matrix for this error term.

okvis::Time okvis::ceres::ImuError::t0_
protected

The start time (i.e. time of the first set of states).

okvis::Time okvis::ceres::ImuError::t1_
protected

The end time (i.e. time of the sedond set of states).


The documentation for this class was generated from the following files: