39 #ifndef INCLUDE_OKVIS_CERES_SPEEDANDBIASERROR_HPP_
40 #define INCLUDE_OKVIS_CERES_SPEEDANDBIASERROR_HPP_
44 #include "ceres/ceres.h"
60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
64 typedef ::ceres::SizedCostFunction<9, 9>
base_t;
90 double speedVariance,
double gyrBiasVariance,
91 double accBiasVariance);
135 virtual bool Evaluate(
double const*
const * parameters,
double* residuals,
136 double** jacobians)
const;
150 double** jacobiansMinimal)
const;
160 return parameter_block_sizes().size();
167 return base_t::parameter_block_sizes().at(parameterBlockId);
172 return "SpeedAndBiasError";
information_t information_
The 9x9 information matrix.
Definition: SpeedAndBiasError.hpp:181
virtual 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 represe...
Definition: SpeedAndBiasError.cpp:89
Header file for the ErrorInterface class. A simple interface class that other error classes should in...
virtual std::string typeInfo() const
Residual block type as string.
Definition: SpeedAndBiasError.hpp:171
size_t residualDim() const
Residual dimension.
Definition: SpeedAndBiasError.hpp:154
okvis::SpeedAndBias measurement_
The (9D) measurement.
Definition: SpeedAndBiasError.hpp:178
const okvis::SpeedAndBias & measurement() const
Get the measurement.
Definition: SpeedAndBiasError.hpp:111
Definition: SpeedAndBiasError.hpp:54
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
void setMeasurement(const okvis::SpeedAndBias &measurement)
Set the measurement.
Definition: SpeedAndBiasError.hpp:100
Simple interface class the errors implemented here should inherit from.
Definition: ErrorInterface.hpp:53
static const int kNumResiduals
Number of residuals (9)
Definition: SpeedAndBiasError.hpp:67
void setInformation(const information_t &information)
Set the information.
Definition: SpeedAndBiasError.cpp:73
#define OKVIS_DEFINE_EXCEPTION(exceptionName, exceptionParent)
Macro for defining an exception with a given parent.
Definition: assert_macros.hpp:52
Eigen::Matrix< double, 9, 9 > information_t
The information matrix type (9x9).
Definition: SpeedAndBiasError.hpp:70
This file contains some useful assert macros.
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: SpeedAndBiasParameterBlock.hpp:52
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef::ceres::SizedCostFunction< 9, 9 > base_t
The base class type.
Definition: SpeedAndBiasError.hpp:64
Eigen::Matrix< double, 9, 1 > SpeedAndBiases
Definition: FrameTypedefs.hpp:233
information_t squareRootInformation_
The 9x9 square root information matrix.
Definition: SpeedAndBiasError.hpp:182
size_t parameterBlockDim(size_t parameterBlockId) const
Dimension of an individual parameter block.
Definition: SpeedAndBiasError.hpp:166
covariance_t covariance_
The 9x9 covariance matrix.
Definition: SpeedAndBiasError.hpp:183
size_t parameterBlocks() const
Number of parameter blocks.
Definition: SpeedAndBiasError.hpp:159
Eigen::Matrix< double, 9, 9 > covariance_t
The covariance matrix type (same as information).
Definition: SpeedAndBiasError.hpp:73
const covariance_t & covariance() const
Get the covariance matrix.
Definition: SpeedAndBiasError.hpp:123
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
This evaluates the error term and additionally computes the Jacobians.
Definition: SpeedAndBiasError.cpp:82
const information_t & information() const
Get the information matrix.
Definition: SpeedAndBiasError.hpp:117
This file contains useful typedefs and structs related to frames.