Copter: fix sanity checks for takeoff altitude

This commit is contained in:
Tatsuya Yamaguchi 2022-01-26 11:05:29 +09:00 committed by Randy Mackay
parent d71ec5bb4d
commit 3045451769
1 changed files with 3 additions and 6 deletions

View File

@ -258,12 +258,9 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
}
// sanity check target
if (alt_target < copter.current_loc.alt) {
dest.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME);
}
// Note: if taking off from below home this could cause a climb to an unexpectedly high altitude
if (alt_target < 100) {
dest.set_alt_cm(100, Location::AltFrame::ABOVE_HOME);
float alt_target_min_cm = copter.current_loc.alt + (copter.ap.land_complete ? 100 : 0);
if (alt_target < alt_target_min_cm ) {
dest.set_alt_cm(alt_target_min_cm , Location::AltFrame::ABOVE_HOME);
}
// set waypoint controller target