Browse Source

AP_DAL: prevent logical loop between AHRS and EKF

this prevents the EKF using its own rejecting_airspeed flag
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
aab0c31385
  1. 2
      libraries/AP_DAL/AP_DAL.cpp

2
libraries/AP_DAL/AP_DAL.cpp

@ -63,7 +63,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
_RFRN.fly_forward = ahrs.get_fly_forward(); _RFRN.fly_forward = ahrs.get_fly_forward();
_RFRN.takeoff_expected = ahrs.get_takeoff_expected(); _RFRN.takeoff_expected = ahrs.get_takeoff_expected();
_RFRN.touchdown_expected = ahrs.get_touchdown_expected(); _RFRN.touchdown_expected = ahrs.get_touchdown_expected();
_RFRN.ahrs_airspeed_sensor_enabled = AP::ahrs().airspeed_sensor_enabled(); _RFRN.ahrs_airspeed_sensor_enabled = ahrs.airspeed_sensor_enabled(ahrs.get_active_airspeed_index());
_RFRN.available_memory = hal.util->available_memory(); _RFRN.available_memory = hal.util->available_memory();
_RFRN.ahrs_trim = ahrs.get_trim(); _RFRN.ahrs_trim = ahrs.get_trim();
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED

Loading…
Cancel
Save