Class LIO

Nested Relationships

Nested Types

Class Documentation

class LIO

Core LiDAR-inertial odometry algorithm class.

Public Functions

explicit LIO(const Config &config_)
void add_imu_measurement(const ImuControl &base_imu)

Add an IMU measurement expressed in the base frame.

void add_imu_measurement(const Sophus::SE3d &extrinsic_imu2base, const ImuControl &raw_imu)

Add an IMU measurement expressed in the IMU frame and transform it to the base frame using the given extrinsic calibration.

Parameters:
  • extrinsic_imu2base – Extrinsic transform from IMU to base frame.

  • raw_imu – Raw IMU measurement.

Vector3dVector register_scan(const Vector3dVector &scan, const TimestampVector &timestamps)

Register a LiDAR scan, applying deskewing based on the initial motion guess and clipping points beyond valid range.

Parameters:
  • scan – Input raw point cloud.

  • timestamps – Absolute timestamps corresponding to each scan point.

Returns:

Deskewed and clipped point cloud.

Vector3dVector register_scan(const Sophus::SE3d &extrinsic_lidar2base, const Vector3dVector &scan, const TimestampVector &timestamps)

Register a LiDAR scan for which the extrinsic calibration from lidar to base has already been applied.

Parameters:
  • extrinsic_lidar2base – Extrinsic from lidar to base frame.

  • scan – Input raw point cloud.

  • timestamps – Absolute timestamps corresponding to each scan point.

Returns:

Deskewed and clipped scan in the original lidar frame.

Public Members

Config config

Configuration parameters.

VoxelHashMap map

Local map.

State lidar_state

Current LiDAR state estimate.

ImuBias imu_bias

IMU bias estimates when initialization is enabled.

Eigen::Vector3d mean_body_acceleration = Eigen::Vector3d::Zero()

Mean body acceleration estimate.

Eigen::Matrix3d body_acceleration_covariance = Eigen::Matrix3d::Identity()

Covariance of body acceleration estimate.

IntervalStats interval_stats

IMU measurement statistics since last LiDAR frame.

std::vector<std::pair<Nsec, Sophus::SE3d>> poses_with_timestamps

Sequence of registered scan poses with corresponding timestamps.

State imu_state

Base-frame state propagated from IMU measurements.

Runs ahead of lidar_state between scans; reset to the optimized lidar pose after each successful registration. Used for gravity compensation and for publishing IMU-rate odometry from the ROS wrapper.

struct Config

Configuration parameters for odometry.

Public Members

bool deskew = true

Enable scan deskewing.

size_t max_iterations = 100

Maximum number of ICP iterations.

double voxel_size = 1.0

Size of voxel grid (m).

int max_points_per_voxel = 20

Max points per voxel.

double max_range = 100.0

Maximum lidar range (m).

double min_range = 1.0

Minimum lidar range (m).

double convergence_criterion = 1e-5

ICP convergence threshold.

double max_correspondence_distance = 0.5

Max distance for correspondences (m).

int max_num_threads = 0

Thread count for data association (0 = automatic).

bool initialization_phase = false

Enable initialization phase.

double max_expected_jerk = 3

Maximum expected jerk (m/s³).

bool double_downsample = true

Enable double downsampling.

double min_beta = 200

Minimum weight for orientation regularization.