From 2837471ddf6c6de30d38c4460ff32f3014b0425d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 22 Nov 2022 21:04:44 +1100 Subject: [PATCH] AP_GPS: fixed build without GPS_MOVING_BASELINE --- libraries/AP_GPS/AP_GPS_NMEA.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index ab6abf55d6..5c4ef8acc4 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -454,12 +454,14 @@ bool AP_GPS_NMEA::_term_complete() state.have_undulation = true; if (ag.heading_status == 4) { +#if GPS_MOVING_BASELINE Location slave( ag.slave_lat*1.0e7, ag.slave_lng*1.0e7, ag.slave_alt*1.0e2, Location::AltFrame::ABSOLUTE ); const float dist = state.location.get_distance_NED(slave).length(); const float bearing = degrees(state.location.get_bearing(slave)); const float alt_diff = (state.location.alt - slave.alt)*0.01; calculate_moving_base_yaw(bearing, dist, alt_diff); state.gps_yaw_configured = true; +#endif } else { state.have_gps_yaw = false; }