PreintegratedCombinedMeasurements integrates the IMU measurements (rotation rates and accelerations) and the corresponding covariance matrix. The measurements are then used to build the CombinedImuFactor. Integration is done incrementally (ideally, one integrates the measurement as soon as it is received from the IMU) so as to avoid costly integration at time of factor construction.
CombinedImuFactor is a 6-ways factor involving previous state (pose and velocity of the vehicle, as well as bias at previous time step), and current state (pose, velocity, bias at current time step). Following the pre- integration scheme proposed in [2], the CombinedImuFactor includes many IMU measurements, which are "summarized" using the PreintegratedCombinedMeasurements class. There are 3 main differences wrpt the ImuFactor class: 1) The factor is 6-ways, meaning that it also involves both biases (previous and current time step).Therefore, the factor internally imposes the biases to be slowly varying; in particular, the matrices "biasAccCovariance" and "biasOmegaCovariance" described the random walk that models bias evolution. 2) The preintegration covariance takes into account the noise in the bias estimate used for integration. 3) The covariance matrix of the PreintegratedCombinedMeasurements preserves the correlation between the bias uncertainty and the preintegrated measurements uncertainty.
PreintegratedImuMeasurements accumulates (integrates) the IMU measurements (rotation rates and accelerations) and the corresponding covariance matrix. The measurements are then used to build the Preintegrated IMU factor. Integration is done incrementally (ideally, one integrates the measurement as soon as it is received from the IMU) so as to avoid costly integration at time of factor construction.
ImuFactor is a 5-ways factor involving previous state (pose and velocity of the vehicle at previous time step), current state (pose and velocity at current time step), and the bias estimate. Following the preintegration scheme proposed in [2], the ImuFactor includes many IMU measurements, which are "summarized" using the PreintegratedIMUMeasurements class. Note that this factor does not model "temporal consistency" of the biases (which are usually slowly varying quantities), which is up to the caller. See also CombinedImuFactor for a class that does this for you.
ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
A class for a soft prior on any Value type
Binary factor for a bearing/range measurement
A class for downdating an existing factor from a graph. The AntiFactor returns the same linearized Hessian matrices of the original factor, but with the opposite sign. This effectively cancels out any affects of the original factor during optimization."
A class for a measurement predicted by "between(config[key1],config[key2])"
VALUE | the Value type |
Unary inequality constraint forcing a scalar to be greater/less than a fixed threshold. The function will need to have its value function implemented to return a scalar for comparison.
Binary factor between two Pose3 variables induced by an EssentialMatrix measurement
Non-linear factor for a constraint derived from a 2D measurement. The calibration is unknown here compared to GenericProjectionFactor
Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here. i.e. the main building block for visual SLAM.
If you are using the factor, please cite: L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally independent sets in factor graphs: a unifying perspective based on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014.
This factor assumes that camera calibration is fixed, and that the calibration is the same for all cameras involved in this factor. The factor only constrains poses (variable dimension is 6). This factor requires that values contains the involved poses (Pose3). If the calibration should be optimized, as well, use SmartProjectionFactor instead!
Non-linear factor for a constraint derived from a 2D measurement. The calibration and pose are assumed known.
A class to model GPS measurements, including a bias term which models common-mode errors and that can be partially corrected if other sensors are used
A class for a measurement predicted by "between(config[key1],config[key2])"
POSE | the Pose type |
A class for a measurement between a pose and a point.
Non-linear factor for a constraint derived from a 2D measurement. This factor estimates the body pose, body-camera transform, 3D landmark, and calibration.
Smart factor for range SLAM
This factor assumes that camera calibration is fixed, but each camera has its own calibration. The factor only constrains poses (variable dimension is 6). This factor requires that values contains the involved poses (Pose3).