We released a new open source 3D mapping framework GLIM.
We also developed a map-based localization system GLIL as closed source.
hdl_localization is a ROS package for real-time 3D localization using a 3D LIDAR, such as velodyne HDL32e and VLP16. This package performs Unscented Kalman Filter-based pose estimation. It first estimates the sensor pose from IMU data implemented on the LIDAR, and then performs multi-threaded NDT scan matching between a globalmap point cloud and input point clouds to correct the estimated pose. IMU-based pose prediction is optional. If you disable it, the system uses the constant velocity model without IMU information.
hdl_localization requires the following libraries:
- PCL
- OpenMP
The following ros packages are required:
- pcl_ros
- ndt_omp
- fast_gicp
- hdl_global_localization
cd /your/ros2_ws/src
git clone https://github.com/koide3/ndt_omp
git clone https://github.com/SMRT-AIST/fast_gicp --recursive
git clone https://github.com/koide3/hdl_localization -b humble
git clone https://github.com/koide3/hdl_global_localization -b humble --recursive
cd /your/ros2_ws
colcon build --cmake-args "-DCMAKE_BUILD_TYPE=Release"
# if you want to enable CUDA-accelerated NDT
# colcon build --cmake-args "-DCMAKE_BUILD_TYPE=Release -DBUILD_VGICP_CUDA=ON"Using docker, you can conveniently satisfy the requirement environment.
Please refer to the repository below and use the docker easily.
All configurable parameters are listed in param/hdl_localization.yaml and launch/hdl_localization.launch.py as ros parameters. The estimated pose can be reset using using "2D Pose Estimate" on rviz
- /odom (nav_msgs/msg/Odometry)
- Estimated sensor pose in the map frame
- /aligned_points
- Input point cloud aligned with the map
- /status (hdl_localization/msg/ScanMatchingStatus)
- Scan matching result information (e.g., convergence, matching error, and inlier fraction)
- /relocalize (std_srvs/srv/Empty)
- Reset the sensor pose with the global localization result
- For details of the global localization method, see hdl_global_localization
Example bag file (recorded in an outdoor environment): hdl_400.bag.tar.gz (933MB)
ros2 launch hdl_localization hdl_localization.launch.py
ros2 param set use_sim_time truecolcon_cd hdl_localization
cd rviz
rviz2 -d hdl_localization.rviz# need rosbag_v2 plugin
ros2 bag play -s rosbag_v2 --clock hdl_400.bag# perform global localization
ros2 service call /relocalize std_srvs/srv/EmptyIf it doesn't work well or the CPU usage is too high, change ndt_neighbor_search_method in hdl_localization.launch to "DIRECT1". It makes the scan matching significantly fast, but a bit unstable.
Kenji Koide, Jun Miura, and Emanuele Menegatti, A Portable 3D LIDAR-based System for Long-term and Wide-area People Behavior Measurement, Advanced Robotic Systems, 2019 [link].
Kenji Koide, [email protected]
Active Intelligent Systems Laboratory, Toyohashi University of Technology, Japan [URL] Human-Centered Mobility Research Center, National Institute of Advanced Industrial Science and Technology, Japan [URL]



