Plane: bugfix: never reset auto_state.sink_rate

This commit is contained in:
Tom Pittenger 2020-05-23 17:24:23 -07:00 committed by Tom Pittenger
parent 63b5711a4d
commit 0a5021fdcf
1 changed files with 0 additions and 3 deletions

View File

@ -15,9 +15,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
// special handling for nav vs non-nav commands // special handling for nav vs non-nav commands
if (AP_Mission::is_nav_cmd(cmd)) { if (AP_Mission::is_nav_cmd(cmd)) {
// set land_complete to false to stop us zeroing the throttle
auto_state.sink_rate = 0;
// set takeoff_complete to true so we don't add extra elevator // set takeoff_complete to true so we don't add extra elevator
// except in a takeoff // except in a takeoff
auto_state.takeoff_complete = true; auto_state.takeoff_complete = true;