Skip to content

Using Eagleye with Autoware#

This page will show you how to set up Eagleye in order to use it with Autoware. For the details of the integration proposal, please refer to this Discussion.

What is Eagleye?#

Eagleye is an open-source GNSS/IMU-based localizer initially developed by MAP IV. Inc. It provides a cost-effective alternative to LiDAR and point cloud-based localization by using low-cost GNSS and IMU sensors to provide vehicle position, orientation, and altitude information. By integrating Eagleye into Autoware, users can choose between LiDAR and point cloud-based localization stacks or GNSS/IMU-based Eagleye localizer, depending on their specific needs and operating environment.

Architecture#

Eagleye can be utilized in the Autoware localization stack in two ways:

  1. Feed only twist into the EKF localizer.

    Eagleye twist integration

  2. Feed both twist and pose from Eagleye into the EKF localizer (twist can also be used with regular gyro_odometry).

    Eagleye pose twist integration

Note that RTK positioning is only required for localization using the Eagleye pose. RTK positioning is not required for twist.

Requirements#

GNSS/IMU/vehicle speed is required for Eagleye input.

IMU topic#

sensor_msgs/msg/Imu are supported for IMU.

Vehicle speed topic#

geometry_msgs/msg/TwistStamped and geometry_msgs/msg/TwistWithCovarianceStamped are supported for the input vehicle speed.

GNSS topic#

Eagleye requires latitude/longitude height information and velocity information generated by the GNSS receiver. Your GNSS ROS driver must publish the following messages:

  • sensor_msgs/msg/NavSatFix: This message contains latitude, longitude, and height information.
  • geometry_msgs/msg/TwistWithCovarianceStamped: This message contains gnss doppler velocity information.

Eagleye has been tested with the following example GNSS ROS drivers: ublox_gps and septentrio_gnss_driver. The settings needed for each of these drivers are as follows:

  • ublox_gps: This ROS driver publishes sensor_msgs/msg/NavSatFix and geometry_msgs/msg/TwistWithCovarianceStamped required by Eagleye with default settings. Therefore, no additional settings are required.
  • septentrio_gnss_driver: Set publish.navsatfix and publish.twist in the config file gnss.yaml to true

Eagleye Setup#

Install dependencies#

Clone the following three packages for Eagleye:

  1. Eagleye (autoware-main branch)
  2. RTKLIB ROS Bridge (ros2-v0.1.0 branch)
  3. LLH Converter (ros2 branch)

Modifying Autoware Launch files#

You need to install Eagleye-related packages and change Autoware's launcher. Four files are required in the Autoware localization launcher to run Eagleye: eagleye_rt.launch.xml, eagleye_config.yaml, gnss_converter.launch.xml, and fix2pose.launch.xml.

You must correctly specify input topics for GNSS latitude, longitude, and height information, GNSS speed information, IMU information, and vehicle speed information in the eagleye_config.yaml.

# Topic
twist:
  twist_type: 1 # TwistStamped : 0, TwistWithCovarianceStamped: 1
  twist_topic: /sensing/vehicle_velocity_converter/twist_with_covariance
imu_topic: /sensing/imu/tamagawa/imu_raw
gnss:
  velocity_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
  velocity_source_topic: /sensing/gnss/ublox/navpvt
  llh_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
  llh_source_topic: /sensing/gnss/ublox/nav_sat_fix

Also, the frequency of GNSS and IMU must be set in eagleye_config.yaml

common:
  imu_rate: 50
  gnss_rate: 5

The basic parameters that do not need to be changed except those mentioned above, i.e., topic names and sensors' frequency, are described below here. Additionally, the parameters for converting sensor_msgs/msg/NavSatFix to geometry_msgs/msg/PoseWithCovarianceStamped is listed in fix2pose.yaml.

Please refer to map4_localization_launch in the autoware.universe package and map4_localization_component.launch.xml in autoware_launch package for information on how to modify the localization launch.

Eagleye has a function for position estimation and a function for twist estimation, namely pose_estimator and twist_estimator, respectively.

localization launch twist estimator pose estimator
tier4_localization_launch gyro_odometry ndt_scan_matcher
map4_localization_launch/eagleye_twist_localization_launch eagleye_rt(gyro/odom/gnss fusion) ndt_scan_matcher
map4_localization_launch/eagleye_pose_twist_localization_launch eagleye_rt(gyro/odom/gnss fusion) eagleye_rt(gyro/odom/gnss fusion)

In Autoware, you can set the pose estimator to GNSS by setting pose_estimator_mode:=gnss in map4_localization_component.launch.xml in autoware_launch package. Note that the output position might not appear to be in the point cloud maps if you are using maps that are not properly georeferenced. In the case of a single GNSS antenna, initial position estimation (dynamic initialization) can take several seconds to complete after starting to run in an environment where GNSS positioning is available.

Alternatively, the twist estimator can be set to Eagleye and the pose estimator to NDT by specifying pose_estimator_mode:=lidar in the same launch file. Unlike Eagleye position estimation, Eagleye twist estimation first outputs uncorrected raw values when activated, and then outputs corrected twists as soon as static initialization is complete.

Executing Launch files#

Execution command#

Enable Eagleye in Autoware by switching the localization module in autoware.launch.xml and the pose_estimator_mode parameter in map4_localization_component.launch.xml in autoware.launch.xml.

When using Eagleye, comment out tier4_localization_component.launch.xml and start map4_localization_component.launch.xml in autoware.launch.xml.

  <!-- Localization -->
  <group if="$(var launch_localization)">
    <!-- <include file="$(find-pkg-share autoware_launch)/launch/components/tier4_localization_component.launch.xml"/> -->
    <include file="$(find-pkg-share autoware_launch)/launch/components/map4_localization_component.launch.xml"/>
  </group>

Notes with initialization#

Eagleye requires an initialization process for proper operation. Without initialization, the output for twist will be in the raw value, and the pose data will not be available.

The first step is static initialization, which involves allowing the Eagleye to remain stationary for approximately 5 seconds after startup to estimate the yaw-rate offset.

The next step is dynamic initialization, which involves running the Eagleye in a straight line for approximately 30 seconds. This process estimates the scale factor of wheel speed and azimuth angle. Once dynamic initialization is complete, the Eagleye will be able to provide corrected twist and pose data.