Rover: correct clamping of RTL_SPEED parameter

MAX wasn't treating these things as floats
This commit is contained in:
Peter Barker 2024-05-07 13:21:16 +10:00 committed by Andrew Tridgell
parent e92c38454b
commit 96cb8aedc8
1 changed files with 1 additions and 1 deletions

View File

@ -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