mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
mission_feasibility_checker: takeoff: fix logic to return as valid
This commit is contained in:
@@ -181,10 +181,10 @@ MissionFeasibilityChecker::checkRotarywing(const mission_s &mission, float home_
|
||||
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: takeoff waypoint required!");
|
||||
return false;
|
||||
|
||||
} else {
|
||||
// all checks have passed
|
||||
return true;
|
||||
}
|
||||
|
||||
// all checks have passed
|
||||
return true;
|
||||
}
|
||||
|
||||
bool
|
||||
@@ -461,10 +461,10 @@ MissionFeasibilityChecker::checkFixedWingTakeoff(const mission_s &mission, float
|
||||
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: takeoff waypoint required!");
|
||||
return false;
|
||||
|
||||
} else {
|
||||
// all checks have passed
|
||||
return true;
|
||||
}
|
||||
|
||||
// all checks have passed
|
||||
return true;
|
||||
}
|
||||
|
||||
bool
|
||||
|
||||
Reference in New Issue
Block a user