mirror of https://github.com/ArduPilot/ardupilot
Plane: Call new TECS method in case of altitude change
This commit is contained in:
parent
5b8a702b54
commit
2f9ff3ef73
|
@ -44,7 +44,7 @@ void Plane::check_home_alt_change(void)
|
|||
next_WP_loc.alt += alt_change_cm;
|
||||
}
|
||||
// reset TECS to force the field elevation estimate to reset
|
||||
TECS_controller.reset();
|
||||
TECS_controller.offset_altitude(alt_change_cm * 0.01f);
|
||||
}
|
||||
auto_state.last_home_alt_cm = home_alt_cm;
|
||||
}
|
||||
|
|
|
@ -1527,4 +1527,5 @@ void AP_TECS::offset_altitude(const float alt_offset)
|
|||
// _hgt_dem
|
||||
// _hgt_dem_in_raw
|
||||
// _hgt_dem_in
|
||||
// Energies
|
||||
}
|
Loading…
Reference in New Issue