Browse Source

Copter: loiter loses redundant z-axis init

master
Randy Mackay 7 years ago
parent
commit
cbd2756467
  1. 4
      ArduCopter/mode_loiter.cpp

4
ArduCopter/mode_loiter.cpp

@ -12,10 +12,6 @@ bool Copter::ModeLoiter::init(bool ignore_checks) @@ -12,10 +12,6 @@ bool Copter::ModeLoiter::init(bool ignore_checks)
// set target to current position
wp_nav->init_loiter_target();
// initialize vertical speed and acceleration
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();

Loading…
Cancel
Save