diff --git a/AntennaTracker/control_auto.cpp b/AntennaTracker/control_auto.cpp index 17616af75d..1d9ebc2cf0 100644 --- a/AntennaTracker/control_auto.cpp +++ b/AntennaTracker/control_auto.cpp @@ -16,7 +16,7 @@ void Tracker::update_auto(void) } float yaw = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100); // target yaw in centidegrees - float pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90) * 100; // target pitch in centidegrees + float pitch = constrain_float(nav_status.pitch+g.pitch_trim, g.pitch_min, g.pitch_max) * 100; // target pitch in centidegrees bool direction_reversed = get_ef_yaw_direction(); diff --git a/AntennaTracker/control_scan.cpp b/AntennaTracker/control_scan.cpp index 21363e0307..b04fcdc401 100644 --- a/AntennaTracker/control_scan.cpp +++ b/AntennaTracker/control_scan.cpp @@ -25,13 +25,13 @@ void Tracker::update_scan(void) if (!nav_status.manual_control_pitch) { float pitch_delta = g.scan_speed_pitch * 0.02f; nav_status.pitch += pitch_delta * (nav_status.scan_reverse_pitch?-1:1); - if (nav_status.pitch < -90 && nav_status.scan_reverse_pitch) { + if (nav_status.pitch < g.pitch_min && nav_status.scan_reverse_pitch) { nav_status.scan_reverse_pitch = false; } - if (nav_status.pitch > 90 && !nav_status.scan_reverse_pitch) { + if (nav_status.pitch > g.pitch_max && !nav_status.scan_reverse_pitch) { nav_status.scan_reverse_pitch = true; } - nav_status.pitch = constrain_float(nav_status.pitch, -90, 90); + nav_status.pitch = constrain_float(nav_status.pitch, -g.pitch_min, g.pitch_max); } update_auto();