mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: acro sets alt target to zero for reporting
This commit is contained in:
parent
a5e4f64b20
commit
674bedd867
@ -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())) {
|
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (g.rc_3.control_in > get_non_takeoff_throttle())) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
// set target altitude to zero for reporting
|
||||||
|
pos_control.set_alt_target(0);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user