Closed KkCabin closed 6 months ago
Hello @KkCabin,
We appreciate you choosing MA-LIO for your project.
From your description, it appears that your parameter settings are appropriate, and the initialization process seems to be functioning correctly.
To assist you further, could you please share your dataset with us? If it's possible, a Google Drive link or any other file-sharing method would be great. In case the dataset is large, including just the segment where the error occurs and about 10 seconds after the error occurred from the beginning would be sufficient.
Looking forward to your response and thank you for your cooperation.
Hello, thank you very much for your help. This is the link to the sample data. https://drive.google.com/file/d/1fL-_xBhkdeMwyX-nczEyNvSqI0eQ1r__/view?usp=drive_link I have provided the yaml I used and some corresponding explanations. Feel free to contact me if you have any questions. Thank you again.
Hello @KkCabin,
Thanks for providing the dataset and additional details.
Given that our repository, MA-LIO, is an extension of FAST-LIO2, it's important to first verify if the issue persists when using a single LiDAR, as FAST-LIO2 operates without issues in such a configuration.
Upon reviewing your data with just one LiDAR, I observed similar performance issues as you described. This led me to compare the MA-LIO codebase with FAST-LIO2, revealing key distinctions between the two.
In MA-LIO, we tend to select measurements as planes when the variable s
is greater than 0.1, as seen in this segment of our code: https://github.com/minwoo0611/MA-LIO/blob/b911ad69c3a8bf43133333e8913d0d42cb5dabba/MA_LIO/src/laserMapping.cpp#L601. In contrast, FAST-LIO2 uses a threshold of 0.9.
Your dataset presents a unique challenge with features that share the same normal vector at starting points, making the selection of points a critical factor over the quantity of measurements. Therefore, we modified the 's' condition to 0.9.
Additionally, considering that measurements occur in environments with limited variability (only two normal vectors), we adjusted the parameters for localize_cov_max
and localize_cov_min
to be larger, and point_cov_max
and point_cov_min
to be smaller.
After these adjustments, MA-LIO demonstrated improved results, as showcased below.
Furthermore, your dataset presents a fascinating and challenging scenario, especially considering the starting point is situated in a particularly difficult environment. I want to express my gratitude once again for bringing this issue to our attention and for sharing your dataset. Your contribution is invaluable in helping us improve MA-LIO and better understand its performance in diverse conditions.
Hello, @minwoo0611, Thank you for your prompt response and detailed analysis. The issues mentioned earlier have been well resolved, and there are two small issues that I need to consult with you: I tried to adjust the four covariance parameters you mentioned, but the results were not very satisfactory. Would it be convenient for you to guide the specific parameters? Also, I noticed that your map visualization is clear. Is the adjustment of visualization achieved through RVIZ? Or modify the pointcloud data structure? Thank you again. Looking forward to your reply.
Sorry for the late reply!
To address your queries:
For parameter tuning, we used the following settings:
In the case of a .launch
file:
<param name="max_iteration" type="int" value="5" />
<param name="filter_size_surf" type="double" value="0.45" />
<param name="filter_size_map" type="double" value="0.45" />
<param name="cube_side_length" type="double" value="1000" />
<param name="plane_th" type="double" value="0.1" />
In the case of a yaml
file:
common:
lid_topic: ["/livox/lidar_3JEDK4L00130111", "/livox/lidar_3WEDJA700100231", "/livox/lidar_3WEDK5C001EQ881"]
lid_type: [1, 1, 1] # 1-Livox 2-Velodyne 3-Ouster
N_SCANS: [6, 6, 6]
point_filter_num: [3, 3, 3]
lid_num: 3
imu_topic: "/livox/imu_3JEDK4L00130111"
time_sync_en: false # ONLY turn on when external time synchronization is not possible
time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g., LI-Init.
preprocess:
timestamp_unit: 3 # Time unit in PointCloud2 rostopic: 0-second, 1-millisecond, 2-microsecond, 3-nanosecond.
blind: 5
mapping:
acc_cov: 0.1
gyr_cov: 0.1
b_acc_cov: 0.0001
b_gyr_cov: 0.0001
fov_degree: 90
det_range: 450.0
extrinsic_est_en: false # Enable/disable online estimation of IMU-LiDAR extrinsic.
# ... (extrinsic parameters)
publish:
path_en: true
scan_publish_en: true
dense_publish_en: true
scan_bodyframe_pub_en: true
pcd_save:
pcd_save_en: true
interval: -1
uncertainty:
point_cov_max: 0.003
point_cov_min: 0.002
plane_cov_max: 1.25
plane_cov_min: 0.8
localize_cov_max: 10
localize_cov_min: 5
localize_thresh_max: 1.5
localize_thresh_min: 0.75
cov_threshold: 0.5
Since it may not be the best parameters, I recommend you to change the variables based on these settings!
Regarding visualization, we use the pointcloud's intensity and the Foxglove visualizer tools. Although modifying the point intensity from lidar_idx to their actual intensity is feasible, it can be a bit of direct coding. We also highly recommend using Foxglove for visualization as it is lightweight and efficient.
Let me know if you need further assistance!
Hello, @minwoo0611 Thank you for your help. I have achieved the expected result, and I will continue to learn your paper and open source code for further adaptation. Additionally, the Foxglove visualizer tool you recommended looks great and I am eager to give it a try. Thank you again for your positive and prompt response. Thank you for your outstanding work and open source spirit. All my issues have been quickly resolved, thank you.
Hello, thank you for your excellent work. I made an attempt on my own dataset, which includes one livox avia and two livox horizons. I use aiva as the main lidar and the imu data I use is the built-in imu in avia. Also, I know the extrinsics between two horiozns and avia. I have modified yaml as follows:
At the beginning of the program, the point cloud in rviz was normal, but after running for a short period of time, the point cloud encountered an error and the program stopped.
I tried to apply extrinsic est set en to false, although the program will not stop, the estimation of motion is incorrect, as shown in the following figure,
In addition, after making simple modifications to fast lio2, the dataset and corresponding parameters I used were able to run normally, and the normal results are roughly as follows
I am not sure if the information I have provided is sufficient. Looking forward to your reply.