mirror of https://github.com/ArduPilot/ardupilot
Rover: remove handling of prearm empty-string case
it is clear by inspection that this string can never be empty when the called function returns false. AP_OAPathPlanner::pre_arm_check is not that complicated!
This commit is contained in:
parent
c5964ecd35
commit
34b775259f
|
@ -168,12 +168,7 @@ bool AP_Arming_Rover::oa_check(bool report)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// display failure
|
check_failed(report, "%s", failure_msg);
|
||||||
if (strlen(failure_msg) == 0) {
|
|
||||||
check_failed(report, "Check Object Avoidance");
|
|
||||||
} else {
|
|
||||||
check_failed(report, "%s", failure_msg);
|
|
||||||
}
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif // AP_OAPATHPLANNER_ENABLED
|
#endif // AP_OAPATHPLANNER_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue