Eagleye is an open-source software for vehicle localization utilizing GNSS and IMU[1]. Eagleye provides highly accurate and stable vehicle position and orientation by using GNSS Doppler[2][3][4][5][6]. The flowchart of the algorithm is shown in the figure below. The algorithms in this software are based on the outcome of the research undertaken by Machinery Information Systems Lab (Meguro Lab) in Meijo University.
GNSS receiver
IMU
Wheel speed sensor
- Eagleye uses vehicle speed acquired from CAN bus.
Clone and Build MapIV's fork of RTKLIB. You can find more details about RTKLIB here.
sudo apt-get install gfortran
cd $HOME
git clone -b rtklib_ros_bridge_b34 https://github.com/MapIV/RTKLIB.git
cd $HOME/RTKLIB/lib/iers/gcc/
make
cd $HOME/RTKLIB/app/consapp
make
Clone and build the necessary packages for Eagleye. (rtklib_ros_bridge, nmea_ros_bridge)
cd $HOME/catkin_ws/src
git clone https://github.com/MapIV/eagleye.git -b main-ros2 --recursive
git clone https://github.com/MapIV/rtklib_ros_bridge.git -b ros2-v0.1.0
git clone https://github.com/MapIV/llh_converter.git -b ros2
git clone https://github.com/MapIV/nmea_ros_bridge.git -b ros2-v0.1.0
git clone https://github.com/MapIV/gnss_compass_ros.git -b main-ros2
sudo apt-get install -y libgeographic-dev geographiclib-tools geographiclib-doc
sudo geographiclib-get-geoids best
sudo mkdir /usr/share/GSIGEO
sudo cp llh_converter/data/gsigeo2011_ver2_1.asc /usr/share/GSIGEO/
cd ..
rosdep install --from-paths src --ignore-src -r -y
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
- nmea_ros_bridge settings.
Change adress
and port
of $HOME/ros2_ws/src/nmea_ros_bridge/config/udp_config.yaml
according to the serial device you use.
ie)
adress: 192.168.30.10
port: 62001
- GNSS receiver settings.
Access mosaic's web ui and upload the following file in Admin/Configuration.
https://www.dropbox.com/s/uckt9
The parameters of eagleye can be set in the eagleye_config.yaml. The default settings are 5Hz for GNSS and 50Hz for IMU.
The TF between sensors can be set in sensors_tf.yaml. The settings are reflected by describing the positional relationship of each sensor with respect to base_link. If you want to change the base frame, change basic_parent_flame to reflect the change.
-
Play the sample data.
ros2 bag play -s rosbag_v2 eagleye_sample.bag
-
Launch eagleye.
ros2 launch eagleye_rt eagleye_rt.launch.xml
The estimated results will be output about 100 seconds after playing the rosbag. This is because we need to wait for the data to accumulate for estimation.
- Check if wheel speed (vehicle speed) is published in
/can_twist
topic.
- Topic name: /can_twist
- Message type: geometry_msgs/TwistStamped twist.liner.x or geometry_msgs/TwistWithCovarianceStamped twist.twist.liner.x
-
Check if the IMU data is published in
/imu/data_raw
topic. -
Start RTKLIB.
cd $HOME/RTKLIB bash rtklib_ros_bridge.sh
-
Check if RTKLIB is working by execute the following command in the terminal. If the RTKLIB is working correctly, positioning information is appeared continuously in the terminal.
status 0.1
-
Start rtklib_ros_bridge.
ros2 run rtklib_bridge rtklib_bridge --ros-args --params-file $HOME/ros2_ws/src/rtklib_ros_bridge/rtklib_bridge/param/param.yaml
-
Start nmea_ros_bridge.
ros2 launch nmea_ros_bridge nmea_udp.launch.py
-
Start eagleye.
ros2 launch eagleye_rt eagleye_rt.launch.xml
-
/navsat/nmea_sentence (nmea_msgs/Sentence)
-
/can_twist (geometry_msgs/TwistStamped or geometry_msgs/TwistWithCovarianceStamped)
-
/rtklib_nav (rtklib_msgs/RtklibNav)
-
/imu/data_raw (sensor_msgs/Imu)
-
/eagleye/fix (sensor_msgs/NavSatFix)
-
/eagleye/twist (geometry_msgs/TwistStamped)
-
/eagleye/twist_with_covariance (geometry_msgs/TwistWithCovarianceStamped)
To visualize the eagleye output location /eagleye/fix, for example, use the following command
ros2 launch eagleye_fix2kml fix2kml.xml
To convert from eagleye/fix to eagleye/pose, use the following command
ros2 launch eagleye_fix2pose fix2pose.xml
No. | Date | Place | Sensors | Link |
---|---|---|---|---|
1 | 2020/01/27 | Moriyama, Nagoya route |
GNSS: Ublox F9P IMU: Tamagawa AU7684 LiDAR: Velodyne HDL-32E |
Download |
2 | 2020/07/15 | Moriyama, Nagoya route |
GNSS: Ublox F9P with RTK IMU: Tamagawa AU7684 LiDAR: Velodyne VLP-32C |
Download |
The 3D maps (point cloud and vector data) of the route is also available from Autoware sample data.
-
J Meguro, T Arakawa, S Mizutani, A Takanose, "Low-cost Lane-level Positioning in Urban Area Using Optimized Long Time Series GNSS and IMU Data", International Conference on Intelligent Transportation Systems(ITSC), 2018 Link
-
Takeyama Kojiro, Kojima Yoshiko, Meguro Jun-ichi, Iwase Tatsuya, Teramoto Eiji, "Trajectory Estimation Based on Tightly Coupled Integration of GPS Doppler and INS" -Improvement of Trajectory Estimation in Urban Area-, Transactions of Society of Automotive Engineers of Japan 44(1) 199-204, 2013 Link
-
Junichi Meguro, Yoshiko Kojima, Noriyoshi Suzuki, Teramoto Eiji, "Positioning Technique Based on Vehicle Trajectory Using GPS Raw Data and Low-cost IMU", International Journal of Automotive Engineering 3(2) 75-80, 2012 Link
-
K Takeyama, Y Kojima, E Teramoto, "Trajectory estimation improvement based on time-series constraint of GPS Doppler and INS in urban areas", IEEE/ION Position, Location and Navigation Symposium(PLANS), 2012 Link
-
Junichi Meguro, Yoshiko Kojima, Noriyoshi Suzuki, Eiji Teramoto, "Automotive Positioning Based on Bundle Adjustment of GPS Raw Data and Vehicle Trajectory", International Technical Meeting of the Satellite Division of the Institute of Navigation (ION), 2011 Link
-
Yoshiko Kojima, et., al., "Precise Localization using Tightly Coupled Integration based on Trajectory estimated from GPS Doppler", International Symposium on Advanced Vehicle Control(AVEC), 2010 Link
-
A. Takanose, et., al., "Eagleye: A Lane-Level Localization Using Low-Cost GNSS/IMU", Intelligent Vehicles (IV) workshop, 2021 Link
Eagleye is provided under the BSD 3-Clause License.
If you have further question, email to [email protected] .