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
GNSS Antenna
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 https://github.com/MapIV/RTKLIB.git cd $HOME/RTKLIB/lib/iers/gcc/ make cd $HOME/RTKLIB/app make
-
Clone and build rtklib_ros_bridge.
cd $HOME/catkin_ws/src git clone https://github.com/MapIV/rtklib_ros_bridge.git cd .. catkin_make -DCMAKE_BUILD_TYPE=Release
-
Clone and build nmea_navsat_driver.
cd $HOME/catkin_ws/src git clone https://github.com/MapIV/nmea_navsat_driver.git cd .. catkin_make -DCMAKE_BUILD_TYPE=Release
-
Installing dependent packages
In the case of Ubuntu18.04 melodic.
sudo apt-get install ros-melodic-geodesy
sudo apt-get install ros-melodic-can-msgs
In the case of Ubuntu16.04 kinetic.
sudo apt-get install ros-kinetic-geodesy
sudo apt-get install ros-kinetic-can-msgs
-
Clone and build eagleye.
cd $HOME/catkin_ws/src git clone https://github.com/MapIV/eagleye.git cd .. catkin_make -DCMAKE_BUILD_TYPE=Release
-
RTKLIB settings.
Change inpstr1-path
of $HOME/RTKLIB/app/rtkrcv/conf/rtklib_ros_bridge_sample.conf
according to the serial device you use.
ie)
inpstr1-path =/serial/by-id/usb-u-blox_AG_-_www.u-blox.com_u-blox_GNSS_receiver-if00:230400:8:n:1:off
- nmea_navsat_driver settings.
Change arg name="port"
of $HOME/catkin_ws/src/nmea_navsat_driver/launch/f9p_nmea_serial_driver.launch
according to the serial device you use.
ie)
<arg name="port" default="/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_AG0JNPDS-if00-port0" />
- GNSS receiver settings. Configure the receiver settings using u-center.
- UART1(Connect to RTKLIB) Enable UBX message (output rate 5Hz, baudrate 230400) ※ Set to output only RAWX and SFRBX
- UART2(Connect to nmea_navsat_driver) Enable NMEA message (output rate 1Hz, baudrate 115200) ※ Set to output only GGA and RMC
This file is a sample configuration file for F9P.
Open u-center.
Tools/Receiver Configuration.../Load configuration "Transfer file -> GNSS"
- IMU settings.
- Output rate 50Hz
-
Check the rotation direction of z axis of IMU being used. If you look from the top of the vehicle, if the left turn is positive, set "reverse_imu" to
true
ineagleye/launch/eagleye_localization.launch
.param name="/eagleye/reverse_imu" type="bool" value="true"
- Check if wheel speed (vehicle speed) is published in
/can_twist
topic.
- Topic name: /can_twist
- Message type: geometry_msgs/TwistStamped twist.liner.x
-
Check if the IMU data is published in
/imu_raw
topic. -
Start RTKLIB.
cd $HOME/RTKLIB bash rtklib_ros_bridge_single.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.
roslaunch rtklib_bridge rtklib_bridge.launch
-
Start nmea_navsat_driver.
rosrun nmea_navsat_driver f9p_nmea_serial_driver.launch
-
Start eagleye.
roslaunch eagleye_rt eagleye_rt.launch
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.
-
Play the sample data.
rosparam set use_sim_time true rosbag play --clock eagleye_sample.bag
-
Launch eagleye.
roslaunch eagleye_rt eagleye_rt.launch
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.
-
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
Eagleye is provided under the BSD 3-Clause License.
If you have further question, email to [email protected].