AP_Vehicle: move control_mode_reason up to AP_Vehicle

This commit is contained in:
Peter Barker 2021-02-03 10:48:14 +11:00 committed by Andrew Tridgell
parent cdaff74948
commit f15a1fbd62

View File

@ -76,9 +76,14 @@ public:
// HAL::Callbacks implementation. // HAL::Callbacks implementation.
void loop() override final; void loop() override final;
// set_mode *must* set control_mode_reason
bool virtual set_mode(const uint8_t new_mode, const ModeReason reason) = 0; bool virtual set_mode(const uint8_t new_mode, const ModeReason reason) = 0;
uint8_t virtual get_mode() const = 0; uint8_t virtual get_mode() const = 0;
ModeReason get_control_mode_reason() const {
return control_mode_reason;
}
/* /*
common parameters for fixed wing aircraft common parameters for fixed wing aircraft
*/ */
@ -321,6 +326,8 @@ protected:
void publish_osd_info(); void publish_osd_info();
#endif #endif
ModeReason control_mode_reason = ModeReason::UNKNOWN;
private: private:
// delay() callback that processing MAVLink packets // delay() callback that processing MAVLink packets