Skip to content

Commit 35449e7

Browse files
committed
Rover: correct clamping of RTL_SPEED parameter
MAX wasn't treating these things as floats
1 parent a031780 commit 35449e7

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

Rover/mode_rtl.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ bool ModeRTL::_enter()
88
}
99

1010
// initialise waypoint navigation library
11-
g2.wp_nav.init(MAX(0, g2.rtl_speed));
11+
g2.wp_nav.init(MAX(0.0f, g2.rtl_speed));
1212

1313
// set target to the closest rally point or home
1414
#if HAL_RALLY_ENABLED

0 commit comments

Comments
 (0)