AP_ICEngine: Update for AHRS NED changes

This commit is contained in:
Michael du Breuil 2017-01-30 12:09:03 -07:00 committed by Andrew Tridgell
parent d71533dc2b
commit 42b6ca9eed
1 changed files with 2 additions and 2 deletions

View File

@ -152,7 +152,7 @@ void AP_ICEngine::update(void)
Vector3f pos;
if (!should_run) {
state = ICE_OFF;
} else if (ahrs.get_relative_position_NED(pos)) {
} else if (ahrs.get_relative_position_NED_origin(pos)) {
if (height_pending) {
height_pending = false;
initial_height = -pos.z;
@ -201,7 +201,7 @@ void AP_ICEngine::update(void)
if (state == ICE_START_HEIGHT_DELAY) {
// when disarmed we can be waiting for takeoff
Vector3f pos;
if (ahrs.get_relative_position_NED(pos)) {
if (ahrs.get_relative_position_NED_origin(pos)) {
// reset initial height while disarmed
initial_height = -pos.z;
}