From 7a82898e92e2ba2cf878ab88c3ad164d8b7337a6 Mon Sep 17 00:00:00 2001 From: Hwurzburg Date: Wed, 25 Nov 2020 17:54:27 -0600 Subject: [PATCH] AP_GPS: expand gps rate description --- libraries/AP_GPS/AP_GPS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 58108bfdd6..c159b59761 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -186,7 +186,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: RATE_MS // @DisplayName: GPS update rate in milliseconds - // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed + // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance. // @Units: ms // @Values: 100:10Hz,125:8Hz,200:5Hz // @Range: 50 200 @@ -196,7 +196,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { #if GPS_MAX_RECEIVERS > 1 // @Param: RATE_MS2 // @DisplayName: GPS 2 update rate in milliseconds - // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed + // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance. // @Units: ms // @Values: 100:10Hz,125:8Hz,200:5Hz // @Range: 50 200