mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_DAL: prevent logical loop between AHRS and EKF
this prevents the EKF using its own rejecting_airspeed flag
This commit is contained in:
parent
01ac314837
commit
aab0c31385
@ -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…
Reference in New Issue
Block a user