diff --git a/README.md b/README.md index 0849132..9489d27 100644 --- a/README.md +++ b/README.md @@ -111,6 +111,7 @@ Edit ``` config/avia.yaml ``` to set the below parameters: 3. Translational extrinsic: ``` extrinsic_T ``` 4. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix) - The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). They can be found in the official manual. +- FAST-LIO produces a very simple software time sync for livox LiDAR, set parameter ```time_sync_en``` to ture to turn on. But turn on **ONLY IF external time synchronization is really not possible**, since the software time sync cannot make sure accuracy. ### 3.3 For Velodyne or Ouster (Velodyne as an example) diff --git a/config/avia.yaml b/config/avia.yaml index 921ecec..2f4c6be 100644 --- a/config/avia.yaml +++ b/config/avia.yaml @@ -1,6 +1,7 @@ common: lid_topic: "/livox/lidar" imu_topic: "/livox/imu" + time_sync_en: false # ONLY turn on when external time synchronization is really not possible preprocess: lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, diff --git a/config/horizon.yaml b/config/horizon.yaml index b4774ee..1b34be6 100644 --- a/config/horizon.yaml +++ b/config/horizon.yaml @@ -1,6 +1,7 @@ common: lid_topic: "/livox/lidar" imu_topic: "/livox/imu" + time_sync_en: false # ONLY turn on when external time synchronization is really not possible preprocess: lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, diff --git a/config/ouster64.yaml b/config/ouster64.yaml index b8e7957..55b0e44 100644 --- a/config/ouster64.yaml +++ b/config/ouster64.yaml @@ -1,6 +1,7 @@ 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 preprocess: lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, diff --git a/config/velodyne.yaml b/config/velodyne.yaml index 2e77bbd..b280b0c 100644 --- a/config/velodyne.yaml +++ b/config/velodyne.yaml @@ -1,6 +1,7 @@ common: lid_topic: "/velodyne_points" imu_topic: "/imu/data" + time_sync_en: false # ONLY turn on when external time synchronization is really not possible preprocess: lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, diff --git a/rviz_cfg/loam_livox.rviz b/rviz_cfg/loam_livox.rviz index 768e676..5699dba 100644 --- a/rviz_cfg/loam_livox.rviz +++ b/rviz_cfg/loam_livox.rviz @@ -9,7 +9,6 @@ Panels: - /mapping1/surround1 - /mapping1/currPoints1 - /mapping1/currPoints1/Autocompute Value Bounds1 - - /Odometry1 - /Odometry1/Odometry1 - /Odometry1/Odometry1/Shape1 - /Odometry1/Odometry1/Covariance1 @@ -86,9 +85,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 255 + Max Intensity: 150 Min Color: 0; 0; 0 - Min Intensity: 0 + Min Intensity: 1 Name: surround Position Transformer: XYZ Queue Size: 1 @@ -101,7 +100,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Alpha: 0.07000000029802322 + - Alpha: 0.10000000149011612 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 15 @@ -327,33 +326,33 @@ Visualization Manager: Views: Current: Class: rviz/ThirdPersonFollower - Distance: 122.74785614013672 + Distance: 10 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 17.150386810302734 - Y: 1.2471342086791992 - Z: 3.980784458690323e-5 - Focal Shape Fixed Size: true + X: 5.284592628479004 + Y: -1.0116491317749023 + Z: -9.5367431640625e-7 + Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false + Invert Z Axis: true Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.189797043800354 + Pitch: -0.31460127234458923 Target Frame: camera_init Value: ThirdPersonFollower (rviz) - Yaw: 3.293565511703491 + Yaw: 4.585422039031982 Saved: ~ Window Geometry: Displays: collapsed: false Height: 1385 Hide Left Dock: false - Hide Right Dock: true - QMainWindow State: 000000ff00000000fd00000004000000000000016b000004b7fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004b7000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009bd00000052fc0100000002fb0000000800540069006d00650100000000000009bd000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000084c000004b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000016b000004b7fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004b7000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009bd00000052fc0100000002fb0000000800540069006d00650100000000000009bd000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000006f4000004b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -361,7 +360,7 @@ Window Geometry: Tool Properties: collapsed: false Views: - collapsed: true + collapsed: false Width: 2493 X: 67 Y: 27 diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp index 15f518a..45fece8 100644 --- a/src/laserMapping.cpp +++ b/src/laserMapping.cpp @@ -70,7 +70,7 @@ double kdtree_incremental_time = 0.0, kdtree_search_time = 0.0, kdtree_delete_ti double T1[MAXN], s_plot[MAXN], s_plot2[MAXN], s_plot3[MAXN], s_plot4[MAXN], s_plot5[MAXN], s_plot6[MAXN], s_plot7[MAXN], s_plot8[MAXN], s_plot9[MAXN], s_plot10[MAXN], s_plot11[MAXN]; double match_time = 0, solve_time = 0, solve_const_H_time = 0; int kdtree_size_st = 0, kdtree_size_end = 0, add_point_size = 0, kdtree_delete_counter = 0; -bool runtime_pos_log = false, pcd_save_en = false; +bool runtime_pos_log = false, pcd_save_en = false, time_sync_en = false; /**************************/ float res_last[100000] = {0.0}; @@ -284,22 +284,37 @@ void standard_pcl_cbk(const sensor_msgs::PointCloud2::ConstPtr &msg) sig_buffer.notify_all(); } +double timediff_lidar_wrt_imu = 0.0; +bool timediff_set_flg = false; void livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg) { mtx_buffer.lock(); - scan_count ++; double preprocess_start_time = omp_get_wtime(); - cout<<"lidar got at: "<header.stamp.toSec()<header.stamp.toSec() < last_timestamp_lidar) { ROS_ERROR("lidar loop back, clear buffer"); lidar_buffer.clear(); } + last_timestamp_lidar = msg->header.stamp.toSec(); + + if (!time_sync_en && abs(last_timestamp_imu - lidar_end_time) > 10.0) + { + printf("IMU and LiDAR not Synced, IMU time: %lf, lidar scan end time: %lf",last_timestamp_imu, lidar_end_time); + } + + if (time_sync_en && !timediff_set_flg && abs(last_timestamp_lidar - last_timestamp_imu) > 1 && !imu_buffer.empty()) + { + timediff_set_flg = true; + timediff_lidar_wrt_imu = last_timestamp_lidar + 0.1 - last_timestamp_imu; + printf("Self sync IMU and LiDAR, time diff is %.10lf \n", timediff_lidar_wrt_imu); + } + PointCloudXYZI::Ptr ptr(new PointCloudXYZI()); p_pre->process(msg, ptr); lidar_buffer.push_back(ptr); - time_buffer.push_back(msg->header.stamp.toSec()); - last_timestamp_lidar = msg->header.stamp.toSec(); + time_buffer.push_back(last_timestamp_lidar); + s_plot11[scan_count] = omp_get_wtime() - preprocess_start_time; mtx_buffer.unlock(); sig_buffer.notify_all(); @@ -308,18 +323,23 @@ void livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg) void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in) { publish_count ++; - cout<<"IMU got at: "<header.stamp.toSec()<header.stamp.toSec()< 0.1 && time_sync_en) + { + msg->header.stamp = \ + ros::Time().fromSec(timediff_lidar_wrt_imu + msg_in->header.stamp.toSec()); + } + double timestamp = msg->header.stamp.toSec(); mtx_buffer.lock(); if (timestamp < last_timestamp_imu) { - ROS_ERROR("imu loop back, clear buffer"); + ROS_WARN("imu loop back, clear buffer"); imu_buffer.clear(); - flg_reset = true; } last_timestamp_imu = timestamp; @@ -349,11 +369,6 @@ bool sync_packages(MeasureGroup &meas) lidar_pushed = true; } - if (abs(last_timestamp_imu - lidar_end_time) > 10.0) - { - printf("IMU and LiDAR not Synced, IMU time: %lf, lidar scan end time: %lf",last_timestamp_imu, lidar_end_time); - } - if (last_timestamp_imu < lidar_end_time) { return false; @@ -439,7 +454,6 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFullRes) { RGBpointBodyToWorld(&laserCloudFullRes->points[i], \ &laserCloudWorld->points[i]); - cout<points[i].intensity<("map_file_path",map_file_path,""); nh.param("common/lid_topic",lid_topic,"/livox/lidar"); nh.param("common/imu_topic", imu_topic,"/livox/imu"); + nh.param("common/time_sync_en", time_sync_en, false); nh.param("filter_size_corner",filter_size_corner_min,0.5); nh.param("filter_size_surf",filter_size_surf_min,0.5); nh.param("filter_size_map",filter_size_map_min,0.5); @@ -761,6 +776,7 @@ int main(int argc, char** argv) ROS_WARN("reset when rosbag play back"); p_imu->Reset(); flg_reset = false; + Measures.imu.clear(); continue; } diff --git a/src/preprocess.cpp b/src/preprocess.cpp index e5ab948..ac347f4 100644 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -89,7 +89,7 @@ void Preprocess::avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) { for(uint i=1; ipoints[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10)) + if((msg->points[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) { pl_full[i].x = msg->points[i].x; pl_full[i].y = msg->points[i].y; @@ -138,7 +138,7 @@ void Preprocess::avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) { for(uint i=1; ipoints[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10)) + if((msg->points[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) { valid_num ++; if (valid_num % point_filter_num == 0)