mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: Fix AP_GPS.h include and use the singleton
This commit is contained in:
parent
c70107cabb
commit
157a3b1e34
|
@ -2,6 +2,7 @@
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AP_Airspeed.h"
|
#include "AP_Airspeed.h"
|
||||||
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
|
||||||
void AP_Airspeed::check_sensor_failures()
|
void AP_Airspeed::check_sensor_failures()
|
||||||
{
|
{
|
||||||
|
@ -30,8 +31,9 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
|
||||||
|
|
||||||
// update state[i].failures.health_probability via LowPassFilter
|
// update state[i].failures.health_probability via LowPassFilter
|
||||||
float speed_accuracy;
|
float speed_accuracy;
|
||||||
if (AP::gps().speed_accuracy(speed_accuracy)) {
|
const AP_GPS &gps = AP::gps();
|
||||||
const float gnd_speed = AP::gps().ground_speed();
|
if (gps.speed_accuracy(speed_accuracy)) {
|
||||||
|
const float gnd_speed = gps.ground_speed();
|
||||||
|
|
||||||
if (aspeed > (gnd_speed + wind_max) || aspeed < (gnd_speed - wind_max)) {
|
if (aspeed > (gnd_speed + wind_max) || aspeed < (gnd_speed - wind_max)) {
|
||||||
// bad, decay fast
|
// bad, decay fast
|
||||||
|
|
Loading…
Reference in New Issue