Plane: Parameterize the home altitude reset conditions

This commit is contained in:
Michael du Breuil 2017-08-28 15:20:13 -07:00 committed by Tom Pittenger
parent e492c733d8
commit 8630037fd7
3 changed files with 16 additions and 1 deletions

View File

@ -1176,6 +1176,15 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0), AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0),
// @Param: HOME_RESET_ALT
// @DisplayName: Home reset altitude threshold
// @Description: When the aircraft is within this altitude of the home waypoint, while disarmed it will automatically update the home position. Set to 0 to continously reset it.
// @Values: -1:Never reset,0:Always reset
// @Range: -1 127
// @Units: m
// @User: Advanced
AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -541,6 +541,10 @@ public:
// mask of channels to do manual pass-thru for // mask of channels to do manual pass-thru for
AP_Int32 manual_rc_mask; AP_Int32 manual_rc_mask;
// home reset altitude threshold
AP_Int8 home_reset_threshold;
}; };
extern const AP_Param::Info var_info[]; extern const AP_Param::Info var_info[];

View File

@ -126,7 +126,9 @@ void Plane::init_home()
*/ */
void Plane::update_home() void Plane::update_home()
{ {
if (fabsf(barometer.get_altitude()) > 2) { if ((g2.home_reset_threshold == -1) ||
((g2.home_reset_threshold > 0) &&
(fabsf(barometer.get_altitude()) > g2.home_reset_threshold))) {
// don't auto-update if we have changed barometer altitude // don't auto-update if we have changed barometer altitude
// significantly. This allows us to cope with slow baro drift // significantly. This allows us to cope with slow baro drift
// but not re-do home and the baro if we have changed height // but not re-do home and the baro if we have changed height