mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OLC: fixed build of OSD on SITL
failed to link with constexpr, simple fix is to use defines, which also scopes it inside the cpp
This commit is contained in:
parent
a9a2c8c392
commit
c423bcca65
@ -24,6 +24,22 @@
|
||||
// This is a port of https://github.com/google/open-location-code/blob/master/c/olc.c
|
||||
// to avoid double floating point math and use integer math as much as possible.
|
||||
|
||||
#define SEPARATOR_CHAR '+'
|
||||
#define SEPARATOR_POS 8U
|
||||
#define PADDING_CHAR '0'
|
||||
|
||||
#define ENCODING_BASE 20U
|
||||
#define PAIR_CODE_LEN 10U
|
||||
#define CODE_LEN_MAX 15U
|
||||
|
||||
#define GRID_COLS 4U
|
||||
#define GRID_ROWS (ENCODING_BASE / GRID_COLS)
|
||||
|
||||
#define OLC_DEG_MULTIPLIER 10000000U // 1e7
|
||||
|
||||
#define LAT_MAX int32_t(90 * OLC_DEG_MULTIPLIER)
|
||||
#define LON_MAX int32_t(180 * OLC_DEG_MULTIPLIER)
|
||||
|
||||
const int32_t AP_OLC::initial_exponent = floorf(logf(2 * (LON_MAX / OLC_DEG_MULTIPLIER)) / logf(ENCODING_BASE));
|
||||
const int32_t AP_OLC::grid_size = (1 / powf(ENCODING_BASE, PAIR_CODE_LEN / 2 - (initial_exponent + 1))) * OLC_DEG_MULTIPLIER;
|
||||
const int32_t AP_OLC::initial_resolution = powf(ENCODING_BASE, initial_exponent) * OLC_DEG_MULTIPLIER;
|
||||
|
@ -36,23 +36,6 @@ public:
|
||||
static int olc_encode(int32_t lat, int32_t lon, size_t length, char *buf, size_t bufsize);
|
||||
|
||||
private:
|
||||
|
||||
static constexpr uint8_t SEPARATOR_CHAR = '+';
|
||||
static constexpr uint8_t SEPARATOR_POS = 8;
|
||||
static constexpr uint8_t PADDING_CHAR = '0';
|
||||
|
||||
static constexpr uint8_t ENCODING_BASE = 20;
|
||||
static constexpr uint8_t PAIR_CODE_LEN = 10;
|
||||
static constexpr uint8_t CODE_LEN_MAX = 15;
|
||||
|
||||
static constexpr uint8_t GRID_COLS = 4;
|
||||
static constexpr uint8_t GRID_ROWS = ENCODING_BASE / GRID_COLS;
|
||||
|
||||
static constexpr int32_t OLC_DEG_MULTIPLIER = 10000000; // 1e7
|
||||
|
||||
static constexpr int32_t LAT_MAX = 90 * OLC_DEG_MULTIPLIER;
|
||||
static constexpr int32_t LON_MAX = 180 * OLC_DEG_MULTIPLIER;
|
||||
|
||||
static const int32_t initial_exponent;
|
||||
// Work out the enclosing resolution (in degrees) for the grid algorithm.
|
||||
static const int32_t grid_size;
|
||||
|
Loading…
Reference in New Issue
Block a user