diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 6fb32756a0..d028fb3ab2 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -8,7 +8,6 @@ static void init_home() // copter uses 0 home altitude Location loc = gps.location(); - loc.alt = 0; ahrs.set_home(loc); diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 71d0c0847b..3a2cbb0736 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -801,7 +801,6 @@ static void do_set_home(const AP_Mission::Mission_Command& cmd) init_home(); } else { Location loc = cmd.content.location; - loc.alt = 0; ahrs.set_home(loc); set_home_is_set(true); }