From a1a273392643891e75598508ef1bc1d9ba827b9c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 9 Aug 2019 13:44:30 +0900 Subject: [PATCH] AC_Avoidance: reduce OA path planner look ahead and margin param defaults --- libraries/AC_Avoidance/AP_OAPathPlanner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index d3bc5d7d01..00f971235a 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -24,8 +24,8 @@ extern const AP_HAL::HAL &hal; // parameter defaults -const float OA_LOOKAHEAD_DEFAULT = 50; -const float OA_MARGIN_MAX_DEFAULT = 10; +const float OA_LOOKAHEAD_DEFAULT = 15; +const float OA_MARGIN_MAX_DEFAULT = 5; const int16_t OA_TIMEOUT_MS = 2000; // avoidance results over 2 seconds old are ignored