rko_lio.lio module¶
Public interface classes for the pybind.
- class rko_lio.lio.LIO(config: LIOConfig)¶
Bases:
object
- add_imu_measurement(acceleration: numpy.ndarray, angular_velocity: numpy.ndarray, time: float)¶
- add_imu_measurement_with_extrinsic(extrinsic_imu2base: numpy.ndarray, acceleration: numpy.ndarray, angular_velocity: numpy.ndarray, time: float)¶
- dump_results_to_disk(results_dir: Path, run_name: str)¶
- map_point_cloud() numpy.ndarray ¶
return the local map point cloud in world/odometry frame
- pose() numpy.ndarray ¶
return the 4x4 transform from the base frame to the world/odometry frame
- register_scan(scan: numpy.ndarray, timestamps: numpy.ndarray)¶
- register_scan_with_extrinsic(extrinsic_lidar2base: numpy.ndarray, scan: numpy.ndarray, timestamps: numpy.ndarray)¶
- class rko_lio.lio.LIOConfig(*args: Any, **kwargs: Any)¶
Bases:
_Config
LIO configuration options.
- Parameters:
deskew (bool, default True) – If True, perform scan deskewing.
max_iterations (int, default 100) – Maximum optimization iterations for scan matching.
voxel_size (float, default 1.0) – Size of map voxels (meters).
max_points_per_voxel (int, default 20) – Maximum points stored per voxel.
max_range (float, default 100.0) – Max usable range of lidar (meters).
min_range (float, default 1.0) – Minimum usable range of lidar (meters).
convergence_criterion (float, default 1e-5) – Convergence threshold for optimization.
max_correspondance_distance (float, default 0.5) – Max distance for associating points (meters).
max_num_threads (int, default 0) – Max thread count (0 = autodetect).
initialization_phase (bool, default False) – Whether to initialize on the first two lidar message.
max_expected_jerk (float, default 3.0) – Max expected IMU jerk (m/s^3).
double_downsample (bool, default True) – Double downsamples the incoming scan before registering. Disabling for sparse LiDARs may improve results.
min_beta (float, default 200.0) – Minimum scaling on the orientation regularisation weight. Set to -1 to disable the cost.