mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: AP_Arming ensures mission items present when in auto mode
Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com>
This commit is contained in:
parent
96fa96936b
commit
43c6bb3864
|
@ -95,11 +95,6 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
||||||
ret &= quadplane_checks(display_failure);
|
ret &= quadplane_checks(display_failure);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (plane.control_mode == &plane.mode_auto && plane.mission.num_commands() <= 1) {
|
|
||||||
check_failed(display_failure, "No mission loaded");
|
|
||||||
ret = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// check adsb avoidance failsafe
|
// check adsb avoidance failsafe
|
||||||
if (plane.failsafe.adsb) {
|
if (plane.failsafe.adsb) {
|
||||||
check_failed(display_failure, "ADSB threat detected");
|
check_failed(display_failure, "ADSB threat detected");
|
||||||
|
|
|
@ -974,6 +974,10 @@ private:
|
||||||
bool mode_allows_autotuning(void);
|
bool mode_allows_autotuning(void);
|
||||||
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
|
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
|
||||||
Mode *mode_from_mode_num(const enum Mode::Number num);
|
Mode *mode_from_mode_num(const enum Mode::Number num);
|
||||||
|
bool current_mode_requires_mission() const override {
|
||||||
|
return control_mode == &mode_auto;
|
||||||
|
}
|
||||||
|
|
||||||
bool autotuning;
|
bool autotuning;
|
||||||
|
|
||||||
// events.cpp
|
// events.cpp
|
||||||
|
|
Loading…
Reference in New Issue