Paper: Radar4VoxMap: Accurate Odometry from Blurred Radar Observations
Authors: Jiwon Seok, Soyeong Kim, Jaeyoung Jo, Jaehwan Lee, Minseo Jung, and Kichun Jo
Affiliation: Hanyang University, Konkuk University
Code: https://github.com/ailab-hanyang/Radar4VoxMap
YouTube: Radar4VoxMap demonstration videos
Compared to conventional 3D radar, 4D imaging radar provides additional height data and finer resolution measurements. Moreover, compared to LiDAR sensors, 4D imaging radar is more cost-effective and offers enhanced durability against challenging weather conditions. Despite these advantages, radar-based localization systems face several challenges, including limited resolution, leading to scattered object recognition and less precise localization. Additionally, existing methods that form submaps from filtered results can accumulate errors, leading to blurred submaps and reducing the accuracy of SLAM and odometry. To address these challenges, this paper introduces Radar4VoxMap, a novel approach designed to enhance radar-only odometry. The method includes an RCS-weighted voxel distribution map that improves registration accuracy. Furthermore, fixed-lag optimization with the graph is used to optimize both the submap and pose, effectively reducing cumulative errors.
- RCS-Weighted Voxel Distribution Map: Enhances registration accuracy by utilizing Radar Cross Section (RCS) values to weight radar points within voxels.
- Graph-based Fixed-Lag Smoothing Optimizer: Employs a fixed-lag smoothing approach using g2o to optimize a window of recent poses and the associated submap.
- Doppler-GICP (D-GICP) for Robust Registration: Incorporates Doppler velocity measurements alongside geometric information and point/voxel covariances for more robust point cloud registration.
- Constant Velocity (CV) Motion Model: Utilizes a CV model for pose prediction, suitable for typical vehicle motion patterns.
Radar4VoxMap was primarily evaluated on the View-of-Delft (VoD) dataset (Official Website). This is a publicly available automotive dataset recorded in Delft, the Netherlands, specifically designed for research in autonomous driving and multi-sensor fusion.
- Sensor Configuration: The VoD dataset was collected using a vehicle equipped with a rich sensor suite, including:
- 4D Imaging Radars: Multiple Continental ARS548 sensors, providing dense point clouds with range, azimuth, elevation, Doppler velocity, and Radar Cross Section (RCS) for each point. This is the primary input for Radar4VoxMap.
- LiDAR: A 64-layer LiDAR sensor for detailed 3D environmental perception and ground truth generation.
- Cameras: Stereo camera setups for visual data.
- Data Characteristics:
- The dataset comprises over 8,600 synchronized frames from all sensors.
- It includes extensive 3D bounding box annotations for various road users (over 123,100 total, including pedestrians, cyclists, and cars).
- Semantic map information (lanes, sidewalks, etc.) is also provided.
- Scenarios: Data was collected in complex urban traffic environments in Delft, featuring a high density of Vulnerable Road Users (VRUs), which presents significant challenges for perception and localization algorithms.
- Access: The VoD dataset is available for non-commercial research purposes. Access can be requested through a form on the VoD dataset website.
- ROS Bag for Testing:
To facilitate testing and reproduction of our results, we provide ROS bag files for selected sequences from the VoD dataset. These bags contain the necessary radar topics and ground truth information.
- Download Link for VoD ROS Bags:
Waiting for permission from the original author.
- Download Link for VoD ROS Bags:
In addition to the VoD dataset, we provide a sample custom dataset for testing and integration purposes. This dataset was collected using a different sensor setup:
- Radar: bitsensing AFI910 4D Imaging Radar
- LiDAR: Velodyne VLP-32C
- GNSS/IMU: Novatel PwrPak7
- Camera: CANLab Camera
Important Note: This custom dataset is provided solely for testing the integration and functionality of Radar4VoxMap with different sensor types. The sensor calibration and ground truth localization data for this dataset are not guaranteed to be accurate. Use it primarily to verify data flow and compatibility, not for rigorous performance evaluation.
- Download Link for Custom Dataset ROS Bags: OneDrive
- Usage: To use this dataset:
To use the bitsensing AFI910 dataset, run the following command:
roslaunch radar_4_vox_map radar_4_vox_map_afi910.launch
- Refer to
ros/radar_point_converters.hppto see how theafi910type handles point field mapping.
- Refer to
The comprehensive nature of the VoD dataset, particularly its high-quality 4D radar data and accurate ground truth, makes it an ideal platform for benchmarking radar-based odometry and SLAM systems.
- C++17 (or as required)
- Eigen3
- PCL (Point Cloud Library)
- g2o (Graph Optimization Framework)
- ROS (Robot Operating System) - for using the provided ROS bags and visualization
# Move your catkin workspace
cd ~/catkin_ws/src
# Clone the repository
git clone https://github.com/ailab-hanyang/Radar4VoxMap.git
cd ..
# Configure and build
catkin_make
source devel/setup.bash- Download the VoD ROS bag from the link provided above.
- Ensure your ROS environment is sourced:
source devel/setup.bash(if using a ROS workspace). - Launch the odometry node:
roslaunch radar_4_vox_map radar_4_vox_map.launch
To evaluate Radar4VoxMap with your own custom radar dataset, you will need to:
-
Modify Point Conversion:
- The radar point cloud messages from your custom radar might have a different format or topic name.
- You will need to adapt the point conversion logic. This typically involves modifying a custom function within the
ros/radar_point_converters(or a similarly named directory/package responsible for converting raw radar messages to theSRadarPointstructure used by the odometry algorithm). - Ensure that your custom conversion function correctly populates all necessary fields:
pose(x,y,z),local(x,y,z in sensor frame if different),vel(Doppler velocity),rcs,range,azi_angle,ele_angle,is_static(if available), andtimestamp.
-
Configure ROS Launch File:
- In your
roslaunchfile (e.g., a copy ofradar_odometry_custom.launch), you need to specify that you are using a custom radar type. - Set the
radar_type(or a similar parameter) tocustom. For example:<launch> <!-- Other parameters --> <param name="radar_type" type="string" value="custom" /> <param name="custom_radar_topic" type="string" value="/your/custom_radar_topic" /> <!-- ... other nodes and parameters ... --> <node pkg="radar_4_vox_map" type="radar_odometry_node" name="radar_odometry_node" output="screen"> <!-- Pass parameters to the node --> </node> </launch>
- You will also need to remap the input radar topic in the launch file to match your custom radar's topic name.
- In your
-
Data Playback:
- Play your custom radar data, typically from a ROS bag file:
rosbag play your_custom_radar_data.bag
- Play your custom radar data, typically from a ROS bag file:
By following these steps, you can adapt Radar4VoxMap to process and evaluate data from different radar sensors.
If you use Radar4VoxMap in your research, please cite our paper:
For Radar4VoxMap: (Please update the BibTeX entry with the correct publication details once available.)
This project is licensed under the Apache 2.0 License - see the LICENSE file for details. The View-of-Delft dataset has its own licensing terms, which must be adhered to.
This work was supported in part by a grant from the National Research Foundation of Korea (NRF) grant funded by the Korea government (MSIT). (No.RS-2023-00209252) and the National Research Foundation of Korea (NRF) funded by the Korean government Korean Government Ministry of Science and ICT (MSIT) under grant No. RS-2024-00421129.
We would also like to express our gratitude to the developers and maintainers of the following open-source projects, which provided valuable insights and inspiration for Radar4VoxMap:
- Doppler-ICP: aevainc/Doppler-ICP - For their pioneering work on incorporating Doppler information into ICP.
- KISS-ICP: PRBonn/kiss-icp - For their robust and efficient LiDAR odometry pipeline.
- g2o (General Graph Optimization): RainerKuemmerle/g2o - For the versatile graph optimization framework.
- VoxelMap: hku-mars/VoxelMap - For their efficient adaptive voxel mapping method.
- glim: koide3/glim - For their versatile point cloud-based 3D localization and mapping framework.
Radar4VoxMap also provides a lighter 2-D version (planar assumption) that is useful for applications where roll/pitch variations are negligible. You can switch between 3-D (default) and 2-D simply by changing the radar_4_vox_map_type launch argument.
# Run the 2-D variant
roslaunch radar_4_vox_map radar_4_vox_map.launch radar_4_vox_map_type:=2dOr, change to 2d in ros/launch/radar_4_vox_map_ros.launch.
<arg name="radar_4_vox_map_type" default="2d" />