Skip to content

Commit d0ad5c3

Browse files
authored
Utm using geographiclib ros2 branch (#833)
* Add single test for navsat_conversions * Add a southern point to the navsat_transform test * LLtoUTM using GeographicLib * Use GeographicLib for UTMtoLL conversions * Linting * Forgot include * Fix compilation * Calculate gamma because it's a function output and was supplied before * Also test for gamma conversion * Align naming and install
1 parent ea976f9 commit d0ad5c3

File tree

3 files changed

+100
-222
lines changed

3 files changed

+100
-222
lines changed

CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -287,6 +287,10 @@ if(BUILD_TESTING)
287287
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
288288
)
289289

290+
#### NAVSAT CONVERSION TESTS ####
291+
ament_add_gtest(test_navsat_conversions test/test_navsat_conversions.cpp)
292+
target_link_libraries(test_navsat_conversions ${library_name})
293+
290294
ament_add_gtest_executable(test_ros_robot_localization_listener
291295
test/test_ros_robot_localization_listener.cpp)
292296
target_link_libraries(test_ros_robot_localization_listener ${library_name})
@@ -321,6 +325,7 @@ if(BUILD_TESTING)
321325
#test_ekf_localization_node_bag2
322326
#test_ekf_localization_node_bag3
323327
test_robot_localization_estimator
328+
test_navsat_conversions
324329
test_ros_robot_localization_listener
325330
test_ros_robot_localization_listener_publisher
326331
#test_ukf_localization_node_bag1

include/robot_localization/navsat_conversions.hpp

Lines changed: 23 additions & 222 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,9 @@
5050
#include <stdio.h>
5151
#include <stdlib.h>
5252

53+
#include <GeographicLib/MGRS.hpp>
54+
#include <GeographicLib/UTMUPS.hpp>
55+
5356
#include <cmath>
5457
#include <string>
5558

@@ -139,276 +142,74 @@ static inline void UTM(double lat, double lon, double * x, double * y)
139142
}
140143

141144
/**
142-
* Determine the correct UTM letter designator for the
143-
* given latitude
144-
*
145-
* @returns 'Z' if latitude is outside the UTM limits of 84N to 80S
146-
*
147-
* Written by Chuck Gantz- [email protected]
148-
*/
149-
static inline char UTMLetterDesignator(double Lat)
150-
{
151-
char LetterDesignator;
152-
153-
if ((84 >= Lat) && (Lat >= 72)) {
154-
LetterDesignator = 'X';
155-
} else if ((72 > Lat) && (Lat >= 64)) {
156-
LetterDesignator = 'W';
157-
} else if ((64 > Lat) && (Lat >= 56)) {
158-
LetterDesignator = 'V';
159-
} else if ((56 > Lat) && (Lat >= 48)) {
160-
LetterDesignator = 'U';
161-
} else if ((48 > Lat) && (Lat >= 40)) {
162-
LetterDesignator = 'T';
163-
} else if ((40 > Lat) && (Lat >= 32)) {
164-
LetterDesignator = 'S';
165-
} else if ((32 > Lat) && (Lat >= 24)) {
166-
LetterDesignator = 'R';
167-
} else if ((24 > Lat) && (Lat >= 16)) {
168-
LetterDesignator = 'Q';
169-
} else if ((16 > Lat) && (Lat >= 8)) {
170-
LetterDesignator = 'P';
171-
} else if ((8 > Lat) && (Lat >= 0)) {
172-
LetterDesignator = 'N';
173-
} else if ((0 > Lat) && (Lat >= -8)) {
174-
LetterDesignator = 'M';
175-
} else if ((-8 > Lat) && (Lat >= -16)) {
176-
LetterDesignator = 'L';
177-
} else if ((-16 > Lat) && (Lat >= -24)) {
178-
LetterDesignator = 'K';
179-
} else if ((-24 > Lat) && (Lat >= -32)) {
180-
LetterDesignator = 'J';
181-
} else if ((-32 > Lat) && (Lat >= -40)) {
182-
LetterDesignator = 'H';
183-
} else if ((-40 > Lat) && (Lat >= -48)) {
184-
LetterDesignator = 'G';
185-
} else if ((-48 > Lat) && (Lat >= -56)) {
186-
LetterDesignator = 'F';
187-
} else if ((-56 > Lat) && (Lat >= -64)) {
188-
LetterDesignator = 'E';
189-
} else if ((-64 > Lat) && (Lat >= -72)) {
190-
LetterDesignator = 'D';
191-
} else if ((-72 > Lat) && (Lat >= -80)) {
192-
LetterDesignator = 'C';
193-
} else {
194-
// 'Z' is an error flag, the Latitude is outside the UTM limits
195-
LetterDesignator = 'Z';
196-
}
197-
return LetterDesignator;
198-
}
199-
200-
/**
201-
* Convert lat/long to UTM coords. Equations from USGS Bulletin 1532
145+
* Convert lat/long to UTM coords.
202146
*
203147
* East Longitudes are positive, West longitudes are negative.
204148
* North latitudes are positive, South latitudes are negative
205149
* Lat and Long are in fractional degrees
206-
* Meridian convergence is computed as for Spherical Transverse Mercator,
207-
* which gives quite good approximation.
208150
*
209151
* @param[out] gamma meridian convergence at point (degrees).
210-
*
211-
* Written by Chuck Gantz- [email protected]
212152
*/
213153
static inline void LLtoUTM(
214154
const double Lat, const double Long,
215155
double & UTMNorthing, double & UTMEasting,
216156
std::string & UTMZone, double & gamma)
217157
{
218-
double a = WGS84_A;
219-
double eccSquared = UTM_E2;
220-
double k0 = UTM_K0;
221-
222-
double LongOrigin;
223-
double eccPrimeSquared;
224-
double N, T, C, A, M;
225-
226-
// Make sure the longitude is between -180.00 .. 179.9
227-
double LongTemp =
228-
(Long + 180) - static_cast<int>((Long + 180) / 360) * 360 - 180;
229-
230-
double LatRad = Lat * RADIANS_PER_DEGREE;
231-
double LongRad = LongTemp * RADIANS_PER_DEGREE;
232-
double LongOriginRad;
233-
int ZoneNumber;
234-
235-
ZoneNumber = static_cast<int>((LongTemp + 180) / 6) + 1;
236-
237-
if (Lat >= 56.0 && Lat < 64.0 && LongTemp >= 3.0 && LongTemp < 12.0) {
238-
ZoneNumber = 32;
239-
}
240-
241-
// Special zones for Svalbard
242-
if (Lat >= 72.0 && Lat < 84.0) {
243-
if (LongTemp >= 0.0 && LongTemp < 9.0) {
244-
ZoneNumber = 31;
245-
} else if (LongTemp >= 9.0 && LongTemp < 21.0) {
246-
ZoneNumber = 33;
247-
} else if (LongTemp >= 21.0 && LongTemp < 33.0) {
248-
ZoneNumber = 35;
249-
} else if (LongTemp >= 33.0 && LongTemp < 42.0) {
250-
ZoneNumber = 37;
251-
}
252-
}
253-
// +3 puts origin in middle of zone
254-
LongOrigin = (ZoneNumber - 1) * 6 - 180 + 3;
255-
LongOriginRad = LongOrigin * RADIANS_PER_DEGREE;
256-
257-
// Compute the UTM Zone from the latitude and longitude
258-
char zone_buf[] = {0, 0, 0, 0};
259-
// We &0x3fU to let GCC know the size of ZoneNumber. In this case, it's under
260-
// 63 (6bits)
261-
snprintf(
262-
zone_buf, sizeof(zone_buf), "%d%c", ZoneNumber & 0x3fU,
263-
UTMLetterDesignator(Lat));
264-
UTMZone = std::string(zone_buf);
265-
266-
eccPrimeSquared = (eccSquared) / (1 - eccSquared);
267-
268-
N = a / sqrt(1 - eccSquared * sin(LatRad) * sin(LatRad));
269-
T = tan(LatRad) * tan(LatRad);
270-
C = eccPrimeSquared * cos(LatRad) * cos(LatRad);
271-
A = cos(LatRad) * (LongRad - LongOriginRad);
272-
273-
M = a *
274-
((1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 -
275-
5 * eccSquared * eccSquared * eccSquared / 256) *
276-
LatRad -
277-
(3 * eccSquared / 8 + 3 * eccSquared * eccSquared / 32 +
278-
45 * eccSquared * eccSquared * eccSquared / 1024) *
279-
sin(2 * LatRad) +
280-
(15 * eccSquared * eccSquared / 256 +
281-
45 * eccSquared * eccSquared * eccSquared / 1024) *
282-
sin(4 * LatRad) -
283-
(35 * eccSquared * eccSquared * eccSquared / 3072) * sin(6 * LatRad));
284-
285-
UTMEasting = static_cast<double>(
286-
k0 * N *
287-
(A + (1 - T + C) * A * A * A / 6 +
288-
(5 - 18 * T + T * T + 72 * C - 58 * eccPrimeSquared) * A * A * A *
289-
A * A / 120) +
290-
500000.0);
291-
292-
UTMNorthing = static_cast<double>(
293-
k0 *
294-
(M + N * tan(LatRad) *
295-
(A * A / 2 + (5 - T + 9 * C + 4 * C * C) * A * A * A * A / 24 +
296-
(61 - 58 * T + T * T + 600 * C - 330 * eccPrimeSquared) * A *
297-
A * A * A * A * A / 720)));
298-
299-
gamma = atan(tan(LongRad - LongOriginRad) * sin(LatRad)) * DEGREES_PER_RADIAN;
300-
301-
if (Lat < 0) {
302-
// 10000000 meter offset for southern hemisphere
303-
UTMNorthing += 10000000.0;
304-
}
158+
int zone;
159+
bool northp;
160+
double k_unused;
161+
GeographicLib::UTMUPS::Forward(
162+
Lat, Long, zone, northp, UTMEasting, UTMNorthing, gamma,
163+
k_unused, GeographicLib::UTMUPS::zonespec::MATCH);
164+
GeographicLib::MGRS::Forward(zone, northp, UTMEasting, UTMNorthing, -1, UTMZone);
305165
}
306166

307167
/**
308-
* Convert lat/long to UTM coords. Equations from USGS Bulletin 1532
168+
* Convert lat/long to UTM coords.
309169
*
310170
* East Longitudes are positive, West longitudes are negative.
311171
* North latitudes are positive, South latitudes are negative
312172
* Lat and Long are in fractional degrees
313-
*
314-
* Written by Chuck Gantz- [email protected]
315173
*/
316174
static inline void LLtoUTM(
317175
const double Lat, const double Long,
318176
double & UTMNorthing, double & UTMEasting,
319177
std::string & UTMZone)
320178
{
321-
double gamma;
179+
double gamma = 0.0;
322180
LLtoUTM(Lat, Long, UTMNorthing, UTMEasting, UTMZone, gamma);
323181
}
324182

325183
/**
326-
* Converts UTM coords to lat/long. Equations from USGS Bulletin 1532
184+
* Converts UTM coords to lat/long.
327185
*
328186
* East Longitudes are positive, West longitudes are negative.
329187
* North latitudes are positive, South latitudes are negative
330188
* Lat and Long are in fractional degrees.
331-
* Meridian convergence is computed as for Spherical Transverse Mercator,
332-
* which gives quite good approximation.
333189
*
334190
* @param[out] gamma meridian convergence at point (degrees).
335-
*
336-
* Written by Chuck Gantz- [email protected]
337191
*/
338192
static inline void UTMtoLL(
339193
const double UTMNorthing, const double UTMEasting,
340194
const std::string & UTMZone, double & Lat,
341195
double & Long, double & gamma)
342196
{
343-
double k0 = UTM_K0;
344-
double a = WGS84_A;
345-
double eccSquared = UTM_E2;
346-
double eccPrimeSquared;
347-
double e1 = (1 - sqrt(1 - eccSquared)) / (1 + sqrt(1 - eccSquared));
348-
double N1, T1, C1, R1, D, M;
349-
double LongOrigin;
350-
double mu, phi1Rad;
351-
double x, y;
352-
int ZoneNumber;
353-
char * ZoneLetter;
354-
355-
x = UTMEasting - 500000.0; // remove 500,000 meter offset for longitude
356-
y = UTMNorthing;
357-
358-
ZoneNumber = strtoul(UTMZone.c_str(), &ZoneLetter, 10);
359-
if ((*ZoneLetter - 'N') < 0) {
360-
// remove 10,000,000 meter offset used for southern hemisphere
361-
y -= 10000000.0;
362-
}
363-
364-
// +3 puts origin in middle of zone
365-
LongOrigin = (ZoneNumber - 1) * 6 - 180 + 3;
366-
eccPrimeSquared = (eccSquared) / (1 - eccSquared);
367-
368-
M = y / k0;
369-
mu = M / (a * (1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 -
370-
5 * eccSquared * eccSquared * eccSquared / 256));
371-
372-
phi1Rad =
373-
mu + ((3 * e1 / 2 - 27 * e1 * e1 * e1 / 32) * sin(2 * mu) +
374-
(21 * e1 * e1 / 16 - 55 * e1 * e1 * e1 * e1 / 32) * sin(4 * mu) +
375-
(151 * e1 * e1 * e1 / 96) * sin(6 * mu));
376-
377-
N1 = a / sqrt(1 - eccSquared * sin(phi1Rad) * sin(phi1Rad));
378-
T1 = tan(phi1Rad) * tan(phi1Rad);
379-
C1 = eccPrimeSquared * cos(phi1Rad) * cos(phi1Rad);
380-
R1 = a * (1 - eccSquared) /
381-
pow(1 - eccSquared * sin(phi1Rad) * sin(phi1Rad), 1.5);
382-
D = x / (N1 * k0);
383-
384-
Lat = phi1Rad - ((N1 * tan(phi1Rad) / R1) *
385-
(D * D / 2 -
386-
(5 + 3 * T1 + 10 * C1 - 4 * C1 * C1 - 9 * eccPrimeSquared) *
387-
D * D * D * D / 24 +
388-
(61 + 90 * T1 + 298 * C1 + 45 * T1 * T1 -
389-
252 * eccPrimeSquared - 3 * C1 * C1) *
390-
D * D * D * D * D * D / 720));
391-
392-
Lat = Lat * DEGREES_PER_RADIAN;
393-
394-
Long = ((D - (1 + 2 * T1 + C1) * D * D * D / 6 +
395-
(5 - 2 * C1 + 28 * T1 - 3 * C1 * C1 + 8 * eccPrimeSquared +
396-
24 * T1 * T1) *
397-
D * D * D * D * D / 120) /
398-
cos(phi1Rad));
399-
Long = LongOrigin + Long * DEGREES_PER_RADIAN;
400-
401-
gamma = atan(tanh(x / (k0 * a)) * tan(y / (k0 * a))) * DEGREES_PER_RADIAN;
197+
int zone;
198+
bool northp;
199+
double x_unused;
200+
double y_unused;
201+
int prec_unused;
202+
double k_unused;
203+
GeographicLib::MGRS::Reverse(UTMZone, zone, northp, x_unused, y_unused, prec_unused, true);
204+
GeographicLib::UTMUPS::Reverse(zone, northp, UTMEasting, UTMNorthing, Lat, Long, gamma, k_unused);
402205
}
403206

404207
/**
405-
* Converts UTM coords to lat/long. Equations from USGS Bulletin 1532
208+
* Converts UTM coords to lat/long.
406209
*
407210
* East Longitudes are positive, West longitudes are negative.
408211
* North latitudes are positive, South latitudes are negative
409212
* Lat and Long are in fractional degrees.
410-
*
411-
* Written by Chuck Gantz- [email protected]
412213
*/
413214
static inline void UTMtoLL(
414215
const double UTMNorthing, const double UTMEasting,

test/test_navsat_conversions.cpp

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
/*
2+
* Copyright (c) 2021, Charles River Analytics, Inc.
3+
* All rights reserved.
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions
7+
* are met:
8+
*
9+
* 1. Redistributions of source code must retain the above copyright
10+
* notice, this list of conditions and the following disclaimer.
11+
* 2. Redistributions in binary form must reproduce the above
12+
* copyright notice, this list of conditions and the following
13+
* disclaimer in the documentation and/or other materials provided
14+
* with the distribution.
15+
* 3. Neither the name of the copyright holder nor the names of its
16+
* contributors may be used to endorse or promote products derived
17+
* from this software without specific prior written permission.
18+
*
19+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23+
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
* POSSIBILITY OF SUCH DAMAGE.
31+
*/
32+
33+
#include <gtest/gtest.h>
34+
35+
#include <string>
36+
37+
#include "robot_localization/navsat_conversions.hpp"
38+
39+
void NavsatConversionsTest(
40+
const double lat, const double lon,
41+
const double UTMNorthing, const double UTMEasting,
42+
const std::string UTMZone, const double gamma)
43+
{
44+
double UTMNorthing_new;
45+
double UTMEasting_new;
46+
std::string UTMZone_new;
47+
double gamma_new;
48+
robot_localization::navsat_conversions::LLtoUTM(
49+
lat, lon, UTMNorthing_new, UTMEasting_new, UTMZone_new, gamma_new);
50+
EXPECT_NEAR(UTMNorthing, UTMNorthing_new, 1e-2);
51+
EXPECT_NEAR(UTMEasting, UTMEasting_new, 1e-2);
52+
EXPECT_EQ(UTMZone, UTMZone_new);
53+
EXPECT_NEAR(gamma, gamma_new, 1e-2);
54+
double lat_new;
55+
double lon_new;
56+
robot_localization::navsat_conversions::UTMtoLL(
57+
UTMNorthing, UTMEasting, UTMZone, lat_new, lon_new);
58+
EXPECT_NEAR(lat_new, lat, 1e-5);
59+
EXPECT_NEAR(lon_new, lon, 1e-5);
60+
}
61+
62+
TEST(NavsatConversionsTest, UtmTest)
63+
{
64+
NavsatConversionsTest(51.423964, 5.494271, 5699924.709, 673409.989, "31U", 1.950);
65+
NavsatConversionsTest(-43.530955, 172.636645, 5178919.718, 632246.802, "59G", -1.127);
66+
}
67+
68+
int main(int argc, char ** argv)
69+
{
70+
testing::InitGoogleTest(&argc, argv);
71+
return RUN_ALL_TESTS();
72+
}

0 commit comments

Comments
 (0)