Skip to content

Commit

Permalink
Add new parameter: time offset between LiDAR and IMU.
Browse files Browse the repository at this point in the history
  • Loading branch information
zfc-zfc committed Aug 24, 2022
1 parent 342d361 commit 99c462a
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 3 deletions.
4 changes: 3 additions & 1 deletion config/avia.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@ common:
lid_topic: "/livox/lidar"
imu_topic: "/livox/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: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
Expand Down Expand Up @@ -30,4 +32,4 @@ publish:
pcd_save:
pcd_save_en: true
interval: -1 # how many LiDAR frames saved in each pcd file;
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
4 changes: 3 additions & 1 deletion config/horizon.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@ common:
lid_topic: "/livox/lidar"
imu_topic: "/livox/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: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
Expand Down Expand Up @@ -30,4 +32,4 @@ publish:
pcd_save:
pcd_save_en: true
interval: -1 # how many LiDAR frames saved in each pcd file;
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
2 changes: 2 additions & 0 deletions config/ouster64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
4 changes: 3 additions & 1 deletion config/velodyne.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,9 @@ common:
lid_topic: "/velodyne_points"
imu_topic: "/imu/data"
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: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
scan_line: 32
Expand Down
4 changes: 4 additions & 0 deletions src/laserMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ bool runtime_pos_log = false, pcd_save_en = false, time_sync_en = false, extri
float res_last[100000] = {0.0};
float DET_RANGE = 300.0f;
const float MOV_THRESHOLD = 1.5f;
double time_diff_lidar_to_imu = 0.0;

mutex mtx_buffer;
condition_variable sig_buffer;
Expand Down Expand Up @@ -343,6 +344,8 @@ void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in)
ros::Time().fromSec(timediff_lidar_wrt_imu + msg_in->header.stamp.toSec());
}

msg->header.stamp = ros::Time().fromSec(msg_in->header.stamp.toSec() - time_diff_lidar_to_imu);

double timestamp = msg->header.stamp.toSec();

mtx_buffer.lock();
Expand Down Expand Up @@ -760,6 +763,7 @@ int main(int argc, char** argv)
nh.param<string>("common/lid_topic",lid_topic,"/livox/lidar");
nh.param<string>("common/imu_topic", imu_topic,"/livox/imu");
nh.param<bool>("common/time_sync_en", time_sync_en, false);
nh.param<double>("common/time_offset_lidar_to_imu", time_diff_lidar_to_imu, 0.0);
nh.param<double>("filter_size_corner",filter_size_corner_min,0.5);
nh.param<double>("filter_size_surf",filter_size_surf_min,0.5);
nh.param<double>("filter_size_map",filter_size_map_min,0.5);
Expand Down

0 comments on commit 99c462a

Please sign in to comment.