mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: AP_Arming ensures mission items present when in auto mode
Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com>
This commit is contained in:
parent
50dbf4219b
commit
96fa96936b
|
@ -446,6 +446,14 @@ bool Copter::has_ekf_failsafed() const
|
||||||
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
|
|
||||||
|
bool Copter::current_mode_requires_mission() const
|
||||||
|
{
|
||||||
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
|
return flightmode == &mode_auto;
|
||||||
|
#else
|
||||||
|
return false;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
// rc_loops - reads user input from transmitter/receiver
|
// rc_loops - reads user input from transmitter/receiver
|
||||||
// called at 100hz
|
// called at 100hz
|
||||||
|
|
|
@ -851,6 +851,7 @@ private:
|
||||||
// called when an attempt to change into a mode is unsuccessful:
|
// called when an attempt to change into a mode is unsuccessful:
|
||||||
void mode_change_failed(const Mode *mode, const char *reason);
|
void mode_change_failed(const Mode *mode, const char *reason);
|
||||||
uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
|
uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
|
||||||
|
bool current_mode_requires_mission() const override;
|
||||||
void update_flight_mode();
|
void update_flight_mode();
|
||||||
void notify_flight_mode();
|
void notify_flight_mode();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue