#include <SpeedAndBiasError.hpp>
|
typedef Eigen::Matrix< double, 9, 9 > | information_t |
| The information matrix type (9x9). More...
|
|
typedef Eigen::Matrix< double, 9, 9 > | covariance_t |
| The covariance matrix type (same as information). More...
|
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef::ceres::SizedCostFunction< 9, 9 > | base_t |
| The base class type. More...
|
|
The covariance matrix type (same as information).
The information matrix type (9x9).
okvis::ceres::SpeedAndBiasError::SpeedAndBiasError |
( |
| ) |
|
Construct with measurement and information matrix.
- Parameters
-
[in] | measurement | The measurement. |
[in] | information | The information (weight) matrix. |
okvis::ceres::SpeedAndBiasError::SpeedAndBiasError |
( |
const okvis::SpeedAndBiases & |
measurement, |
|
|
double |
speedVariance, |
|
|
double |
gyrBiasVariance, |
|
|
double |
accBiasVariance |
|
) |
| |
Construct with measurement and variance.
- Parameters
-
[in] | measurement | The measurement. |
[in] | speedVariance | The variance of the speed measurement, i.e. information_ has variance in its diagonal. |
[in] | gyrBiasVariance | The variance of the gyro bias measurement, i.e. information_ has variance in its diagonal. |
[in] | accBiasVariance | The variance of the accelerometer bias measurement, i.e. information_ has variance in its diagonal. |
virtual okvis::ceres::SpeedAndBiasError::~SpeedAndBiasError |
( |
| ) |
|
|
inlinevirtual |
const covariance_t& okvis::ceres::SpeedAndBiasError::covariance |
( |
| ) |
const |
|
inline |
Get the covariance matrix.
- Returns
- The inverse information (covariance) matrix.
bool okvis::ceres::SpeedAndBiasError::Evaluate |
( |
double const *const * |
parameters, |
|
|
double * |
residuals, |
|
|
double ** |
jacobians |
|
) |
| const |
|
virtual |
This evaluates the error term and additionally computes the Jacobians.
- Parameters
-
parameters | Pointer to the parameters (see ceres) |
residuals | Pointer to the residual vector (see ceres) |
jacobians | Pointer to the Jacobians (see ceres) |
- Returns
- success of th evaluation.
bool okvis::ceres::SpeedAndBiasError::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
-
parameters | Pointer to the parameters (see ceres) |
residuals | Pointer to the residual vector (see ceres) |
jacobians | Pointer to the Jacobians (see ceres) |
jacobiansMinimal | Pointer to the minimal Jacobians (equivalent to jacobians). |
- Returns
- Success of the evaluation.
Implements okvis::ceres::ErrorInterface.
const information_t& okvis::ceres::SpeedAndBiasError::information |
( |
| ) |
const |
|
inline |
Get the information matrix.
- Returns
- The information (weight) matrix.
Get the measurement.
- Returns
- The measurement vector.
size_t okvis::ceres::SpeedAndBiasError::parameterBlockDim |
( |
size_t |
parameterBlockId | ) |
const |
|
inlinevirtual |
Dimension of an individual parameter block.
- Parameters
-
[in] | parameterBlockId | ID of the parameter block of interest. |
- Returns
- The dimension.
Implements okvis::ceres::ErrorInterface.
size_t okvis::ceres::SpeedAndBiasError::parameterBlocks |
( |
| ) |
const |
|
inlinevirtual |
size_t okvis::ceres::SpeedAndBiasError::residualDim |
( |
| ) |
const |
|
inlinevirtual |
void okvis::ceres::SpeedAndBiasError::setInformation |
( |
const information_t & |
information | ) |
|
Set the information.
- Parameters
-
[in] | information | The information (weight) matrix. |
void okvis::ceres::SpeedAndBiasError::setMeasurement |
( |
const okvis::SpeedAndBias & |
measurement | ) |
|
|
inline |
Set the measurement.
- Parameters
-
[in] | measurement | The measurement. |
virtual std::string okvis::ceres::SpeedAndBiasError::typeInfo |
( |
| ) |
const |
|
inlinevirtual |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ::ceres::SizedCostFunction<9, 9> okvis::ceres::SpeedAndBiasError::base_t |
The 9x9 covariance matrix.
The 9x9 information matrix.
const int okvis::ceres::SpeedAndBiasError::kNumResiduals = 9 |
|
static |
information_t okvis::ceres::SpeedAndBiasError::squareRootInformation_ |
|
protected |
The 9x9 square root information matrix.
The documentation for this class was generated from the following files: