AP_OAPathPlanner: slow updates to 1hz, timeout to 3sec

This commit is contained in:
Randy Mackay 2019-12-09 20:07:31 +09:00
parent 28e707466b
commit 50b4dd2599
1 changed files with 3 additions and 2 deletions

View File

@ -27,7 +27,8 @@ extern const AP_HAL::HAL &hal;
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
const int16_t OA_UPDATE_MS = 1000; // path planning updates run at 1hz
const int16_t OA_TIMEOUT_MS = 3000; // results over 3 seconds old are ignored
const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {
@ -204,7 +205,7 @@ void AP_OAPathPlanner::avoidance_thread()
}
const uint32_t now = AP_HAL::millis();
if (now - avoidance_latest_ms < 100) {
if (now - avoidance_latest_ms < OA_UPDATE_MS) {
continue;
}
avoidance_latest_ms = now;