Contact me at [email protected]
for questions or ideas.
- Oriol just released Fast-LIMO - a thread-safe and fast implementation of LIMO-Velo!
- Now with a ROS2 branch,
ros2
- thanks to bertaveira. Broader LiDARs support is needed. - bertaveira is also working on a LIMO-Velo++ with python bindings. Check out his work in progress!
Visualization of the algorithm with delta = 0.01
(100Hz)
Designed for easy modifying via modular and easy to understand code. Relying upon HKU-Mars's IKFoM and ikd-Tree open-source libraries. Based also on their FAST_LIO2.
Common working speeds are 20m/s in straights and 100deg/s in the turns.
Tested on and made for Barcelona's own "Xaloc".
Only algorithm that can deliver centimeter-level resolution on real-time. See the part of my thesis where I explain the algorithm and its results: LIMOVelo + Results.
Comparison of cones under racing speeds running all algorithms in real-time, except for LIO-SAM (-r 0.5). It failed otherwise.
Developing an algorithm for a team requires the algorithm to be easy enough to understand being passed through generations.
LIMO-Velo's pipeline. Here are seen the different modules (blue), data (orange) and libraries (dark green).
- Velodyne
- Hesai
- Ouster
- Livox (check
livox
git branch)
Sometimes a higher map quality is needed, now a new high_quality_publish
parameter has been added to yield results like this below.
Sometimes Xaloc needs more definition to see if a cluster of points is actually a cone.
Prelocalization with a previoulsy saved HD map. Still work in progress on the hdmaps
branch. Official release will be in a couple of days.
Xaloc's "fast" dataset. High velocity in the straights (~15m/s) and tight turns (~80deg/s).
Try xaloc.launch
with Xaloc's own rosbags.
- ๐ Find a
slow
(818MB) and afast
(1.71GB) run in this Dropbox folder.
See Issue #10 to see other sample datasets found in the web. Don't hesitate to ask there for more data on specific scenarios/cases.
When cloning the repository, we also need to clone the IKFoM and ikd-Tree submodules. Hence we will use the --recurse-submodules
tag.
git clone --recurse-submodules https://github.com/Huguet57/LIMO-Velo.git
We either can do catkin_make
or catkin build
to compile the code. By default it will compile it optimized already
To run LIMO-Velo, we can run the launch file roslaunch limovelo test.launch
if we want a visualization or roslaunch limovelo run.launch
if we want it without.
An additional launch file roslaunch limovelo debug.launch
is added that uses Valgrind as a analysing tool to check for leaks and offers detailed anaylsis of program crashes.
To adapt LIMO-Velo to our own hardware infrastructure, a YAML file config/params.yaml
is available and we need to change it to our own topic names and sensor specs.
Relevant parameters are:
real_time
if you want to get real time experience.mapping_offline
is on an pre-alpha stage and it does not work 100% as it should of.initialization
which you can choose how you want the initialization of the pointcloud sizes (sizes =: deltas, in seconds).
TODO - This section is intended to explain how to modify the LiDAR driver to increase its frequency by publishing parts of the pointcloud instead of waiting for all of it.
- IKFoM: Iterated Kalman Filters on Manifolds
- ikd-Tree: Incremental KD-Tree for Robotic Applications
- FAST-LIO2: Fast and Direct LIO SLAM
- Work with 9-DOF IMUs
- Saving and loading HD-Maps (needs 9-DOF done)
- Adding GPS as extra input
- Rethink
mapping_offline
(see Discussions)
- Renew Buffer private structure. Interesting answer in StackOverflow: https://stackoverflow.com/a/67236232
- Simplify the upsampling in the Compensator.
- Interpolation and smoothing of states when mapping offline
- Erase unused (potentially dangerous) points in the map
- Check if need to add point in map
- Try to add a module for removing dynamic objects such as people or vehicles
- Use UKF instead of EKF
- Add vision buffer and ability to paint the map's points
- Initialize IMU measurements