From f32e2c9ddbfb158508277026e22af6688c80567c Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Fri, 23 Jun 2023 15:33:12 +1000 Subject: [PATCH] Rover: Lower minimum circle tracking distance --- Rover/mode_circle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Rover/mode_circle.cpp b/Rover/mode_circle.cpp index 8bedb2b16b..11b1edafcc 100644 --- a/Rover/mode_circle.cpp +++ b/Rover/mode_circle.cpp @@ -2,7 +2,7 @@ #define AR_CIRCLE_ACCEL_DEFAULT 1.0 // default acceleration in m/s/s if not specified by user #define AR_CIRCLE_RADIUS_MIN 0.5 // minimum radius in meters -#define AR_CIRCLE_REACHED_EDGE_DIST 1.0 // vehicle has reached edge if within 1m +#define AR_CIRCLE_REACHED_EDGE_DIST 0.2 // vehicle has reached edge if within 0.2m const AP_Param::GroupInfo ModeCircle::var_info[] = {