OKVIS ROS
|
Absolute error of a pose. More...
#include <PoseError.hpp>
Public Types | |
typedef Eigen::Matrix< double, 6, 6 > | information_t |
The information matrix type (6x6). More... | |
typedef Eigen::Matrix< double, 6, 6 > | covariance_t |
The covariance matrix type (same as information). More... | |
Public Member Functions | |
PoseError () | |
Default constructor. More... | |
PoseError (const okvis::kinematics::Transformation &measurement, const Eigen::Matrix< double, 6, 6 > &information) | |
Construct with measurement and information matrix. More... | |
PoseError (const okvis::kinematics::Transformation &measurement, double translationVariance, double rotationVariance) | |
Construct with measurement and variance. More... | |
virtual | ~PoseError () |
Trivial destructor. More... | |
virtual bool | Evaluate (double const *const *parameters, double *residuals, double **jacobians) const |
This evaluates the error term and additionally computes the Jacobians. More... | |
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 representation. More... | |
size_t | residualDim () const |
Residual dimension. More... | |
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... | |
Setters | |
void | setMeasurement (const okvis::kinematics::Transformation &measurement) |
Set the measurement. More... | |
void | setInformation (const information_t &information) |
Set the information. More... | |
Getters | |
const okvis::kinematics::Transformation & | measurement () const |
Get the measurement. More... | |
const information_t & | information () const |
Get the information matrix. More... | |
const information_t & | covariance () const |
Get the covariance matrix. More... | |
Public Member Functions inherited from okvis::ceres::ErrorInterface | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ErrorInterface () |
Constructor. More... | |
virtual | ~ErrorInterface () |
Destructor (does nothing). More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef::ceres::SizedCostFunction< 6, 7 > | base_t |
The base class type. More... | |
Static Public Attributes | |
static const int | kNumResiduals = 6 |
The number of residuals (6). More... | |
Protected Attributes | |
okvis::kinematics::Transformation | measurement_ |
The pose measurement. More... | |
information_t | information_ |
The 6x6 information matrix. More... | |
information_t | squareRootInformation_ |
The 6x6 square root information matrix. More... | |
covariance_t | covariance_ |
The 6x6 covariance matrix. More... | |
Absolute error of a pose.
typedef Eigen::Matrix<double, 6, 6> okvis::ceres::PoseError::covariance_t |
The covariance matrix type (same as information).
typedef Eigen::Matrix<double, 6, 6> okvis::ceres::PoseError::information_t |
The information matrix type (6x6).
|
inline |
Default constructor.
okvis::ceres::PoseError::PoseError | ( | const okvis::kinematics::Transformation & | measurement, |
const Eigen::Matrix< double, 6, 6 > & | information | ||
) |
Construct with measurement and information matrix.
[in] | measurement | The measurement. |
[in] | information | The information (weight) matrix. |
okvis::ceres::PoseError::PoseError | ( | const okvis::kinematics::Transformation & | measurement, |
double | translationVariance, | ||
double | rotationVariance | ||
) |
Construct with measurement and variance.
[in] | measurement | The measurement. |
[in] | translationVariance | The translation variance. |
[in] | rotationVariance | The rotation variance. |
|
inlinevirtual |
Trivial destructor.
|
inline |
Get the covariance matrix.
|
virtual |
This evaluates the error term and additionally computes the Jacobians.
parameters | Pointer to the parameters (see ceres) |
residuals | Pointer to the residual vector (see ceres) |
jacobians | Pointer to the Jacobians (see ceres) |
|
virtual |
This evaluates the error term and additionally computes the Jacobians in the minimal internal representation.
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). |
Implements okvis::ceres::ErrorInterface.
|
inline |
Get the information matrix.
|
inline |
Get the measurement.
|
inlinevirtual |
Dimension of an individual parameter block.
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Number of parameter blocks.
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Residual dimension.
Implements okvis::ceres::ErrorInterface.
void okvis::ceres::PoseError::setInformation | ( | const information_t & | information | ) |
Set the information.
[in] | information | The information (weight) matrix. |
|
inline |
Set the measurement.
[in] | measurement | The measurement. |
|
inlinevirtual |
Return parameter block type as string.
Implements okvis::ceres::ErrorInterface.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ::ceres::SizedCostFunction<6, 7> okvis::ceres::PoseError::base_t |
The base class type.
|
protected |
The 6x6 covariance matrix.
|
protected |
The 6x6 information matrix.
|
static |
The number of residuals (6).
|
protected |
The pose measurement.
|
protected |
The 6x6 square root information matrix.