mirror of https://github.com/ArduPilot/ardupilot
AP_ExternalAHRS: added support for GPS disable and fwd flight
allow backends to determine if we are in fixed wing flight and/or the GPS is disabled by the user
This commit is contained in:
parent
3a586b2215
commit
77e5446595
|
@ -163,7 +163,12 @@ public:
|
|||
float differential_pressure; // Pa
|
||||
float temperature; // degC
|
||||
} airspeed_data_message_t;
|
||||
|
||||
|
||||
// set GNSS disable for auxillary function GPS_DISABLE
|
||||
void set_gnss_disable(bool disable) {
|
||||
gnss_is_disabled = disable;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
enum class OPTIONS {
|
||||
|
@ -193,6 +198,9 @@ private:
|
|||
}
|
||||
|
||||
uint32_t last_log_ms;
|
||||
|
||||
// true when user has disabled the GNSS
|
||||
bool gnss_is_disabled;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
*/
|
||||
|
||||
#include "AP_ExternalAHRS_backend.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
|
||||
|
@ -37,5 +38,10 @@ bool AP_ExternalAHRS_backend::option_is_set(AP_ExternalAHRS::OPTIONS option) con
|
|||
return frontend.option_is_set(option);
|
||||
}
|
||||
|
||||
bool AP_ExternalAHRS_backend::in_fly_forward(void) const
|
||||
{
|
||||
return AP::ahrs().get_fly_forward();
|
||||
}
|
||||
|
||||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
||||
|
||||
|
|
|
@ -57,7 +57,19 @@ protected:
|
|||
void set_default_sensors(uint16_t sensors) {
|
||||
frontend.set_default_sensors(sensors);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
return true if the GNSS is disabled
|
||||
*/
|
||||
bool gnss_is_disabled(void) const {
|
||||
return frontend.gnss_is_disabled;
|
||||
}
|
||||
|
||||
/*
|
||||
return true when we are in fixed wing flight
|
||||
*/
|
||||
bool in_fly_forward(void) const;
|
||||
|
||||
private:
|
||||
AP_ExternalAHRS &frontend;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue