mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Rover: AP_Arming ensures mission items present when in auto mode
Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com>
This commit is contained in:
parent
43c6bb3864
commit
941bb6a45b
@ -196,9 +196,6 @@ bool AP_Arming_Rover::mode_checks(bool report)
|
|||||||
if (!rover.control_mode->allows_arming()) {
|
if (!rover.control_mode->allows_arming()) {
|
||||||
check_failed(report, "Mode not armable");
|
check_failed(report, "Mode not armable");
|
||||||
return false;
|
return false;
|
||||||
} else if (rover.control_mode == &rover.mode_auto && rover.mode_auto.mission.num_commands() <= 1) {
|
|
||||||
check_failed(report, "AUTO requires mission");
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -362,6 +362,10 @@ private:
|
|||||||
bool set_mode(Mode &new_mode, ModeReason reason);
|
bool set_mode(Mode &new_mode, ModeReason reason);
|
||||||
bool set_mode(const uint8_t new_mode, ModeReason reason) override;
|
bool set_mode(const uint8_t new_mode, ModeReason reason) override;
|
||||||
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(); }
|
||||||
|
bool current_mode_requires_mission() const override {
|
||||||
|
return control_mode == &mode_auto;
|
||||||
|
}
|
||||||
|
|
||||||
void startup_INS_ground(void);
|
void startup_INS_ground(void);
|
||||||
void notify_mode(const Mode *new_mode);
|
void notify_mode(const Mode *new_mode);
|
||||||
uint8_t check_digital_pin(uint8_t pin);
|
uint8_t check_digital_pin(uint8_t pin);
|
||||||
|
Loading…
Reference in New Issue
Block a user