mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_NavEKF2: added set_enable() API
This commit is contained in:
parent
ba8e63d8e7
commit
fe76662faf
@ -225,6 +225,9 @@ public:
|
|||||||
// this function should not have more than one client
|
// this function should not have more than one client
|
||||||
bool getLastYawResetAngle(float &yawAng);
|
bool getLastYawResetAngle(float &yawAng);
|
||||||
|
|
||||||
|
// allow the enable flag to be set by Replay
|
||||||
|
void set_enable(bool enable) { _enable.set(enable); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
NavEKF2_core *core = nullptr;
|
NavEKF2_core *core = nullptr;
|
||||||
const AP_AHRS *_ahrs;
|
const AP_AHRS *_ahrs;
|
||||||
|
Loading…
Reference in New Issue
Block a user