From 510242a291de0036d883f4a8a04cec8e3a9ea707 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Jun 2018 16:05:33 +0900 Subject: [PATCH] Rover: fix RNGFND_TURN_ANGL range --- APMrover2/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 989eec8e03..ede915058b 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -196,7 +196,7 @@ const AP_Param::Info Rover::var_info[] = { // @DisplayName: Rangefinder trigger angle // @Description: The course deviation in degrees to apply while avoiding an obstacle detected with the rangefinder. A positive number means to turn right, and a negative angle means to turn left. // @Units: deg - // @Range: -45 45 + // @Range: 0 450 // @Increment: 1 // @User: Standard GSCALAR(rangefinder_turn_angle, "RNGFND_TURN_ANGL", 45),