mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Add GPS coordinates OSD elements display variants; add support for Open Location Code display
Adds variations in GPS coordinate OSD element display: 1. Fractional degrees with 7 digits (default) - 000.0000000 2. Fractional degrees with 4 digits - 000.0000 3. Degrees, minutes, seconds - 000^00'00.0"E 4. Open Location Code (sometimed called Google Plus Code) - 23ABC4R8+M37 Uses Open Location Code library from: https://github.com/google/open-location-code Added support for `STATE(GPS_FIX_EVER)` to differentiate from having a fix now (`STATE(GPS_FIX)`) vs. ever having a fix. Logic change to only display coordinates from the GPS module once a fix has been initially established. This prevents displaying interim coordinates supplied by the GPS while the fix is still being establised as these coordinates can be inaccurate by hundreds of miles. Once a fix is established initially then the coordinates will continue to be displayed even if the fix is lost or degrades in quality. Add logic to "blink" the coordinates if the 3D fix is lost after initially being established. Alerts the user that the coordinate display may be inaccurate or no longer being updated. We want to keep the coordinates displayed to aid recovery if the user loses the fix (like crashing upside down). Replace GPS defines `LAT` and `LON` used throughout the code with the enumeration: ``` typedef enum { GPS_LATITUDE, GPS_LONGITUDE } gpsCoordinateType_e; ``` The Open Location Code option is bounded with `USE_GPS_PLUS_CODE` to allow it to be excluded if needed for targets with limited flash space. It currently fits for F411 but we may have to remove it in the future.
This commit is contained in:
parent
8511ba930f
commit
37dbbd0755
20 changed files with 1240 additions and 66 deletions
202
lib/main/google/olc/LICENSE
Normal file
202
lib/main/google/olc/LICENSE
Normal file
|
@ -0,0 +1,202 @@
|
|||
|
||||
Apache License
|
||||
Version 2.0, January 2004
|
||||
http://www.apache.org/licenses/
|
||||
|
||||
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
|
||||
|
||||
1. Definitions.
|
||||
|
||||
"License" shall mean the terms and conditions for use, reproduction,
|
||||
and distribution as defined by Sections 1 through 9 of this document.
|
||||
|
||||
"Licensor" shall mean the copyright owner or entity authorized by
|
||||
the copyright owner that is granting the License.
|
||||
|
||||
"Legal Entity" shall mean the union of the acting entity and all
|
||||
other entities that control, are controlled by, or are under common
|
||||
control with that entity. For the purposes of this definition,
|
||||
"control" means (i) the power, direct or indirect, to cause the
|
||||
direction or management of such entity, whether by contract or
|
||||
otherwise, or (ii) ownership of fifty percent (50%) or more of the
|
||||
outstanding shares, or (iii) beneficial ownership of such entity.
|
||||
|
||||
"You" (or "Your") shall mean an individual or Legal Entity
|
||||
exercising permissions granted by this License.
|
||||
|
||||
"Source" form shall mean the preferred form for making modifications,
|
||||
including but not limited to software source code, documentation
|
||||
source, and configuration files.
|
||||
|
||||
"Object" form shall mean any form resulting from mechanical
|
||||
transformation or translation of a Source form, including but
|
||||
not limited to compiled object code, generated documentation,
|
||||
and conversions to other media types.
|
||||
|
||||
"Work" shall mean the work of authorship, whether in Source or
|
||||
Object form, made available under the License, as indicated by a
|
||||
copyright notice that is included in or attached to the work
|
||||
(an example is provided in the Appendix below).
|
||||
|
||||
"Derivative Works" shall mean any work, whether in Source or Object
|
||||
form, that is based on (or derived from) the Work and for which the
|
||||
editorial revisions, annotations, elaborations, or other modifications
|
||||
represent, as a whole, an original work of authorship. For the purposes
|
||||
of this License, Derivative Works shall not include works that remain
|
||||
separable from, or merely link (or bind by name) to the interfaces of,
|
||||
the Work and Derivative Works thereof.
|
||||
|
||||
"Contribution" shall mean any work of authorship, including
|
||||
the original version of the Work and any modifications or additions
|
||||
to that Work or Derivative Works thereof, that is intentionally
|
||||
submitted to Licensor for inclusion in the Work by the copyright owner
|
||||
or by an individual or Legal Entity authorized to submit on behalf of
|
||||
the copyright owner. For the purposes of this definition, "submitted"
|
||||
means any form of electronic, verbal, or written communication sent
|
||||
to the Licensor or its representatives, including but not limited to
|
||||
communication on electronic mailing lists, source code control systems,
|
||||
and issue tracking systems that are managed by, or on behalf of, the
|
||||
Licensor for the purpose of discussing and improving the Work, but
|
||||
excluding communication that is conspicuously marked or otherwise
|
||||
designated in writing by the copyright owner as "Not a Contribution."
|
||||
|
||||
"Contributor" shall mean Licensor and any individual or Legal Entity
|
||||
on behalf of whom a Contribution has been received by Licensor and
|
||||
subsequently incorporated within the Work.
|
||||
|
||||
2. Grant of Copyright License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
copyright license to reproduce, prepare Derivative Works of,
|
||||
publicly display, publicly perform, sublicense, and distribute the
|
||||
Work and such Derivative Works in Source or Object form.
|
||||
|
||||
3. Grant of Patent License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
(except as stated in this section) patent license to make, have made,
|
||||
use, offer to sell, sell, import, and otherwise transfer the Work,
|
||||
where such license applies only to those patent claims licensable
|
||||
by such Contributor that are necessarily infringed by their
|
||||
Contribution(s) alone or by combination of their Contribution(s)
|
||||
with the Work to which such Contribution(s) was submitted. If You
|
||||
institute patent litigation against any entity (including a
|
||||
cross-claim or counterclaim in a lawsuit) alleging that the Work
|
||||
or a Contribution incorporated within the Work constitutes direct
|
||||
or contributory patent infringement, then any patent licenses
|
||||
granted to You under this License for that Work shall terminate
|
||||
as of the date such litigation is filed.
|
||||
|
||||
4. Redistribution. You may reproduce and distribute copies of the
|
||||
Work or Derivative Works thereof in any medium, with or without
|
||||
modifications, and in Source or Object form, provided that You
|
||||
meet the following conditions:
|
||||
|
||||
(a) You must give any other recipients of the Work or
|
||||
Derivative Works a copy of this License; and
|
||||
|
||||
(b) You must cause any modified files to carry prominent notices
|
||||
stating that You changed the files; and
|
||||
|
||||
(c) You must retain, in the Source form of any Derivative Works
|
||||
that You distribute, all copyright, patent, trademark, and
|
||||
attribution notices from the Source form of the Work,
|
||||
excluding those notices that do not pertain to any part of
|
||||
the Derivative Works; and
|
||||
|
||||
(d) If the Work includes a "NOTICE" text file as part of its
|
||||
distribution, then any Derivative Works that You distribute must
|
||||
include a readable copy of the attribution notices contained
|
||||
within such NOTICE file, excluding those notices that do not
|
||||
pertain to any part of the Derivative Works, in at least one
|
||||
of the following places: within a NOTICE text file distributed
|
||||
as part of the Derivative Works; within the Source form or
|
||||
documentation, if provided along with the Derivative Works; or,
|
||||
within a display generated by the Derivative Works, if and
|
||||
wherever such third-party notices normally appear. The contents
|
||||
of the NOTICE file are for informational purposes only and
|
||||
do not modify the License. You may add Your own attribution
|
||||
notices within Derivative Works that You distribute, alongside
|
||||
or as an addendum to the NOTICE text from the Work, provided
|
||||
that such additional attribution notices cannot be construed
|
||||
as modifying the License.
|
||||
|
||||
You may add Your own copyright statement to Your modifications and
|
||||
may provide additional or different license terms and conditions
|
||||
for use, reproduction, or distribution of Your modifications, or
|
||||
for any such Derivative Works as a whole, provided Your use,
|
||||
reproduction, and distribution of the Work otherwise complies with
|
||||
the conditions stated in this License.
|
||||
|
||||
5. Submission of Contributions. Unless You explicitly state otherwise,
|
||||
any Contribution intentionally submitted for inclusion in the Work
|
||||
by You to the Licensor shall be under the terms and conditions of
|
||||
this License, without any additional terms or conditions.
|
||||
Notwithstanding the above, nothing herein shall supersede or modify
|
||||
the terms of any separate license agreement you may have executed
|
||||
with Licensor regarding such Contributions.
|
||||
|
||||
6. Trademarks. This License does not grant permission to use the trade
|
||||
names, trademarks, service marks, or product names of the Licensor,
|
||||
except as required for reasonable and customary use in describing the
|
||||
origin of the Work and reproducing the content of the NOTICE file.
|
||||
|
||||
7. Disclaimer of Warranty. Unless required by applicable law or
|
||||
agreed to in writing, Licensor provides the Work (and each
|
||||
Contributor provides its Contributions) on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
|
||||
implied, including, without limitation, any warranties or conditions
|
||||
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
|
||||
PARTICULAR PURPOSE. You are solely responsible for determining the
|
||||
appropriateness of using or redistributing the Work and assume any
|
||||
risks associated with Your exercise of permissions under this License.
|
||||
|
||||
8. Limitation of Liability. In no event and under no legal theory,
|
||||
whether in tort (including negligence), contract, or otherwise,
|
||||
unless required by applicable law (such as deliberate and grossly
|
||||
negligent acts) or agreed to in writing, shall any Contributor be
|
||||
liable to You for damages, including any direct, indirect, special,
|
||||
incidental, or consequential damages of any character arising as a
|
||||
result of this License or out of the use or inability to use the
|
||||
Work (including but not limited to damages for loss of goodwill,
|
||||
work stoppage, computer failure or malfunction, or any and all
|
||||
other commercial damages or losses), even if such Contributor
|
||||
has been advised of the possibility of such damages.
|
||||
|
||||
9. Accepting Warranty or Additional Liability. While redistributing
|
||||
the Work or Derivative Works thereof, You may choose to offer,
|
||||
and charge a fee for, acceptance of support, warranty, indemnity,
|
||||
or other liability obligations and/or rights consistent with this
|
||||
License. However, in accepting such obligations, You may act only
|
||||
on Your own behalf and on Your sole responsibility, not on behalf
|
||||
of any other Contributor, and only if You agree to indemnify,
|
||||
defend, and hold each Contributor harmless for any liability
|
||||
incurred by, or claims asserted against, such Contributor by reason
|
||||
of your accepting any such warranty or additional liability.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
||||
|
||||
APPENDIX: How to apply the Apache License to your work.
|
||||
|
||||
To apply the Apache License to your work, attach the following
|
||||
boilerplate notice, with the fields enclosed by brackets "[]"
|
||||
replaced with your own identifying information. (Don't include
|
||||
the brackets!) The text should be enclosed in the appropriate
|
||||
comment syntax for the file format. We also recommend that a
|
||||
file or class name and description of purpose be included on the
|
||||
same "printed page" as the copyright notice for easier
|
||||
identification within third-party archives.
|
||||
|
||||
Copyright [yyyy] [name of copyright owner]
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
96
lib/main/google/olc/README.md
Normal file
96
lib/main/google/olc/README.md
Normal file
|
@ -0,0 +1,96 @@
|
|||
Open Location Code
|
||||
==================
|
||||
|
||||
[](https://travis-ci.org/google/open-location-code)
|
||||
[](https://cdnjs.com/libraries/openlocationcode)
|
||||
|
||||
Open Location Code is a technology that gives a way of encoding location into a form that is
|
||||
easier to use than latitude and longitude. The codes generated are called plus codes, as their
|
||||
distinguishing attribute is that they include a "+" character.
|
||||
|
||||
The technology is designed to produce codes that can be used as a replacement for street addresses, especially
|
||||
in places where buildings aren't numbered or streets aren't named.
|
||||
|
||||
Plus codes represent an area, not a point. As digits are added
|
||||
to a code, the area shrinks, so a long code is more precise than a short
|
||||
code.
|
||||
|
||||
Codes that are similar are located closer together than codes that are
|
||||
different.
|
||||
|
||||
A location can be converted into a code, and a code can be converted back
|
||||
to a location completely offline.
|
||||
|
||||
There are no data tables to lookup or online services required. The
|
||||
algorithm is publicly available and can be used without restriction.
|
||||
|
||||
Links
|
||||
-----
|
||||
* [Demonstration site](http://plus.codes/)
|
||||
* [Mailing list](https://groups.google.com/forum/#!forum/open-location-code)
|
||||
* [Comparison of existing location encoding systems](https://github.com/google/open-location-code/wiki/Evaluation-of-Location-Encoding-Systems)
|
||||
* [Open Location Code definition](https://github.com/google/open-location-code/blob/master/docs/olc_definition.adoc)
|
||||
|
||||
Description
|
||||
-----------
|
||||
|
||||
Codes are made up of a sequence of digits chosen from a set of 20. The
|
||||
digits in the code alternate between latitude and longitude. The first
|
||||
four digits describe a one degree latitude by one degree longitude
|
||||
area, aligned on degrees. Adding two further digits to the code,
|
||||
reduces the area to 1/20th of a degree by 1/20th of a degree within the
|
||||
previous area. And so on - each pair of digits reduces the area to
|
||||
1/400th of the previous area.
|
||||
|
||||
As an example, the Parliament Buildings in Nairobi, Kenya are located at
|
||||
6GCRPR6C+24. 6GCR is the area from 2S 36E to 1S 37E. PR6C+24 is a 14 meter
|
||||
wide by 14 meter high area within 6GCR.
|
||||
|
||||
A "+" character is used after eight digits, to break the code up into two parts
|
||||
and to distinguish codes from postal codes.
|
||||
|
||||
There will be locations where a 10 digit code is not sufficiently precise, but
|
||||
refining it by a factor of 20 is i) unnecessarily precise and ii) requires extending
|
||||
the code by two digits. Instead, after 10 digits, the area is divided
|
||||
into a 4x5 grid and a single digit used to identify the grid square. A single
|
||||
grid refinement step reduces the area to approximately 3.5x2.8 meters.
|
||||
|
||||
Codes can be shortened relative to a location. This reduces the number of digits
|
||||
that must be remembered, by using a location to identify an approximate area,
|
||||
and then generating the nearest matching code. Shortening a code, if possible,
|
||||
will drop four or more digits from the start of the code. The degree to which a
|
||||
code can be shortened depends on the proximity of the reference location.
|
||||
|
||||
If the reference location is derived from a town or city name, it is dependent
|
||||
on the accuracy of the geocoding service. Although one service may place
|
||||
"Zurich" close to the Google office, another may move it by a hundred meters or
|
||||
more, and this could be enough to prevent the original code being recovered.
|
||||
Rather than a large city size feature to generate the reference location, it is
|
||||
better to use smaller, neighbourhood features, that will not have as much
|
||||
variation in their geocode results.
|
||||
|
||||
Guidelines for shortening codes are in the [wiki](https://github.com/google/open-location-code/wiki).
|
||||
|
||||
Recovering shortened codes works by providing the short code and a reference
|
||||
location. This does not need to be the same as the location used to shorten the
|
||||
code, but it does need to be nearby. Shortened codes always include the "+"
|
||||
character so it is simple to compute the missing component.
|
||||
|
||||
* 8F+GG is missing six leading characters
|
||||
* 6C8F+GG is missing four leading characters
|
||||
|
||||
Example Code
|
||||
------------
|
||||
|
||||
The subdirectories contain sample implementations and tests for different
|
||||
languages. Each implementation provides the following functions:
|
||||
|
||||
* Test a code to see if it is a valid sequence
|
||||
* Test a code to see if it is a valid full code
|
||||
Not all valid sequences are valid full codes
|
||||
* Encode a latitude and longitude to a standard accuracy
|
||||
(14 meter by 14 meter) code
|
||||
* Encode a latitude and longitude to a code of any length
|
||||
* Decode a code to its coordinates: low, high and center
|
||||
* Shorten a full code relative to a location
|
||||
* Extend a short code relative to a location
|
6
lib/main/google/olc/betaflight.h
Normal file
6
lib/main/google/olc/betaflight.h
Normal file
|
@ -0,0 +1,6 @@
|
|||
// Be sure to add this to olc.c
|
||||
|
||||
// Ignore a bunch of warnings in this sloppy code
|
||||
#pragma GCC diagnostic ignored "-Wdouble-promotion"
|
||||
#pragma GCC diagnostic ignored "-Wunused-parameter"
|
||||
#pragma GCC diagnostic ignored "-Wsign-compare"
|
7
lib/main/google/olc/betaflight_readme.txt
Normal file
7
lib/main/google/olc/betaflight_readme.txt
Normal file
|
@ -0,0 +1,7 @@
|
|||
Open Location Codes
|
||||
|
||||
Source from: https://github.com/google/open-location-code
|
||||
|
||||
Code use here is unaltered except for adding the following header to olc.c to ignore the numerous compiler warnings for sloppy code:
|
||||
|
||||
#include betaflight.h
|
608
lib/main/google/olc/olc.c
Normal file
608
lib/main/google/olc/olc.c
Normal file
|
@ -0,0 +1,608 @@
|
|||
#include "olc.h"
|
||||
#include <ctype.h>
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
#include <memory.h>
|
||||
#include <stdio.h>
|
||||
#include "olc_private.h"
|
||||
|
||||
#include "betaflight.h"
|
||||
|
||||
#define CORRECT_IF_SEPARATOR(var, info) \
|
||||
do { \
|
||||
(var) += (info)->sep_first >= 0 ? 1 : 0; \
|
||||
} while (0)
|
||||
|
||||
// Information about a code, produced by analyse();
|
||||
typedef struct CodeInfo {
|
||||
// Original code.
|
||||
const char* code;
|
||||
// Total count of characters in the code including padding and separators.
|
||||
int size;
|
||||
// Count of valid digits (not including padding or separators).
|
||||
int len;
|
||||
// Index of the first separator in the code.
|
||||
int sep_first;
|
||||
// Index of the last separator in the code. (If there is only one, same as
|
||||
// sep_first.)
|
||||
int sep_last;
|
||||
// Index of the first padding character in the code.
|
||||
int pad_first;
|
||||
// Index of the last padding character in the code. (If there is only one,
|
||||
// same as pad_first.)
|
||||
int pad_last;
|
||||
} CodeInfo;
|
||||
|
||||
// Helper functions
|
||||
static int analyse(const char* code, size_t size, CodeInfo* info);
|
||||
static int is_short(CodeInfo* info);
|
||||
static int is_full(CodeInfo* info);
|
||||
static int decode(CodeInfo* info, OLC_CodeArea* decoded);
|
||||
static size_t code_length(CodeInfo* info);
|
||||
|
||||
static double pow_neg(double base, double exponent);
|
||||
static double compute_latitude_precision(int length);
|
||||
static double normalize_longitude(double lon_degrees);
|
||||
static double adjust_latitude(double lat_degrees, size_t length);
|
||||
|
||||
void OLC_GetCenter(const OLC_CodeArea* area, OLC_LatLon* center) {
|
||||
center->lat = area->lo.lat + (area->hi.lat - area->lo.lat) / 2.0;
|
||||
if (center->lat > kLatMaxDegrees) {
|
||||
center->lat = kLatMaxDegrees;
|
||||
}
|
||||
|
||||
center->lon = area->lo.lon + (area->hi.lon - area->lo.lon) / 2.0;
|
||||
if (center->lon > kLonMaxDegrees) {
|
||||
center->lon = kLonMaxDegrees;
|
||||
}
|
||||
}
|
||||
|
||||
size_t OLC_CodeLength(const char* code, size_t size) {
|
||||
CodeInfo info;
|
||||
analyse(code, size, &info);
|
||||
return code_length(&info);
|
||||
}
|
||||
|
||||
int OLC_IsValid(const char* code, size_t size) {
|
||||
CodeInfo info;
|
||||
return analyse(code, size, &info) > 0;
|
||||
}
|
||||
|
||||
int OLC_IsShort(const char* code, size_t size) {
|
||||
CodeInfo info;
|
||||
if (analyse(code, size, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
return is_short(&info);
|
||||
}
|
||||
|
||||
int OLC_IsFull(const char* code, size_t size) {
|
||||
CodeInfo info;
|
||||
if (analyse(code, size, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
return is_full(&info);
|
||||
}
|
||||
|
||||
int OLC_Encode(const OLC_LatLon* location, size_t length, char* code,
|
||||
int maxlen) {
|
||||
// Limit the maximum number of digits in the code.
|
||||
if (length > kMaximumDigitCount) {
|
||||
length = kMaximumDigitCount;
|
||||
}
|
||||
// Adjust latitude and longitude so they fall into positive ranges.
|
||||
double latitude = adjust_latitude(location->lat, length);
|
||||
double longitude = normalize_longitude(location->lon);
|
||||
|
||||
// Build up the code here, then copy it to the passed pointer.
|
||||
char fullcode[] = "12345678901234567";
|
||||
|
||||
// Compute the code.
|
||||
// This approach converts each value to an integer after multiplying it by
|
||||
// the final precision. This allows us to use only integer operations, so
|
||||
// avoiding any accumulation of floating point representation errors.
|
||||
|
||||
// Multiply values by their precision and convert to positive without any
|
||||
// floating point operations.
|
||||
long long int lat_val = kLatMaxDegrees * 2.5e7;
|
||||
long long int lng_val = kLonMaxDegrees * 8.192e6;
|
||||
lat_val += latitude * 2.5e7;
|
||||
lng_val += longitude * 8.192e6;
|
||||
|
||||
size_t pos = kMaximumDigitCount;
|
||||
// Compute the grid part of the code if necessary.
|
||||
if (length > kPairCodeLength) {
|
||||
for (size_t i = 0; i < kGridCodeLength; i++) {
|
||||
int lat_digit = lat_val % kGridRows;
|
||||
int lng_digit = lng_val % kGridCols;
|
||||
int ndx = lat_digit * kGridCols + lng_digit;
|
||||
fullcode[pos--] = kAlphabet[ndx];
|
||||
// Note! Integer division.
|
||||
lat_val /= kGridRows;
|
||||
lng_val /= kGridCols;
|
||||
}
|
||||
} else {
|
||||
lat_val /= pow(kGridRows, kGridCodeLength);
|
||||
lng_val /= pow(kGridCols, kGridCodeLength);
|
||||
}
|
||||
pos = kPairCodeLength;
|
||||
// Compute the pair section of the code.
|
||||
for (size_t i = 0; i < kPairCodeLength / 2; i++) {
|
||||
int lat_ndx = lat_val % kEncodingBase;
|
||||
int lng_ndx = lng_val % kEncodingBase;
|
||||
fullcode[pos--] = kAlphabet[lng_ndx];
|
||||
fullcode[pos--] = kAlphabet[lat_ndx];
|
||||
// Note! Integer division.
|
||||
lat_val /= kEncodingBase;
|
||||
lng_val /= kEncodingBase;
|
||||
if (i == 0) {
|
||||
fullcode[pos--] = kSeparator;
|
||||
}
|
||||
}
|
||||
// Replace digits with padding if necessary.
|
||||
if (length < kSeparatorPosition) {
|
||||
for (size_t i = length; i < kSeparatorPosition; i++) {
|
||||
fullcode[i] = kPaddingCharacter;
|
||||
}
|
||||
fullcode[kSeparatorPosition] = kSeparator;
|
||||
}
|
||||
// Now copy the full code digits into the buffer.
|
||||
size_t char_count = length + 1;
|
||||
if (kSeparatorPosition + 1 > char_count) {
|
||||
char_count = kSeparatorPosition + 1;
|
||||
}
|
||||
for (size_t i = 0; i < char_count; i++) {
|
||||
code[i] = fullcode[i];
|
||||
}
|
||||
|
||||
// Terminate the buffer.
|
||||
code[char_count] = '\0';
|
||||
|
||||
return char_count;
|
||||
}
|
||||
|
||||
int OLC_EncodeDefault(const OLC_LatLon* location, char* code, int maxlen) {
|
||||
return OLC_Encode(location, kPairCodeLength, code, maxlen);
|
||||
}
|
||||
|
||||
int OLC_Decode(const char* code, size_t size, OLC_CodeArea* decoded) {
|
||||
CodeInfo info;
|
||||
if (analyse(code, size, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
return decode(&info, decoded);
|
||||
}
|
||||
|
||||
int OLC_Shorten(const char* code, size_t size, const OLC_LatLon* reference,
|
||||
char* shortened, int maxlen) {
|
||||
CodeInfo info;
|
||||
if (analyse(code, size, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
if (info.pad_first > 0) {
|
||||
return 0;
|
||||
}
|
||||
if (!is_full(&info)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
OLC_CodeArea code_area;
|
||||
decode(&info, &code_area);
|
||||
OLC_LatLon center;
|
||||
OLC_GetCenter(&code_area, ¢er);
|
||||
|
||||
// Ensure that latitude and longitude are valid.
|
||||
double lat = adjust_latitude(reference->lat, info.len);
|
||||
double lon = normalize_longitude(reference->lon);
|
||||
|
||||
// How close are the latitude and longitude to the code center.
|
||||
double alat = fabs(center.lat - lat);
|
||||
double alon = fabs(center.lon - lon);
|
||||
double range = alat > alon ? alat : alon;
|
||||
|
||||
// Yes, magic numbers... sob.
|
||||
int start = 0;
|
||||
const double safety_factor = 0.3;
|
||||
const int removal_lengths[3] = {8, 6, 4};
|
||||
for (int j = 0; j < sizeof(removal_lengths) / sizeof(removal_lengths[0]);
|
||||
++j) {
|
||||
// Check if we're close enough to shorten. The range must be less than
|
||||
// 1/2 the resolution to shorten at all, and we want to allow some
|
||||
// safety, so use 0.3 instead of 0.5 as a multiplier.
|
||||
int removal_length = removal_lengths[j];
|
||||
double area_edge =
|
||||
compute_latitude_precision(removal_length) * safety_factor;
|
||||
if (range < area_edge) {
|
||||
start = removal_length;
|
||||
break;
|
||||
}
|
||||
}
|
||||
int pos = 0;
|
||||
for (int j = start; j < info.size && code[j] != '\0'; ++j) {
|
||||
shortened[pos++] = code[j];
|
||||
}
|
||||
shortened[pos] = '\0';
|
||||
return pos;
|
||||
}
|
||||
|
||||
int OLC_RecoverNearest(const char* short_code, size_t size,
|
||||
const OLC_LatLon* reference, char* code, int maxlen) {
|
||||
CodeInfo info;
|
||||
if (analyse(short_code, size, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
// Check if it is a full code - then we just convert to upper case.
|
||||
if (is_full(&info)) {
|
||||
OLC_CodeArea code_area;
|
||||
decode(&info, &code_area);
|
||||
OLC_LatLon center;
|
||||
OLC_GetCenter(&code_area, ¢er);
|
||||
return OLC_Encode(¢er, code_area.len, code, maxlen);
|
||||
}
|
||||
if (!is_short(&info)) {
|
||||
return 0;
|
||||
}
|
||||
int len = code_length(&info);
|
||||
|
||||
// Ensure that latitude and longitude are valid.
|
||||
double lat = adjust_latitude(reference->lat, len);
|
||||
double lon = normalize_longitude(reference->lon);
|
||||
|
||||
// Compute the number of digits we need to recover.
|
||||
size_t padding_length = kSeparatorPosition;
|
||||
if (info.sep_first >= 0) {
|
||||
padding_length -= info.sep_first;
|
||||
}
|
||||
|
||||
// The resolution (height and width) of the padded area in degrees.
|
||||
double resolution = pow_neg(kEncodingBase, 2.0 - (padding_length / 2.0));
|
||||
|
||||
// Distance from the center to an edge (in degrees).
|
||||
double half_res = resolution / 2.0;
|
||||
|
||||
// Use the reference location to pad the supplied short code and decode it.
|
||||
OLC_LatLon latlon = {lat, lon};
|
||||
char encoded[256];
|
||||
OLC_EncodeDefault(&latlon, encoded, 256);
|
||||
|
||||
char new_code[256];
|
||||
int pos = 0;
|
||||
for (int j = 0; encoded[j] != '\0'; ++j) {
|
||||
if (j >= padding_length) {
|
||||
break;
|
||||
}
|
||||
new_code[pos++] = encoded[j];
|
||||
}
|
||||
for (int j = 0; j < info.size && short_code[j] != '\0'; ++j) {
|
||||
new_code[pos++] = short_code[j];
|
||||
}
|
||||
new_code[pos] = '\0';
|
||||
if (analyse(new_code, pos, &info) <= 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
OLC_CodeArea code_area;
|
||||
decode(&info, &code_area);
|
||||
OLC_LatLon center;
|
||||
OLC_GetCenter(&code_area, ¢er);
|
||||
|
||||
// How many degrees latitude is the code from the reference?
|
||||
if (lat + half_res < center.lat &&
|
||||
center.lat - resolution > -kLatMaxDegrees) {
|
||||
// If the proposed code is more than half a cell north of the reference
|
||||
// location, it's too far, and the best match will be one cell south.
|
||||
center.lat -= resolution;
|
||||
} else if (lat - half_res > center.lat &&
|
||||
center.lat + resolution < kLatMaxDegrees) {
|
||||
// If the proposed code is more than half a cell south of the reference
|
||||
// location, it's too far, and the best match will be one cell north.
|
||||
center.lat += resolution;
|
||||
}
|
||||
|
||||
// How many degrees longitude is the code from the reference?
|
||||
if (lon + half_res < center.lon) {
|
||||
center.lon -= resolution;
|
||||
} else if (lon - half_res > center.lon) {
|
||||
center.lon += resolution;
|
||||
}
|
||||
|
||||
return OLC_Encode(¢er, len + padding_length, code, maxlen);
|
||||
}
|
||||
|
||||
// private functions
|
||||
|
||||
static int analyse(const char* code, size_t size, CodeInfo* info) {
|
||||
memset(info, 0, sizeof(CodeInfo));
|
||||
|
||||
// null code is not valid
|
||||
if (!code) {
|
||||
return 0;
|
||||
}
|
||||
if (!size) {
|
||||
size = strlen(code);
|
||||
}
|
||||
|
||||
info->code = code;
|
||||
info->size = size < kMaximumDigitCount ? size : kMaximumDigitCount;
|
||||
info->sep_first = -1;
|
||||
info->sep_last = -1;
|
||||
info->pad_first = -1;
|
||||
info->pad_last = -1;
|
||||
int j = 0;
|
||||
for (j = 0; j <= size && code[j] != '\0'; ++j) {
|
||||
int ok = 0;
|
||||
|
||||
// if this is a padding character, remember it
|
||||
if (!ok && code[j] == kPaddingCharacter) {
|
||||
if (info->pad_first < 0) {
|
||||
info->pad_first = j;
|
||||
}
|
||||
info->pad_last = j;
|
||||
ok = 1;
|
||||
}
|
||||
|
||||
// if this is a separator character, remember it
|
||||
if (!ok && code[j] == kSeparator) {
|
||||
if (info->sep_first < 0) {
|
||||
info->sep_first = j;
|
||||
}
|
||||
info->sep_last = j;
|
||||
ok = 1;
|
||||
}
|
||||
|
||||
// only accept characters in the valid character set
|
||||
if (!ok && get_alphabet_position(code[j]) >= 0) {
|
||||
ok = 1;
|
||||
}
|
||||
|
||||
// didn't find anything expected => bail out
|
||||
if (!ok) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// so far, code only has valid characters -- good
|
||||
info->len = j < kMaximumDigitCount ? j : kMaximumDigitCount;
|
||||
|
||||
// Cannot be empty
|
||||
if (info->len <= 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// The separator is required.
|
||||
if (info->sep_first < 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// There can be only one... separator.
|
||||
if (info->sep_last > info->sep_first) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// separator cannot be the only character
|
||||
if (info->len == 1) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Is the separator in an illegal position?
|
||||
if (info->sep_first > kSeparatorPosition || (info->sep_first % 2)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// padding cannot be at the initial position
|
||||
if (info->pad_first == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// We can have an even number of padding characters before the separator,
|
||||
// but then it must be the final character.
|
||||
if (info->pad_first > 0) {
|
||||
// Short codes cannot have padding
|
||||
if (info->sep_first < kSeparatorPosition) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// The first padding character needs to be in an odd position.
|
||||
if (info->pad_first % 2) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// With padding, the separator must be the final character
|
||||
if (info->sep_last < info->len - 1) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// After removing padding characters, we mustn't have anything left.
|
||||
if (info->pad_last < info->sep_first - 1) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// If there are characters after the separator, make sure there isn't just
|
||||
// one of them (not legal).
|
||||
if (info->len - info->sep_first - 1 == 1) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return info->len;
|
||||
}
|
||||
|
||||
static int is_short(CodeInfo* info) {
|
||||
if (info->len <= 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// if there is a separator, it cannot be beyond the valid position
|
||||
if (info->sep_first >= kSeparatorPosition) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
// checks that the first character of latitude or longitude is valid
|
||||
static int valid_first_character(CodeInfo* info, int pos, double kMax) {
|
||||
if (info->len <= pos) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Work out what the first character indicates
|
||||
size_t firstValue = get_alphabet_position(info->code[pos]);
|
||||
firstValue *= kEncodingBase;
|
||||
return firstValue < kMax;
|
||||
}
|
||||
|
||||
static int is_full(CodeInfo* info) {
|
||||
if (info->len <= 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// If there are less characters than expected before the separator.
|
||||
if (info->sep_first < kSeparatorPosition) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// check first latitude character, if any
|
||||
if (!valid_first_character(info, 0, kLatMaxDegreesT2)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// check first longitude character, if any
|
||||
if (!valid_first_character(info, 1, kLonMaxDegreesT2)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
static int decode(CodeInfo* info, OLC_CodeArea* decoded) {
|
||||
// Create a copy of the code, skipping padding and separators.
|
||||
char clean_code[256];
|
||||
int ci = 0;
|
||||
for (size_t i = 0; i < info->len + 1; i++) {
|
||||
if (info->code[i] != kPaddingCharacter && info->code[i] != kSeparator) {
|
||||
clean_code[ci] = info->code[i];
|
||||
ci++;
|
||||
}
|
||||
}
|
||||
clean_code[ci] = '\0';
|
||||
|
||||
// Initialise the values for each section. We work them out as integers and
|
||||
// convert them to floats at the end. Using doubles all the way results in
|
||||
// multiplying small rounding errors until they become significant.
|
||||
int normal_lat = -kLatMaxDegrees * kPairPrecisionInverse;
|
||||
int normal_lng = -kLonMaxDegrees * kPairPrecisionInverse;
|
||||
int extra_lat = 0;
|
||||
int extra_lng = 0;
|
||||
|
||||
// How many digits do we have to process?
|
||||
size_t digits = strlen(clean_code) < kPairCodeLength ? strlen(clean_code)
|
||||
: kPairCodeLength;
|
||||
// Define the place value for the most significant pair.
|
||||
int pv = pow(kEncodingBase, kPairCodeLength / 2);
|
||||
for (size_t i = 0; i < digits - 1; i += 2) {
|
||||
pv /= kEncodingBase;
|
||||
normal_lat += get_alphabet_position(clean_code[i]) * pv;
|
||||
normal_lng += get_alphabet_position(clean_code[i + 1]) * pv;
|
||||
}
|
||||
// Convert the place value to a float in degrees.
|
||||
double lat_precision = (double)pv / kPairPrecisionInverse;
|
||||
double lng_precision = (double)pv / kPairPrecisionInverse;
|
||||
// Process any extra precision digits.
|
||||
if (strlen(clean_code) > kPairCodeLength) {
|
||||
// How many digits do we have to process?
|
||||
digits = strlen(clean_code) < kMaximumDigitCount ? strlen(clean_code)
|
||||
: kMaximumDigitCount;
|
||||
// Initialise the place values for the grid.
|
||||
int row_pv = pow(kGridRows, kGridCodeLength);
|
||||
int col_pv = pow(kGridCols, kGridCodeLength);
|
||||
for (size_t i = kPairCodeLength; i < digits; i++) {
|
||||
row_pv /= kGridRows;
|
||||
col_pv /= kGridCols;
|
||||
int dval = get_alphabet_position(clean_code[i]);
|
||||
int row = dval / kGridCols;
|
||||
int col = dval % kGridCols;
|
||||
extra_lat += row * row_pv;
|
||||
extra_lng += col * col_pv;
|
||||
}
|
||||
// Adjust the precisions from the integer values to degrees.
|
||||
lat_precision = (double)row_pv / kGridLatPrecisionInverse;
|
||||
lng_precision = (double)col_pv / kGridLonPrecisionInverse;
|
||||
}
|
||||
// Merge the values from the normal and extra precision parts of the code.
|
||||
// Everything is ints so they all need to be cast to floats.
|
||||
double lat = (double)normal_lat / kPairPrecisionInverse +
|
||||
(double)extra_lat / kGridLatPrecisionInverse;
|
||||
double lng = (double)normal_lng / kPairPrecisionInverse +
|
||||
(double)extra_lng / kGridLonPrecisionInverse;
|
||||
decoded->lo.lat = lat;
|
||||
decoded->lo.lon = lng;
|
||||
decoded->hi.lat = lat + lat_precision;
|
||||
decoded->hi.lon = lng + lng_precision;
|
||||
decoded->len = strlen(clean_code);
|
||||
return decoded->len;
|
||||
}
|
||||
|
||||
static size_t code_length(CodeInfo* info) {
|
||||
int len = info->len;
|
||||
if (info->sep_first >= 0) {
|
||||
--len;
|
||||
}
|
||||
if (info->pad_first >= 0) {
|
||||
len = info->pad_first;
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
// Raises a number to an exponent, handling negative exponents.
|
||||
static double pow_neg(double base, double exponent) {
|
||||
if (exponent == 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (exponent > 0) {
|
||||
return pow(base, exponent);
|
||||
}
|
||||
|
||||
return 1 / pow(base, -exponent);
|
||||
}
|
||||
|
||||
// Compute the latitude precision value for a given code length. Lengths <= 10
|
||||
// have the same precision for latitude and longitude, but lengths > 10 have
|
||||
// different precisions due to the grid method having fewer columns than rows.
|
||||
static double compute_latitude_precision(int length) {
|
||||
// Magic numbers!
|
||||
if (length <= kPairCodeLength) {
|
||||
return pow_neg(kEncodingBase, floor((length / -2) + 2));
|
||||
}
|
||||
|
||||
return pow_neg(kEncodingBase, -3) / pow(kGridRows, length - kPairCodeLength);
|
||||
}
|
||||
|
||||
// Normalize a longitude into the range -180 to 180, not including 180.
|
||||
static double normalize_longitude(double lon_degrees) {
|
||||
while (lon_degrees < -kLonMaxDegrees) {
|
||||
lon_degrees += kLonMaxDegreesT2;
|
||||
}
|
||||
while (lon_degrees >= kLonMaxDegrees) {
|
||||
lon_degrees -= kLonMaxDegreesT2;
|
||||
}
|
||||
return lon_degrees;
|
||||
}
|
||||
|
||||
// Adjusts 90 degree latitude to be lower so that a legal OLC code can be
|
||||
// generated.
|
||||
static double adjust_latitude(double lat_degrees, size_t length) {
|
||||
if (lat_degrees < -kLatMaxDegrees) {
|
||||
lat_degrees = -kLatMaxDegrees;
|
||||
}
|
||||
if (lat_degrees > kLatMaxDegrees) {
|
||||
lat_degrees = kLatMaxDegrees;
|
||||
}
|
||||
if (lat_degrees < kLatMaxDegrees) {
|
||||
return lat_degrees;
|
||||
}
|
||||
// Subtract half the code precision to get the latitude into the code area.
|
||||
double precision = compute_latitude_precision(length);
|
||||
return lat_degrees - precision / 2;
|
||||
}
|
75
lib/main/google/olc/olc.h
Normal file
75
lib/main/google/olc/olc.h
Normal file
|
@ -0,0 +1,75 @@
|
|||
#ifndef OLC_OPENLOCATIONCODE_H_
|
||||
#define OLC_OPENLOCATIONCODE_H_
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#define OLC_VERSION_MAJOR 1
|
||||
#define OLC_VERSION_MINOR 0
|
||||
#define OLC_VERSION_PATCH 0
|
||||
|
||||
// OLC version number: 2.3.4 => 2003004
|
||||
// Useful for checking against a particular version or above:
|
||||
//
|
||||
// #if OLC_VERSION_NUM < OLC_MAKE_VERSION_NUM(1, 0, 2)
|
||||
// #error UNSUPPORTED OLC VERSION
|
||||
// #endif
|
||||
#define OLC_MAKE_VERSION_NUM(major, minor, patch) \
|
||||
((major * 1000 + minor) * 1000 + patch)
|
||||
|
||||
// OLC version string: 2.3.4 => "2.3.4"
|
||||
#define OLC_MAKE_VERSION_STR_IMPL(major, minor, patch) \
|
||||
(#major "." #minor "." #patch)
|
||||
#define OLC_MAKE_VERSION_STR(major, minor, patch) \
|
||||
OLC_MAKE_VERSION_STR_IMPL(major, minor, patch)
|
||||
|
||||
// Current version, as a number and a string
|
||||
#define OLC_VERSION_NUM \
|
||||
OLC_MAKE_VERSION_NUM(OLC_VERSION_MAJOR, OLC_VERSION_MINOR, OLC_VERSION_PATCH)
|
||||
#define OLC_VERSION_STR \
|
||||
OLC_MAKE_VERSION_STR(OLC_VERSION_MAJOR, OLC_VERSION_MINOR, OLC_VERSION_PATCH)
|
||||
|
||||
// A pair of doubles representing latitude / longitude
|
||||
typedef struct OLC_LatLon {
|
||||
double lat;
|
||||
double lon;
|
||||
} OLC_LatLon;
|
||||
|
||||
// An area defined by two corners (lo and hi) and a code length
|
||||
typedef struct OLC_CodeArea {
|
||||
OLC_LatLon lo;
|
||||
OLC_LatLon hi;
|
||||
size_t len;
|
||||
} OLC_CodeArea;
|
||||
|
||||
// Get the center coordinates for an area
|
||||
void OLC_GetCenter(const OLC_CodeArea* area, OLC_LatLon* center);
|
||||
|
||||
// Get the effective length for a code
|
||||
size_t OLC_CodeLength(const char* code, size_t size);
|
||||
|
||||
// Check for the three obviously-named conditions
|
||||
int OLC_IsValid(const char* code, size_t size);
|
||||
int OLC_IsShort(const char* code, size_t size);
|
||||
int OLC_IsFull(const char* code, size_t size);
|
||||
|
||||
// Encode location with given code length (indicates precision) into an OLC
|
||||
// Return the string length of the code
|
||||
int OLC_Encode(const OLC_LatLon* location, size_t code_length, char* code,
|
||||
int maxlen);
|
||||
|
||||
// Encode location with default code length into an OLC
|
||||
// Return the string length of the code
|
||||
int OLC_EncodeDefault(const OLC_LatLon* location, char* code, int maxlen);
|
||||
|
||||
// Decode OLC into the original location
|
||||
int OLC_Decode(const char* code, size_t size, OLC_CodeArea* decoded);
|
||||
|
||||
// Compute a (shorter) OLC for a given code and a reference location
|
||||
int OLC_Shorten(const char* code, size_t size, const OLC_LatLon* reference,
|
||||
char* buf, int maxlen);
|
||||
|
||||
// Given shorter OLC and reference location, compute original (full length) OLC
|
||||
int OLC_RecoverNearest(const char* short_code, size_t size,
|
||||
const OLC_LatLon* reference, char* code, int maxlen);
|
||||
|
||||
#endif
|
69
lib/main/google/olc/olc_private.h
Normal file
69
lib/main/google/olc/olc_private.h
Normal file
|
@ -0,0 +1,69 @@
|
|||
/*
|
||||
* We place these static definitions on a separate header file so that we can
|
||||
* include the file in both the library and the tests.
|
||||
*/
|
||||
|
||||
#include <ctype.h>
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
#include <memory.h>
|
||||
|
||||
#define OLC_kEncodingBase 20
|
||||
#define OLC_kGridCols 4
|
||||
#define OLC_kLatMaxDegrees 90
|
||||
#define OLC_kLonMaxDegrees 180
|
||||
|
||||
// Separates the first eight digits from the rest of the code.
|
||||
static const char kSeparator = '+';
|
||||
// Used to indicate null values before the separator.
|
||||
static const char kPaddingCharacter = '0';
|
||||
// Digits used in the codes.
|
||||
static const char kAlphabet[] = "23456789CFGHJMPQRVWX";
|
||||
// Number of digits in the alphabet.
|
||||
static const size_t kEncodingBase = OLC_kEncodingBase;
|
||||
// The max number of digits returned in a plus code. Roughly 1 x 0.5 cm.
|
||||
static const size_t kMaximumDigitCount = 15;
|
||||
// The number of code characters that are lat/lng pairs.
|
||||
static const size_t kPairCodeLength = 10;
|
||||
// The number of characters that combine lat and lng into a grid.
|
||||
// kMaximumDigitCount - kPairCodeLength
|
||||
static const size_t kGridCodeLength = 5;
|
||||
// The number of columns in each grid step.
|
||||
static const size_t kGridCols = OLC_kGridCols;
|
||||
// The number of rows in each grid step.
|
||||
static const size_t kGridRows = OLC_kEncodingBase / OLC_kGridCols;
|
||||
// The number of digits before the separator.
|
||||
static const size_t kSeparatorPosition = 8;
|
||||
// Inverse of the precision of the last pair digits (in degrees).
|
||||
static const size_t kPairPrecisionInverse = 8000;
|
||||
// Inverse (1/) of the precision of the final grid digits in degrees.
|
||||
// Latitude is kEncodingBase^3 * kGridRows^kGridCodeLength
|
||||
static const size_t kGridLatPrecisionInverse = 2.5e7;
|
||||
// Longitude is kEncodingBase^3 * kGridColumns^kGridCodeLength
|
||||
static const size_t kGridLonPrecisionInverse = 8.192e6;
|
||||
// Latitude bounds are -kLatMaxDegrees degrees and +kLatMaxDegrees degrees
|
||||
// which we transpose to 0 and 180 degrees.
|
||||
static const double kLatMaxDegrees = OLC_kLatMaxDegrees;
|
||||
static const double kLatMaxDegreesT2 = 2 * OLC_kLatMaxDegrees;
|
||||
|
||||
// Longitude bounds are -kLonMaxDegrees degrees and +kLonMaxDegrees degrees
|
||||
// which we transpose to 0 and 360 degrees.
|
||||
static const double kLonMaxDegrees = OLC_kLonMaxDegrees;
|
||||
static const double kLonMaxDegreesT2 = 2 * OLC_kLonMaxDegrees;
|
||||
|
||||
// Lookup table of the alphabet positions of characters 'C' through 'X',
|
||||
// inclusive. A value of -1 means the character isn't part of the alphabet.
|
||||
static const int kPositionLUT['X' - 'C' + 1] = {
|
||||
8, -1, -1, 9, 10, 11, -1, 12, -1, -1, 13,
|
||||
-1, -1, 14, 15, 16, -1, -1, -1, 17, 18, 19,
|
||||
};
|
||||
|
||||
// Returns the position of a char in the encoding alphabet, or -1 if invalid.
|
||||
static int get_alphabet_position(char c) {
|
||||
char uc = toupper(c);
|
||||
// We use a lookup table for performance reasons.
|
||||
if (uc >= 'C' && uc <= 'X') return kPositionLUT[uc - 'C'];
|
||||
if (uc >= 'c' && uc <= 'x') return kPositionLUT[uc - 'c'];
|
||||
if (uc >= '2' && uc <= '9') return uc - '2';
|
||||
return -1;
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue