Copter: acro sets alt target to zero for reporting

This commit is contained in:
Randy Mackay 2015-11-18 21:47:07 +09:00
parent a5e4f64b20
commit 674bedd867

View File

@ -13,6 +13,9 @@ bool Copter::acro_init(bool ignore_checks)
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (g.rc_3.control_in > get_non_takeoff_throttle())) {
return false;
}
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
return true;
}