mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
Copter: implement has_ekf_failsafed for use by lua
This commit is contained in:
parent
21ee06d362
commit
5ad6a0d2ef
@ -444,6 +444,12 @@ void Copter::nav_script_time_done(uint16_t id)
|
|||||||
return mode_auto.nav_script_time_done(id);
|
return mode_auto.nav_script_time_done(id);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// returns true if the EKF failsafe has triggered. Only used by Lua scripts
|
||||||
|
bool Copter::has_ekf_failsafed() const
|
||||||
|
{
|
||||||
|
return failsafe.ekf;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
|
|
||||||
|
|
||||||
|
@ -655,6 +655,9 @@ private:
|
|||||||
bool nav_scripting_enable(uint8_t mode) override;
|
bool nav_scripting_enable(uint8_t mode) override;
|
||||||
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
|
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
|
||||||
void nav_script_time_done(uint16_t id) override;
|
void nav_script_time_done(uint16_t id) override;
|
||||||
|
// lua scripts use this to retrieve EKF failsafe state
|
||||||
|
// returns true if the EKF failsafe has triggered
|
||||||
|
bool has_ekf_failsafed() const override;
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
void rc_loop();
|
void rc_loop();
|
||||||
void throttle_loop();
|
void throttle_loop();
|
||||||
|
Loading…
Reference in New Issue
Block a user