mirror of
https://github.com/hku-mars/FAST_LIO.git
synced 2023-04-06 16:28:55 +08:00
Add new parameter: time offset between LiDAR and IMU.
This commit is contained in:
@@ -2,6 +2,8 @@ common:
|
||||
lid_topic: "/os_cloud_node/points"
|
||||
imu_topic: "/os_cloud_node/imu"
|
||||
time_sync_en: false # ONLY turn on when external time synchronization is really not possible
|
||||
time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README).
|
||||
# This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0
|
||||
|
||||
preprocess:
|
||||
lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
|
||||
|
||||
Reference in New Issue
Block a user