Copter: guided mode velocity control can trigger takeoff

This commit is contained in:
Randy Mackay 2020-10-14 14:26:35 +09:00
parent eb3aca7acf
commit ab42bbc43f
1 changed files with 11 additions and 0 deletions

View File

@ -466,6 +466,17 @@ void ModeGuided::vel_control_run()
}
}
// landed with positive desired climb rate, initiate takeoff
if (motors->armed() && copter.ap.auto_armed && copter.ap.land_complete && is_positive(guided_vel_target_cms.z)) {
zero_throttle_and_relax_ac();
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
set_land_complete(false);
set_throttle_takeoff();
}
return;
}
// if not armed set throttle to zero and exit immediately
if (is_disarmed_or_landed()) {
make_safe_spool_down();