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
This commit is contained in:
Andrew Tridgell 2012-11-27 15:41:52 +11:00
parent 4463150122
commit 48b37cac5a
1 changed files with 2 additions and 2 deletions

View File

@ -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),