mirror of https://github.com/ArduPilot/ardupilot
AP_OAPathPlanner: using static constexpr instead const
This commit is contained in:
parent
c2f77d0593
commit
9123554db3
|
@ -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[] = {
|
||||
|
||||
|
|
Loading…
Reference in New Issue