From 0decd870dcd386dc7fc8aab0d994ecd62dcc50c9 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Tue, 25 Dec 2012 12:39:25 +0900 Subject: [PATCH] ArduCopter: inertial nav - only initialise horizontal position when home is initialised --- ArduCopter/commands.pde | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index d559939b3e..d364eb9ebd 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -190,8 +190,6 @@ static void init_home() #if INERTIAL_NAV_XY == ENABLED // set inertial nav's home position inertial_nav.set_current_position(g_gps->longitude, g_gps->latitude); - inertial_nav.set_altitude(home.alt); - inertial_nav.set_velocity_z(0); #endif if (g.log_bitmask & MASK_LOG_CMD)