From 6840cb183d8a5b97519668b919aeed82d16e79ad Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 May 2024 13:21:16 +1000 Subject: [PATCH] Rover: correct clamping of RTL_SPEED parameter MAX wasn't treating these things as floats --- Rover/mode_rtl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index e896c5151f..8fe2ad7595 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -8,7 +8,7 @@ bool ModeRTL::_enter() } // initialise waypoint navigation library - g2.wp_nav.init(MAX(0, g2.rtl_speed)); + g2.wp_nav.init(MAX(0.0f, g2.rtl_speed)); // set target to the closest rally point or home #if HAL_RALLY_ENABLED