If you use River in a scientific publication, please cite the following paper 😄:
[IEEE RA-L 2024] River: A Tightly-coupled Radar-inertial Velocity Estimator Based on Continuous-time Optimization
@ARTICLE{10529532,
author={Chen, Shuolong and Li, Xingxing and Li, Shengyu and Zhou, Yuxuan and Wang, Shiwen},
journal={IEEE Robotics and Automation Letters},
title={River: A Tightly-coupled Radar-inertial Velocity Estimator Based on Continuous-time Optimization},
year={2024},
volume={},
number={},
pages={1-8},
keywords={Estimation;Radar;Splines (mathematics);Radar measurements;Optimization;Velocity measurement;Sensors;Ego-velocity estimation;millimeter-wavelength radar;inertial measurement unit;continuous-time optimization},
doi={10.1109/LRA.2024.3400154}}
Considering the lack of an open-source radar-inertial spatiotemporal calibrator currently, we also developed a targetless spatiotemporal calibrator for multiple radars and IMUs, termed as RIs-Calib, which
- supports one-shot multi-radar multiIMU spatial and temporal determination;
- not require any additional artificial infrastructure or prior knowledge;
- capable of accurate and consistent calibration;
The GitHub repository of RIs-Calib now is available at https://github.com/Unsigned-Long/RIs-Calib.git, which contains all source code and mathematics documentation in implementations. Demo video of RIs-Calib is also available.
Continuous and reliable ego-velocity information is significant for high-performance motion control and planning in a variety of robotic tasks, such as autonomous navigation and exploration. While linear velocities as first-order kinematics can be simultaneously estimated with other states or explicitly obtained by differentiation from positions in ego-motion estimators such as odometers, the high coupling leads to instability and even failures when estimators degenerate. To this end, we present River
: an accurate and continuous linear velocity estimator that efficiently fuses high-frequency inertial and radar target measurements based on continuous-time optimization. Specifically, a dynamic initialization procedure is first performed to rigorously recover the initials of states, followed by batch estimations, where the velocity and rotation B-splines would be optimized incrementally to provide continuous body-frame velocity estimates. Results from both simulated and real-world experiments demonstrate that River
is capable of high accuracy, repeatability, and consistency for ego-velocity estimation. We open-source our implementations here to benefit the research community.
Our accompanying videos are now available on YouTube (click below images to open) and Bilibili.
-
install
ROS1
(Ubuntu 20.04 is suggested, Ubuntu 18.04 (ros melodic) is also available):sudo apt install ros-noetic-desktop-full echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc source ~/.bashrc
Requirements: ROS1 & C++17 Support
-
install
Ceres
:see the
GitHub
Profile of Ceres library, clone it, compile it, and install it. Make sure that the version ofCeres
contains theManifold
module. (Ceres
version equal to 2.2.0 or higher than that) -
install
Sophus
:see the
GitHub
Profile of Sophus library, clone it, compile it, and install it. Set optionSOPHUS_USE_BASIC_LOGGING
ON
when compile (cmake
) the Sophus library, this would avoid to involvefmt
logger dependency (as the followingspdlog
would use internalfmt
too, which may lead to conflict). -
install
magic-enum
:see the
GitHub
Profile of magic-enum library, clone it, compile it, and install it. -
install
Pangolin
:see the
GitHub
Profile of Pangolin library, clone it, compile it, and install it. -
install
spdlog
:see the
GitHub
Profile of spdlog library, clone it, compile it, and install it. Though this library can be installed bysudo apt-get install libspdlog-dev
, the version is too old to supportriver
, thus installing from the source is recommended. -
install
cereal
,yaml-cpp
:sudo apt-get install libcereal-dev sudo apt-get install libyaml-cpp-dev
-
create a ros workspace if needed and clone
River
tosrc
directory asriver
:mkdir -p ~/River/src cd ~/River/src git clone --recursive https://github.com/Unsigned-Long/River.git river
change directory to '
river
', and run 'build_thirdparty.sh
'.cd river chmod +x build_thirdparty.sh ./build_thirdparty.sh
this would build '
tiny-viewer
' and 'ctraj
' libraries. -
Prepare for thirdparty ros packages:
clone ros packages '
ainstein_radar
', 'ti_mmwave_rospkg
', 'serial
', 'sbg_ros_driver
' to 'river/..
' (directory at the same level asriver
):cd .. git clone https://github.com/AinsteinAI/ainstein_radar.git git clone https://github.com/Unsigned-Long/ti_mmwave_rospkg.git git clone https://github.com/wjwwood/serial.git git clone https://github.com/SBG-Systems/sbg_ros_driver.git
then change directory to the ros workspace to build these packages:
cd .. catkin_make -DCATKIN_WHITELIST_PACKAGES="ainstein_radar;ti_mmwave_rospkg;serial;sbg_driver"
Note that these packages will depend on many other ros packages, you need to install them patiently.
-
compile
River
:catkin_make -DCATKIN_WHITELIST_PACKAGES=""
Attention: to create a virtual reality (VR) perspective of the IMU (left window view in runtime), you have to change the model file path in configure field (Preference::ObjFileForDisplay
) to {root path}/river/model/river.obj
. For a better VR perspective, you can design your own simulation scenario using Blender
and export it as an obj
file, then pass it to the configure file.
simulation experiments (datasets, launch, result visualization)
real-world experiments (datasets, launch, result visualization)
Find a configure file in river/dataset
, then change the fields in the configure files to be compatible with your dataset (there are detailed comments for each field). You only need to change a few fields related to io (input and output), perhaps some additional fields related to optimization.
Then give the path of your configuration file to the launch file of river
in folder river/launch
(handheld, xrio, or simu-test folder), Then, we launch 'river
':
roslaunch river {the-launch-filename}.launch
The corresponding results would be output to the directory you set in the configure file when solving finished (or interrupted).