diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 5e2b0f7e6c..d513d49756 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -24,11 +24,11 @@ extern const AP_HAL::HAL &hal; // parameter defaults -const float OA_MARGIN_MAX_DEFAULT = 5; -const int16_t OA_OPTIONS_DEFAULT = 1; +static constexpr float OA_MARGIN_MAX_DEFAULT = 5; +static constexpr int16_t OA_OPTIONS_DEFAULT = 1; -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 +static constexpr int16_t OA_UPDATE_MS = 1000; // path planning updates run at 1hz +static constexpr int16_t OA_TIMEOUT_MS = 3000; // results over 3 seconds old are ignored const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {