From 48b37cac5ad0c4b4d7b7c6d6599fb693ea5ec1cb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Nov 2012 15:41:52 +1100 Subject: [PATCH] AHRS: improved docs for AHRS_GPS_USE some people are setting this to zero to prevent jitter, which results in their plane flying off into the distance and never coming back --- libraries/AP_AHRS/AP_AHRS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 0e9f1cbdf8..c0a807f19c 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -22,8 +22,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0), // @Param: GPS_USE - // @DisplayName: AHRS use GPS - // @Description: This controls how how much to use the GPS to correct the attitude. This is for testing the dead-reckoning code + // @DisplayName: AHRS use GPS for navigation + // @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. // @User: Advanced AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),