mission_feasibility_checker: takeoff: fix logic to return as valid

This commit is contained in:
TSC21 2019-02-21 13:00:37 +00:00 committed by Julian Oes
parent 676e1eb224
commit f6ab40d2dd

View File

@ -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