AP_NavEKF2: Require reboot after changing ALT_SOURCE parameter

Toggling between alt sources in flight using the parameter can have unpredictable effects due to the various height offsets and the possibility that the data source may be unavailable.
This commit is contained in:
priseborough 2017-10-04 08:00:43 +11:00 committed by Francisco Ferreira
parent 3a78255e54
commit efdc651d1a
1 changed files with 1 additions and 0 deletions

View File

@ -204,6 +204,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Description: This parameter controls the primary height sensor used by the EKF. If the selected option cannot be used, it will default to Baro as the primary height source. Setting 0 will use the baro altitude at all times. Setting 1 uses the range finder and is only available in combination with optical flow navigation (EK2_GPS_TYPE = 3). Setting 2 uses GPS. Setting 3 uses the range beacon data. NOTE - the EK2_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground.
// @Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS, 3:Use Range Beacon
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("ALT_SOURCE", 9, NavEKF2, _altSource, 0),
// @Param: ALT_M_NSE