From a46c5c2900359de811baa321b8e12fe614586671 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 3 Feb 2026 00:04:10 +0000 Subject: [PATCH] Rover: increase max pilot speed to 100m/s --- Rover/mode.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 894a6e2120..ede889a1ef 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -377,8 +377,8 @@ float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) const speed_max = (1.0f / cruise_throttle) * cruise_speed; } - // constrain to 30m/s (108km/h) and return - return constrain_float(speed_max, 0.0f, 30.0f); + // constrain to 100m/s and return + return constrain_float(speed_max, 0.0f, 100.0f); } // calculate pilot input to nudge speed up or down