5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-02 22:18:28 -04:00

AP_DAL: use ahrs for EAS2TAS

this uses the stored value calculated once per loop
This commit is contained in:
Andrew Tridgell 2024-04-28 16:53:12 +10:00 committed by Peter Barker
parent 3d2037ef03
commit db9cc9ac84

View File

@ -65,7 +65,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
_RFRN.lat = _home.lat;
_RFRN.lng = _home.lng;
_RFRN.alt = _home.alt;
_RFRN.EAS2TAS = AP::baro().get_EAS2TAS();
_RFRN.EAS2TAS = ahrs.get_EAS2TAS();
_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();
_RFRN.fly_forward = ahrs.get_fly_forward();
_RFRN.takeoff_expected = ahrs.get_takeoff_expected();