OKVIS ROS
|
Implements a nonlinear IMU factor. More...
#include <ImuError.hpp>
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::ImuParameters & | imuParameters () const |
Get the IMU Parameters. More... | |
const okvis::ImuMeasurementDeque & | imuMeasurements () 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... | |
Implements a nonlinear IMU factor.
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 –.
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.
|
inline |
Default constructor – assumes information recomputation.
|
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.
|
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 IMU measurements.
|
inline |
Get the IMU Parameters.
|
inlinevirtual |
Dimension of an individual parameter block.
[in] | parameterBlockId | ID of the parameter block of interest. |
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Number of parameter blocks.
Implements okvis::ceres::ErrorInterface.
|
static |
Propagates pose, speeds and biases with given IMU measurements.
[in] | imuMeasurements | All the IMU measurements. |
[in] | imuParams | The parameters to be used. |
[in,out] | T_WS | Start pose. |
[in,out] | speedAndBiases | Start speed and biases. |
[in] | t_start | Start time. |
[in] | t_end | End time. |
[out] | covariance | Covariance for GIVEN start states. |
[out] | jacobian | Jacobian w.r.t. start states. |
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.
[in] | T_WS | Start pose. |
[in] | speedAndBiases | Start speed and biases. |
|
inlinevirtual |
Residual dimension.
Implements okvis::ceres::ErrorInterface.
|
inline |
(Re)set the measurements @param[in] imuMeasurements All the IMU measurements.
|
inline |
(Re)set the parameters. @param[in] imuParameters The parameters to be used.
|
inline |
(Re)set the start time. @param[in] t_0 Start time.
|
inline |
(Re)set the start time. @param[in] t_1 End time.
|
inline |
Get the start time.
|
inline |
Get the end time.
|
inlinevirtual |
Return parameter block type as string.
Implements okvis::ceres::ErrorInterface.
|
mutableprotected |
Intermediate result.
|
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.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
mutableprotected |
Intermediate result.
|
protected |
The IMU measurements used. Must be spanning t0_ - t1_.
|
protected |
The IMU parameters.
|
mutableprotected |
The information matrix for this error term.
|
static |
The number of residuals.
|
mutableprotected |
The Jacobian of the increment (w/o biases).
|
mutableprotected |
|
mutableprotected |
Keeps track of whether or not this redoPreintegration() needs to be called.
|
mutableprotected |
Counts the number of preintegrations for statistics.
|
mutableprotected |
Reference biases that are updated when called redoPreintegration.
|
mutableprotected |
The square root information matrix for this error term.
|
protected |
The start time (i.e. time of the first set of states).
|
protected |
The end time (i.e. time of the sedond set of states).