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.

Dependencies#

The below packages are automatically installed during the setup of Autoware as they are listed in autoware.repos.

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

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: RTK positioning is required when using Eagleye as the pose estimator. On the other hand, it is not mandatory when using it as the twist estimator.

Requirements#

Eagleye requires GNSS, IMU and vehicle speed as inputs.

IMU topic#

sensor_msgs/msg/Imu is supported for Eagleye IMU input.

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 and doppler velocity 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:

GNSS ROS drivers modification
ublox_gps No additional settings are required. It publishes sensor_msgs/msg/NavSatFix and geometry_msgs/msg/TwistWithCovarianceStamped required by Eagleye with default settings.
septentrio_gnss_driver Set publish.navsatfix and publish.twist in the config file gnss.yaml to true

Parameter Modifications for Integration into Your Vehicle#

topic name & topic type#

The users must correctly specify input topics for GNSS latitude, longitude, and height , GNSS doppler speed , IMU , and vehicle speed 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

sensor frequency#

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

common:
  imu_rate: 50
  gnss_rate: 5

Conversion from fix to pose#

The parameters for converting sensor_msgs/msg/NavSatFix to geometry_msgs/msg/PoseWithCovarianceStamped is listed in geo_pose_converter.launch.xml. If you use a different geoid or projection type, change these parameters.

Other parameters#

The other parameters are described here. Basically, these do not need to be changed .

Notes on 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.

1. Static Initialization#

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.

2. Dynamic initialization#

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.

How to check the progress of initialization#

  • TODO

Note on georeferenced maps#

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.