robotics-upo / dll

DLL: Direct Lidar Localization
BSD 3-Clause "New" or "Revised" License
186 stars 40 forks source link

Working with a new reference map #13

Open MigVega opened 1 year ago

MigVega commented 1 year ago

Hi all,

First of all, thank you for your awesome work. Your code is very well structured and commented on, and that really helps to understand and learn how it works.

I have been trying to implement it on a new dataset. I was able to run it without issues with the catec example. However, with my data, I need help to get it to work.

You can find here a small set of my data (together with a launch file that executes your package):

The issue seems to be related to the map, even when I reduced the size of the map drastically, the method still seems to not be able to recognize it. One interesting fact is that If I play my bag file and load your catec.bt map, the method tries to find the correct alignment and works much better than with my map, Using my map, after giving the initial pose the current scan stays for a few seconds in that pose and then jumps far away.

I have tried to create smaller and dense maps, however, I have yet to succeed to make it work. Is there something special I should consider while changing the map (besides the size which was already mentioned in this issue)?

The other question I have is about using the odometry from LOAM, I think I will create another issue for that later.

fercabe commented 1 year ago

Hi Miguel Ángel,

At first glance, I can see in your launch file that parameter "align_method" is set to 3, which is ICP. Please, set to 1 (DLL).

In addition, I would have a look at the TF-tree to see if the different frames are ok, and well-connected.

If the error persists, do not hesitate to email me (you find my email it in the paper), so that you can give me details directly.

Un abrazo, Fernando caballero

MigVega commented 1 year ago

Hi Fernando,

Thanks for the quick answer.

In the end, we also tested with different methods to see if it performed better, but the performance was almost the same. The alignment With ICP seems to be very slow, but then it jumps far away, similar to DLL and NDT.

Here you can see the TF-tree; it is the same as when I run your catec1.launch example. TF_tree

Here you can see videos of the behavior: https://www.dropbox.com/scl/fo/nwbn3hnm4wmyupgd45it9/h?dl=0&rlkey=u8mmweb817bgaka8d7u62h0yp

You can see here that If I play my bag file and load your catec.bt map, the method tries to find the correct alignment and works much better than with my map. Therefore the issue is with my map.

Here is also a larger bag file with the corrected launch file. https://www.dropbox.com/scl/fo/ixn4xz2tbnivenc3z7602/h?dl=0&rlkey=wtgqfun5bhuv5ls82adl8bxf1

What are the advantages of using a bt file instead of a point cloud? What do you think you could recommend to obtain a bt file from a point cloud? Could we use a point cloud as input for DLL?

un saludo, Miguel Arturo :)

fercabe commented 1 year ago

Hi Miguel Arturo,

The TF seems to be right. Your map, in principle, looks good, do not see any reason to not work properly. I will take a look at your bag and map during this week, and let you know about it.

Regarding your questions about the .bt, we use it because it is convenient. Normally, you do not have a single point-cloud of the map. Instead, people launch a slam, localize the robot and then “accumulate” the poin-cliuds of the different robot's poses. We use octomap for mapping, which produce .bt files a representation of the environment. If you have a single .pcd file with the point-cloud of the envirnoment, then it is easy to update the code to read directly from it insteat of the .bt.

Fernando Caballero

MigVega commented 1 year ago

Hi Fernando,

A ok, so the .bt is used because of octomap. I also like it; it is very convenient to have a representation of the free space for me as well!

Thanks, let me know if you have issues or questions regarding my bag and map files.

Best, Miguel

fercabe commented 1 year ago

Hi Miguel,

Taking a look to your data, I can see the following issues:

Hope this help, Fernando

fercabe commented 1 year ago

Dear Miguel, did you solve this issue? Something new to comment?

MigVega commented 1 year ago

Dear Fernando,

Thanks for your help. I'm sorry for not getting back to you sooner; I have been focusing on other issues. Recently, we have tried the following:

We first generated a new map ConSLAM_cut05.bt with a resolution of 0.05, as you instructed, and obtained an accurate initial robot position. However, a significant drift occurs during the localization process, and the LIDAR scan point cloud does not align with the 3D map. Even with the correct initial z value, the map jumps at the very beginning and seems to be below the floor of the prior map. As a result, we modified the z-coordinate of the initial position from 0.58 to 3.58. Subsequently, the robot appeared in the correct position, and it ran stably for the first 40-50 seconds. However, severe deviation issues started occurring afterward.

Here is the link to Dropbox, which contains the files (launch file, bt.map, rosbag) and recorded video https://www.dropbox.com/scl/fo/s2q0la83senu6gboo7fox/h?rlkey=uor566d2jbkhfq9iw0t7un9d1&dl=0

The lidar is also not upside-down; it only looks like that at the beginning since it scans some points in the ceiling. Moreover, other localization algorithms work very well with that initial pose, so the pose is correct.

We appreciate any help.

Best,

Miguel

fercabe commented 1 year ago

Hi again Miguel,

I found a small bug in the loss function parameterization, in the DLL Solver. Once fixed, I was able to run your bag using 2.5m as initial altitude. You can find the result in the following video: https://drive.google.com/file/d/1qeOdwUJgNZ-IBTSwzhv9SDU6_fsl3ebn/view?usp=sharing

Please, notice that DLL does not compute roll and pitch angles, if you do not provide an IMU or 6DoF odometry, it will be assumed the roll and pitch angles are zero. In this case, you can see in the video (second 50) that the LIDAR is tilted, but this tilt angle is not compensated because your bag have no IMU neither 6DoF odometry. This produces alignment errors in the solution that could be mitigated if IMU was provided.

I just push the fix to the solver, update your git and check if things works.

Fernando