HKUST-Aerial-Robotics / FIESTA

Fast Incremental Euclidean Distance Fields for Online Motion Planning of Aerial Robots
MIT License
632 stars 129 forks source link

Fundamental differences between local mapping approaches in TRR / Fastplanner / FIESTA #3

Closed ChengeYang closed 5 years ago

ChengeYang commented 5 years ago

Hi,

I have looked through your repos in TRR, FastPlanner and FIESTA with the following questions:

  1. What is the fundamental differences betweet local planners approaches in these three repos?

  2. In the TRR paper, you say that the local mapping is based on FIESTA, but the code says otherwise. Why?

  3. Why does TRR and FIESTA use raycasting, while Fast Planner does not?

  4. What kind of speedup does raycasting provide in real scenarios?

Thanks!

USTfgaoaa commented 5 years ago

@ChengeYang Hi Chenge, I will answer your questions:

  1. No fundamental differences in all local planners listed here. But there may be some customized changes for each application. For example, in FastPlanner, while local planning, we select a local target and then search a kino path and then optimize it. In TRR, since we already have a very high-quality global plan, when we need a replan, we truncate a piece of the global trajectory in a small window and directly optimize it without a path search but included extra boundary states constraints.
  2. The local mapping used in TRR is a customized version based on FIESTA. All map fusion part (updating, raycasting, other tricks) is directly integrated from FIESTA. But for the ESDF maintenance, when we developing this project, we found that it's totally OK and can run faster if we only keep a small local map and clear all history, i.e. throw the global map. This holds just for our TRR application (as you know, FIEST's point is to keep a global map and incrementally update it). So we change the ESDF updating mechanism in TRR's local map to a 'batch updating' way, as shown in the code. I'm sorry that I forgot to modify the detailed worlds in the manuscript when I submit the paper, and this causes some misleadings to you. I will fix this in a later released manuscript.
  3. In TRR's planning applications, we use stereo cameras that have a lot of noise in its depth measurements. Without raycasting, the map quickly messes-up. But in FastPlanner's demo, we use a Velodyne LiDAR that can output high-quality point clouds. What's more, when we use LiDAR to do SLAM, we have already had several mechanisms to clear the noise and keep a clean point cloud map. So it's not necessary to have raycasting. So, you can see that whether to use raycasting or not totally depends on your concrete applications. For FIESTA, since it's a complete mapping framework, it must have raycasting for others to use, but whether to use it or not depends on users.
  4. Actually, for a real application with many depth measurements for a high-resolution stereo set-up, such as 1080 x 720 pixels, the tricks (speedup) dominates the efficiency in raycasting. For detailed tricks, I recommend you to read the code of the local mapping in the TRR project, since we have most engineering experience in that project.

All in all, an efficient mapping framework is the point (core contribution) of FIESTA, while not of FastPlanner and TRR. So, there may have some inconsistencies between the map modules used in these projects. If you want to learn a complete, global, incremental mapping system, read FIESTA. If you are interested in applying a mapping method for planning in real scenarios, FastPlanner and TRR would be good examples. By the way, in our group, for applications where we need to build a dense map for exploration/infrastructure inspection, we use this FIESTA repo.

USTfgaoaa commented 5 years ago

@ChengeYang

By the way, if you find these repos useful, you may consider giving us 'stars'. ^_^

mhkabir commented 5 years ago

@USTfgaoaa this was a very insightful post! I've been lurking and reading the code, and this seems like it would be very beneficial for future readers and could go into a Wiki or similar. :)

I have an additional question along these lines - what are the fundamental performance and accuracy differences in terms of the map fusion and ESDF update in all your approaches vs Ewok? (https://github.com/VladyslavUsenko/ewok/tree/master/ewok_ring_buffer)

USTfgaoaa commented 5 years ago

@mhkabir Hi Kabir. Ewok is all about local ESDF mapping. This means, only a local map sliding with the drone is kept and others are all thrown away. Since only a small portion of the map is kept, the computational complexity is much less, Ewok updates ESDF in a batch style by this method: Pedro F Felzenszwalb and Daniel P Huttenlocher, Distance transforms of sampled functions.

But FIESTA is more like Voxblox from ETH (https://github.com/ethz-asl/voxblox), since they both want to maintain a global map and update their ESDF values incrementally. So, Ewok and FIESTA are fundamentally different from the most underlying motivations and we can't compare the speed between Ewok and FIESTA.

Accuracy and efficiency of ESDF:

Ewok has 100% accurate solution because the method they use calculate the true ESDF at each grid's coordinate by finding the lower envelope of some parabola curves. Instead, Voxblox and FIESTA calculate ESDF based on graph search and distance propagation. And we prove in FIESTA paper that, with methods based on graph search, the accuracy can never be 100%. However, we are more accurate than Voxblox since we use the true Euclidean distance instead of quasi Euclidean distance.

For the speed. We'are much faster than Voxblox because of the elaborated data structure used in the map. Details can be checked in FIESTA's paper.

Accuracy and efficiency of map fusion:

We incorporate more engineering tricks than Ewok. So I believe FIESTA would generate better (cleaner, more accurate, faster) fusion results than Ewok although we didn't compare. You may have a try on this claim. And FIESTA's performance of fusion is comparable with Voxblox. We have compared the fusion performances and found FIEST and Voxblox are almost the same.

Overall comparison of 'fundamental differences' stuff about all these ESDF methods:

If you just want a drone to conduct local collision avoidance, Ewok is totally OK. But that's not the problem FIESTA wants to solve. There are a lot of applications where people want a global ESDF available during the flight and a dense global map left after the drone's navigation. That map may be used for later repeatable global planning, or just for inspection. I believe that's also the basic motivation of Voxblox. Also, you may imagine some problems Ewok may encounter. When the drone flies around a place, some obstacles are sometimes observed or not observed. In the local map without any historical memory, some ESDF values affected by these obstacles would change suddenly on your map. And these suddenly changed ESDF values affect the consistency of your local planning significantly.

mhkabir commented 5 years ago

@USTfgaoaa Thanks for the detailed response!

mhkabir commented 5 years ago

We incorporate more engineering tricks than Ewok

@USTfgaoaa Would you be able to elaborate on some of the general engineering and tricks you've used in TRR/Fiesta to be able to operate under real world conditions (e.g noisy depth camera data)? I'm quite interested in learning how these translate to real world performance compared to that in a controlled laboratory environment.

USTfgaoaa commented 5 years ago

@mhkabir All tricks and engineering considerations we adopted are common tricks used in many mapping works. We will post them in ReadMe of FIESTA by today.

mhkabir commented 5 years ago

@USTfgaoaa thanks!

USTfgaoaa commented 5 years ago

@hlx1996 Please finish it soon.

hlx1996 commented 5 years ago

@mhkabir Already done. Please refer here

tejalbarnwal commented 2 months ago

@USTfgaoaa , Thank you for such informative comments. I had just one more query about various ESDF mapping methods. I understand that FIESTA is an incremental mapping system and maintains a global ESDF map reference.

Let's say there is a robot equipped with the exploration planner module and an independent SLAM module running for localization and relocalization(for, e.g. LI0 SAM). Let us say that the robot, during exploration, starts with place A, goes to place B, goes to places C, and D , E,... and eventually returns to place C(for, e.g.) while completing the exploration. At this point, the SLAM algorithm will perform a loop closure, leading to a sudden slight pose jump and further corrections to the drone's previous poses. So, the map made by the SLAM algorithm would also be updated. However, the ESDF map used for the exploration planning wouldn't be updated thoroughly, which might lead to some inconsistencies in the system; due to misalignment, some part obstacle-free regions might actually be treated as obstacle-rich regions. How should the ESDF map get adjusted after the SLAM algorithm performs loop closures in these cases? Should the planner-mapping algorithm rebuild an ESDF map from the affected part of the SLAM map again?