From 316cea65b1425471852dfd75155e3a8983923bdc Mon Sep 17 00:00:00 2001 From: Evan Huang Date: Tue, 10 Dec 2024 19:42:49 +0800 Subject: [PATCH] Update eagleye configuration file for F1EIGHTH vehicle. --- .../localization/eagleye_config.param.yaml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/autoware_launch/config/localization/eagleye_config.param.yaml b/autoware_launch/config/localization/eagleye_config.param.yaml index 05f9fc586c..d8953cd135 100644 --- a/autoware_launch/config/localization/eagleye_config.param.yaml +++ b/autoware_launch/config/localization/eagleye_config.param.yaml @@ -1,7 +1,7 @@ /**: #GNSS cycle 5Hz, IMU cycle 50Hz. ros__parameters: # Estimate mode - use_gnss_mode: rtklib + use_gnss_mode: NMEA use_can_less_mode: false # Topic @@ -10,18 +10,18 @@ twist_topic: /sensing/vehicle_velocity_converter/twist_with_covariance imu_topic: /sensing/imu/imu_data 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 + velocity_source_type: 3 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3 + velocity_source_topic: /sensing/vehicle_velocity_converter/twist_with_covariance 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 + llh_source_topic: /sensing/gnss/garmin/fix sub_gnss: llh_source_type: 2 # nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2 - llh_source_topic: /sensing/sub_gnss/ublox/nav_sat_fix + llh_source_topic: /sensing/gnss/garmin/fix # TF tf_gnss_frame: parent: "base_link" - child: "imu_link" + child: "gnss_link" # Origin of GNSS coordinates (ECEF to ENU) ecef_base_pos: @@ -35,11 +35,11 @@ # Navigation Parameters # Basic Navigation Functions common: - imu_rate: 50 - gnss_rate: 5 + imu_rate: 5 + gnss_rate: 1 stop_judgment_threshold: 0.01 slow_judgment_threshold: 0.278 - moving_judgment_threshold: 2.78 + moving_judgment_threshold: 0.556 velocity_scale_factor: estimated_minimum_interval: 20