From a3a1601837c3964a3908e8197c7daee409d085bc Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sat, 17 Mar 2018 12:54:40 +0900 Subject: [PATCH] Copter: althold remove redundant z-axis init --- ArduCopter/mode_althold.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index f0c94a1d91..6b0086cba0 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -8,10 +8,6 @@ // althold_init - initialise althold controller bool Copter::ModeAltHold::init(bool ignore_checks) { - // initialize vertical speeds and leash lengths - pos_control->set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up); - pos_control->set_accel_z(g.pilot_accel_z); - // initialise position and desired velocity if (!pos_control->is_active_z()) { pos_control->set_alt_target_to_current_alt();