mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_Avoidance: reduce OA path planner look ahead and margin param defaults
This commit is contained in:
parent
a5ec64fc99
commit
a1a2733926
@ -24,8 +24,8 @@
|
|||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
// parameter defaults
|
// parameter defaults
|
||||||
const float OA_LOOKAHEAD_DEFAULT = 50;
|
const float OA_LOOKAHEAD_DEFAULT = 15;
|
||||||
const float OA_MARGIN_MAX_DEFAULT = 10;
|
const float OA_MARGIN_MAX_DEFAULT = 5;
|
||||||
|
|
||||||
const int16_t OA_TIMEOUT_MS = 2000; // avoidance results over 2 seconds old are ignored
|
const int16_t OA_TIMEOUT_MS = 2000; // avoidance results over 2 seconds old are ignored
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user