Documentation Index
Fetch the complete documentation index at: https://mintlify.com/UZ-SLAMLab/ORB_SLAM3/llms.txt
Use this file to discover all available pages before exploring further.
Overview
The IMU namespace provides data structures and classes for handling inertial measurements in ORB-SLAM3’s visual-inertial mode. It includes raw IMU measurements, bias estimation, calibration, and preintegration.
Header: ImuTypes.h
Namespace: ORB_SLAM3::IMU
Constants
const float GRAVITY_VALUE = 9.81
Standard gravity magnitude in m/s².
IMU::Point
Represents a single IMU measurement with accelerometer and gyroscope data.
Structure
class Point {
public:
Eigen::Vector3f a; // Accelerometer (m/s²)
Eigen::Vector3f w; // Gyroscope (rad/s)
double t; // Timestamp (seconds)
}
Constructors
Point(
const float &acc_x, const float &acc_y, const float &acc_z,
const float &ang_vel_x, const float &ang_vel_y, const float &ang_vel_z,
const double ×tamp
)
Construct from individual components.
Parameters:
acc_x, acc_y, acc_z - Accelerometer readings in m/s²
ang_vel_x, ang_vel_y, ang_vel_z - Gyroscope readings in rad/s
timestamp - Measurement timestamp in seconds
Point(
const cv::Point3f Acc,
const cv::Point3f Gyro,
const double ×tamp
)
Construct from OpenCV 3D points.
Parameters:
Acc - Accelerometer vector
Gyro - Gyroscope vector
timestamp - Measurement timestamp
Usage Example
// Create IMU measurement
IMU::Point imu(ax, ay, az, wx, wy, wz, timestamp);
// Access data
Eigen::Vector3f accel = imu.a;
Eigen::Vector3f gyro = imu.w;
double time = imu.t;
IMU::Bias
Represents IMU biases for accelerometer and gyroscope.
Structure
class Bias {
public:
float bax, bay, baz; // Accelerometer bias (m/s²)
float bwx, bwy, bwz; // Gyroscope bias (rad/s)
}
Constructors
Default constructor (all biases = 0).
Bias(
const float &b_acc_x, const float &b_acc_y, const float &b_acc_z,
const float &b_ang_vel_x, const float &b_ang_vel_y, const float &b_ang_vel_z
)
Construct with specific bias values.
Parameters:
b_acc_x, b_acc_y, b_acc_z - Accelerometer bias components
b_ang_vel_x, b_ang_vel_y, b_ang_vel_z - Gyroscope bias components
Methods
Copy bias values from another Bias object.
Stream Operator
friend std::ostream& operator<<(std::ostream &out, const Bias &b)
Output bias values to stream.
Usage Example
// Initialize bias
IMU::Bias bias(0.01, -0.005, 0.02, 0.001, -0.001, 0.0005);
// Access components
float acc_bias_x = bias.bax;
float gyro_bias_z = bias.bwz;
// Print
std::cout << "IMU Bias: " << bias << std::endl;
IMU::Calib
IMU calibration including extrinsic transform and noise parameters.
Structure
class Calib {
public:
Sophus::SE3<float> mTcb; // Transform: camera to IMU body
Sophus::SE3<float> mTbc; // Transform: IMU body to camera
Eigen::DiagonalMatrix<float,6> Cov; // Measurement covariance
Eigen::DiagonalMatrix<float,6> CovWalk; // Random walk covariance
bool mbIsSet; // Calibration validity flag
}
Constructors
Default constructor (not set).
Calib(
const Sophus::SE3<float> &Tbc,
const float &ng, // Gyroscope noise density
const float &na, // Accelerometer noise density
const float &ngw, // Gyroscope random walk
const float &naw // Accelerometer random walk
)
Construct with calibration parameters.
Parameters:
Tbc - Transform from IMU body frame to camera frame
ng - Gyroscope noise density (rad/s/√Hz)
na - Accelerometer noise density (m/s²/√Hz)
ngw - Gyroscope random walk (rad/s²/√Hz)
naw - Accelerometer random walk (m/s³/√Hz)
Calib(const Calib &calib)
Copy constructor.
Methods
void Set(
const Sophus::SE3<float> &sophTbc,
const float &ng, const float &na,
const float &ngw, const float &naw
)
Set calibration parameters.
Usage Example
// Define IMU-camera transform
Sophus::SE3f Tbc = ...; // From calibration
// Set noise parameters
float ng = 0.01; // Gyro noise
float na = 0.1; // Accel noise
float ngw = 0.0001; // Gyro walk
float naw = 0.001; // Accel walk
// Create calibration
IMU::Calib calib(Tbc, ng, na, ngw, naw);
IMU::IntegratedRotation
Integration of a single gyroscope measurement.
Structure
class IntegratedRotation {
public:
float deltaT; // Integration time
Eigen::Matrix3f deltaR; // Rotation increment
Eigen::Matrix3f rightJ; // Right Jacobian
}
Constructor
IntegratedRotation(
const Eigen::Vector3f &angVel,
const Bias &imuBias,
const float &time
)
Integrate one gyroscope measurement.
Parameters:
angVel - Angular velocity measurement
imuBias - Current IMU bias estimate
time - Integration time step
IMU::Preintegrated
Preintegrated IMU measurements between keyframes.
Key Members
class Preintegrated {
public:
float dT; // Total integration time
// Preintegrated measurements
Eigen::Matrix3f dR; // Rotation
Eigen::Vector3f dV; // Velocity
Eigen::Vector3f dP; // Position
// Jacobians w.r.t. bias
Eigen::Matrix3f JRg, JVg, JVa, JPg, JPa;
// Average measurements
Eigen::Vector3f avgA; // Average acceleration
Eigen::Vector3f avgW; // Average angular velocity
// Covariance matrices
Eigen::Matrix<float,15,15> C; // Covariance
Eigen::Matrix<float,15,15> Info; // Information matrix
// Noise parameters
Eigen::DiagonalMatrix<float,6> Nga, NgaWalk;
// Bias
Bias b; // Original bias
}
Constructors
Preintegrated(const Bias &b_, const Calib &calib)
Construct preintegration with initial bias and calibration.
Preintegrated(Preintegrated *pImuPre)
Copy constructor.
Core Methods
Initialize
void Initialize(const Bias &b_)
Initialize/reset preintegration with new bias.
Integrate Measurement
void IntegrateNewMeasurement(
const Eigen::Vector3f &acceleration,
const Eigen::Vector3f &angVel,
const float &dt
)
Add new IMU measurement to preintegration.
Parameters:
acceleration - Accelerometer reading (m/s²)
angVel - Gyroscope reading (rad/s)
dt - Time step since last measurement
Reintegrate
Recompute preintegration with updated bias (after optimization).
Merge
void MergePrevious(Preintegrated *pPrev)
Merge with previous preintegration (when removing keyframe).
Update Bias
void SetNewBias(const Bias &bu_)
Update bias estimate and recompute deltas.
Delta Computation
Get preintegrated values with bias correction:
Eigen::Matrix3f GetDeltaRotation(const Bias &b_)
Eigen::Vector3f GetDeltaVelocity(const Bias &b_)
Eigen::Vector3f GetDeltaPosition(const Bias &b_)
Parameters:
b_ - Bias to use for correction
Returns: Corrected preintegrated rotation/velocity/position
Original Values
Get values computed with original bias:
Eigen::Matrix3f GetOriginalDeltaRotation()
Eigen::Vector3f GetOriginalDeltaVelocity()
Eigen::Vector3f GetOriginalDeltaPosition()
Updated Values
Get values with current updated bias:
Eigen::Matrix3f GetUpdatedDeltaRotation()
Eigen::Vector3f GetUpdatedDeltaVelocity()
Eigen::Vector3f GetUpdatedDeltaPosition()
Bias Access
Get bias used for original integration.
Get current updated bias.
IMU::Bias GetDeltaBias(const Bias &b_)
Compute difference between given bias and original.
Eigen::Matrix<float,6,1> GetDeltaBias()
Get current bias correction as 6D vector.
Copy
void CopyFrom(Preintegrated *pImuPre)
Copy all preintegration data from another object.
Usage Example
// Create preintegration
IMU::Bias initialBias;
IMU::Calib calib(Tbc, ng, na, ngw, naw);
IMU::Preintegrated preint(initialBias, calib);
// Add measurements
for (auto& imu : vImuMeasurements) {
preint.IntegrateNewMeasurement(imu.a, imu.w, dt);
}
// Get preintegrated values
Eigen::Matrix3f dR = preint.GetDeltaRotation(currentBias);
Eigen::Vector3f dV = preint.GetDeltaVelocity(currentBias);
Eigen::Vector3f dP = preint.GetDeltaPosition(currentBias);
// After bias optimization
preint.SetNewBias(optimizedBias);
Lie Algebra Functions
Utility functions for SO(3) operations:
Eigen::Matrix3f RightJacobianSO3(const Eigen::Vector3f &v)
Compute right Jacobian of SO(3).
Eigen::Matrix3f InverseRightJacobianSO3(const Eigen::Vector3f &v)
Compute inverse right Jacobian of SO(3).
Eigen::Matrix3f NormalizeRotation(const Eigen::Matrix3f &R)
Project matrix to SO(3) (nearest rotation matrix).
Integration in SLAM Pipeline
- Initialization: Create
Preintegrated with initial bias from previous keyframe
- Tracking: Integrate IMU measurements between frames using
IntegrateNewMeasurement
- Keyframe Creation: Store preintegrated measurements in keyframe
- Optimization: Update bias estimates, recompute using
SetNewBias
- Prediction: Use deltas to predict next frame pose
See Also
- Settings - IMU configuration loading
- System - Visual-Inertial SLAM modes