|
51 | 51 | #include <stdio.h> |
52 | 52 | #include <stdlib.h> |
53 | 53 |
|
| 54 | +#include <GeographicLib/MGRS.hpp> |
| 55 | +#include <GeographicLib/UTMUPS.hpp> |
| 56 | + |
54 | 57 | #include <cmath> |
55 | 58 | #include <string> |
56 | 59 |
|
@@ -140,276 +143,74 @@ static inline void UTM(double lat, double lon, double * x, double * y) |
140 | 143 | } |
141 | 144 |
|
142 | 145 | /** |
143 | | - * Determine the correct UTM letter designator for the |
144 | | - * given latitude |
145 | | - * |
146 | | - * @returns 'Z' if latitude is outside the UTM limits of 84N to 80S |
147 | | - * |
148 | | - * Written by Chuck Gantz- [email protected] |
149 | | - */ |
150 | | -static inline char UTMLetterDesignator(double Lat) |
151 | | -{ |
152 | | - char LetterDesignator; |
153 | | - |
154 | | - if ((84 >= Lat) && (Lat >= 72)) { |
155 | | - LetterDesignator = 'X'; |
156 | | - } else if ((72 > Lat) && (Lat >= 64)) { |
157 | | - LetterDesignator = 'W'; |
158 | | - } else if ((64 > Lat) && (Lat >= 56)) { |
159 | | - LetterDesignator = 'V'; |
160 | | - } else if ((56 > Lat) && (Lat >= 48)) { |
161 | | - LetterDesignator = 'U'; |
162 | | - } else if ((48 > Lat) && (Lat >= 40)) { |
163 | | - LetterDesignator = 'T'; |
164 | | - } else if ((40 > Lat) && (Lat >= 32)) { |
165 | | - LetterDesignator = 'S'; |
166 | | - } else if ((32 > Lat) && (Lat >= 24)) { |
167 | | - LetterDesignator = 'R'; |
168 | | - } else if ((24 > Lat) && (Lat >= 16)) { |
169 | | - LetterDesignator = 'Q'; |
170 | | - } else if ((16 > Lat) && (Lat >= 8)) { |
171 | | - LetterDesignator = 'P'; |
172 | | - } else if ((8 > Lat) && (Lat >= 0)) { |
173 | | - LetterDesignator = 'N'; |
174 | | - } else if ((0 > Lat) && (Lat >= -8)) { |
175 | | - LetterDesignator = 'M'; |
176 | | - } else if ((-8 > Lat) && (Lat >= -16)) { |
177 | | - LetterDesignator = 'L'; |
178 | | - } else if ((-16 > Lat) && (Lat >= -24)) { |
179 | | - LetterDesignator = 'K'; |
180 | | - } else if ((-24 > Lat) && (Lat >= -32)) { |
181 | | - LetterDesignator = 'J'; |
182 | | - } else if ((-32 > Lat) && (Lat >= -40)) { |
183 | | - LetterDesignator = 'H'; |
184 | | - } else if ((-40 > Lat) && (Lat >= -48)) { |
185 | | - LetterDesignator = 'G'; |
186 | | - } else if ((-48 > Lat) && (Lat >= -56)) { |
187 | | - LetterDesignator = 'F'; |
188 | | - } else if ((-56 > Lat) && (Lat >= -64)) { |
189 | | - LetterDesignator = 'E'; |
190 | | - } else if ((-64 > Lat) && (Lat >= -72)) { |
191 | | - LetterDesignator = 'D'; |
192 | | - } else if ((-72 > Lat) && (Lat >= -80)) { |
193 | | - LetterDesignator = 'C'; |
194 | | - } else { |
195 | | - // 'Z' is an error flag, the Latitude is outside the UTM limits |
196 | | - LetterDesignator = 'Z'; |
197 | | - } |
198 | | - return LetterDesignator; |
199 | | -} |
200 | | - |
201 | | -/** |
202 | | - * Convert lat/long to UTM coords. Equations from USGS Bulletin 1532 |
| 146 | + * Convert lat/long to UTM coords. |
203 | 147 | * |
204 | 148 | * East Longitudes are positive, West longitudes are negative. |
205 | 149 | * North latitudes are positive, South latitudes are negative |
206 | 150 | * Lat and Long are in fractional degrees |
207 | | - * Meridian convergence is computed as for Spherical Transverse Mercator, |
208 | | - * which gives quite good approximation. |
209 | 151 | * |
210 | 152 | * @param[out] gamma meridian convergence at point (degrees). |
211 | | - * |
212 | | - * Written by Chuck Gantz- [email protected] |
213 | 153 | */ |
214 | 154 | static inline void LLtoUTM( |
215 | 155 | const double Lat, const double Long, |
216 | 156 | double & UTMNorthing, double & UTMEasting, |
217 | 157 | std::string & UTMZone, double & gamma) |
218 | 158 | { |
219 | | - double a = WGS84_A; |
220 | | - double eccSquared = UTM_E2; |
221 | | - double k0 = UTM_K0; |
222 | | - |
223 | | - double LongOrigin; |
224 | | - double eccPrimeSquared; |
225 | | - double N, T, C, A, M; |
226 | | - |
227 | | - // Make sure the longitude is between -180.00 .. 179.9 |
228 | | - double LongTemp = |
229 | | - (Long + 180) - static_cast<int>((Long + 180) / 360) * 360 - 180; |
230 | | - |
231 | | - double LatRad = Lat * RADIANS_PER_DEGREE; |
232 | | - double LongRad = LongTemp * RADIANS_PER_DEGREE; |
233 | | - double LongOriginRad; |
234 | | - int ZoneNumber; |
235 | | - |
236 | | - ZoneNumber = static_cast<int>((LongTemp + 180) / 6) + 1; |
237 | | - |
238 | | - if (Lat >= 56.0 && Lat < 64.0 && LongTemp >= 3.0 && LongTemp < 12.0) { |
239 | | - ZoneNumber = 32; |
240 | | - } |
241 | | - |
242 | | - // Special zones for Svalbard |
243 | | - if (Lat >= 72.0 && Lat < 84.0) { |
244 | | - if (LongTemp >= 0.0 && LongTemp < 9.0) { |
245 | | - ZoneNumber = 31; |
246 | | - } else if (LongTemp >= 9.0 && LongTemp < 21.0) { |
247 | | - ZoneNumber = 33; |
248 | | - } else if (LongTemp >= 21.0 && LongTemp < 33.0) { |
249 | | - ZoneNumber = 35; |
250 | | - } else if (LongTemp >= 33.0 && LongTemp < 42.0) { |
251 | | - ZoneNumber = 37; |
252 | | - } |
253 | | - } |
254 | | - // +3 puts origin in middle of zone |
255 | | - LongOrigin = (ZoneNumber - 1) * 6 - 180 + 3; |
256 | | - LongOriginRad = LongOrigin * RADIANS_PER_DEGREE; |
257 | | - |
258 | | - // Compute the UTM Zone from the latitude and longitude |
259 | | - char zone_buf[] = {0, 0, 0, 0}; |
260 | | - // We &0x3fU to let GCC know the size of ZoneNumber. In this case, it's under |
261 | | - // 63 (6bits) |
262 | | - snprintf( |
263 | | - zone_buf, sizeof(zone_buf), "%d%c", ZoneNumber & 0x3fU, |
264 | | - UTMLetterDesignator(Lat)); |
265 | | - UTMZone = std::string(zone_buf); |
266 | | - |
267 | | - eccPrimeSquared = (eccSquared) / (1 - eccSquared); |
268 | | - |
269 | | - N = a / sqrt(1 - eccSquared * sin(LatRad) * sin(LatRad)); |
270 | | - T = tan(LatRad) * tan(LatRad); |
271 | | - C = eccPrimeSquared * cos(LatRad) * cos(LatRad); |
272 | | - A = cos(LatRad) * (LongRad - LongOriginRad); |
273 | | - |
274 | | - M = a * |
275 | | - ((1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 - |
276 | | - 5 * eccSquared * eccSquared * eccSquared / 256) * |
277 | | - LatRad - |
278 | | - (3 * eccSquared / 8 + 3 * eccSquared * eccSquared / 32 + |
279 | | - 45 * eccSquared * eccSquared * eccSquared / 1024) * |
280 | | - sin(2 * LatRad) + |
281 | | - (15 * eccSquared * eccSquared / 256 + |
282 | | - 45 * eccSquared * eccSquared * eccSquared / 1024) * |
283 | | - sin(4 * LatRad) - |
284 | | - (35 * eccSquared * eccSquared * eccSquared / 3072) * sin(6 * LatRad)); |
285 | | - |
286 | | - UTMEasting = static_cast<double>( |
287 | | - k0 * N * |
288 | | - (A + (1 - T + C) * A * A * A / 6 + |
289 | | - (5 - 18 * T + T * T + 72 * C - 58 * eccPrimeSquared) * A * A * A * |
290 | | - A * A / 120) + |
291 | | - 500000.0); |
292 | | - |
293 | | - UTMNorthing = static_cast<double>( |
294 | | - k0 * |
295 | | - (M + N * tan(LatRad) * |
296 | | - (A * A / 2 + (5 - T + 9 * C + 4 * C * C) * A * A * A * A / 24 + |
297 | | - (61 - 58 * T + T * T + 600 * C - 330 * eccPrimeSquared) * A * |
298 | | - A * A * A * A * A / 720))); |
299 | | - |
300 | | - gamma = atan(tan(LongRad - LongOriginRad) * sin(LatRad)) * DEGREES_PER_RADIAN; |
301 | | - |
302 | | - if (Lat < 0) { |
303 | | - // 10000000 meter offset for southern hemisphere |
304 | | - UTMNorthing += 10000000.0; |
305 | | - } |
| 159 | + int zone; |
| 160 | + bool northp; |
| 161 | + double k_unused; |
| 162 | + GeographicLib::UTMUPS::Forward( |
| 163 | + Lat, Long, zone, northp, UTMEasting, UTMNorthing, gamma, |
| 164 | + k_unused, GeographicLib::UTMUPS::zonespec::MATCH); |
| 165 | + GeographicLib::MGRS::Forward(zone, northp, UTMEasting, UTMNorthing, -1, UTMZone); |
306 | 166 | } |
307 | 167 |
|
308 | 168 | /** |
309 | | - * Convert lat/long to UTM coords. Equations from USGS Bulletin 1532 |
| 169 | + * Convert lat/long to UTM coords. |
310 | 170 | * |
311 | 171 | * East Longitudes are positive, West longitudes are negative. |
312 | 172 | * North latitudes are positive, South latitudes are negative |
313 | 173 | * Lat and Long are in fractional degrees |
314 | | - * |
315 | | - * Written by Chuck Gantz- [email protected] |
316 | 174 | */ |
317 | 175 | static inline void LLtoUTM( |
318 | 176 | const double Lat, const double Long, |
319 | 177 | double & UTMNorthing, double & UTMEasting, |
320 | 178 | std::string & UTMZone) |
321 | 179 | { |
322 | | - double gamma; |
| 180 | + double gamma = 0.0; |
323 | 181 | LLtoUTM(Lat, Long, UTMNorthing, UTMEasting, UTMZone, gamma); |
324 | 182 | } |
325 | 183 |
|
326 | 184 | /** |
327 | | - * Converts UTM coords to lat/long. Equations from USGS Bulletin 1532 |
| 185 | + * Converts UTM coords to lat/long. |
328 | 186 | * |
329 | 187 | * East Longitudes are positive, West longitudes are negative. |
330 | 188 | * North latitudes are positive, South latitudes are negative |
331 | 189 | * Lat and Long are in fractional degrees. |
332 | | - * Meridian convergence is computed as for Spherical Transverse Mercator, |
333 | | - * which gives quite good approximation. |
334 | 190 | * |
335 | 191 | * @param[out] gamma meridian convergence at point (degrees). |
336 | | - * |
337 | | - * Written by Chuck Gantz- [email protected] |
338 | 192 | */ |
339 | 193 | static inline void UTMtoLL( |
340 | 194 | const double UTMNorthing, const double UTMEasting, |
341 | 195 | const std::string & UTMZone, double & Lat, |
342 | 196 | double & Long, double & gamma) |
343 | 197 | { |
344 | | - double k0 = UTM_K0; |
345 | | - double a = WGS84_A; |
346 | | - double eccSquared = UTM_E2; |
347 | | - double eccPrimeSquared; |
348 | | - double e1 = (1 - sqrt(1 - eccSquared)) / (1 + sqrt(1 - eccSquared)); |
349 | | - double N1, T1, C1, R1, D, M; |
350 | | - double LongOrigin; |
351 | | - double mu, phi1Rad; |
352 | | - double x, y; |
353 | | - int ZoneNumber; |
354 | | - char * ZoneLetter; |
355 | | - |
356 | | - x = UTMEasting - 500000.0; // remove 500,000 meter offset for longitude |
357 | | - y = UTMNorthing; |
358 | | - |
359 | | - ZoneNumber = strtoul(UTMZone.c_str(), &ZoneLetter, 10); |
360 | | - if ((*ZoneLetter - 'N') < 0) { |
361 | | - // remove 10,000,000 meter offset used for southern hemisphere |
362 | | - y -= 10000000.0; |
363 | | - } |
364 | | - |
365 | | - // +3 puts origin in middle of zone |
366 | | - LongOrigin = (ZoneNumber - 1) * 6 - 180 + 3; |
367 | | - eccPrimeSquared = (eccSquared) / (1 - eccSquared); |
368 | | - |
369 | | - M = y / k0; |
370 | | - mu = M / (a * (1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 - |
371 | | - 5 * eccSquared * eccSquared * eccSquared / 256)); |
372 | | - |
373 | | - phi1Rad = |
374 | | - mu + ((3 * e1 / 2 - 27 * e1 * e1 * e1 / 32) * sin(2 * mu) + |
375 | | - (21 * e1 * e1 / 16 - 55 * e1 * e1 * e1 * e1 / 32) * sin(4 * mu) + |
376 | | - (151 * e1 * e1 * e1 / 96) * sin(6 * mu)); |
377 | | - |
378 | | - N1 = a / sqrt(1 - eccSquared * sin(phi1Rad) * sin(phi1Rad)); |
379 | | - T1 = tan(phi1Rad) * tan(phi1Rad); |
380 | | - C1 = eccPrimeSquared * cos(phi1Rad) * cos(phi1Rad); |
381 | | - R1 = a * (1 - eccSquared) / |
382 | | - pow(1 - eccSquared * sin(phi1Rad) * sin(phi1Rad), 1.5); |
383 | | - D = x / (N1 * k0); |
384 | | - |
385 | | - Lat = phi1Rad - ((N1 * tan(phi1Rad) / R1) * |
386 | | - (D * D / 2 - |
387 | | - (5 + 3 * T1 + 10 * C1 - 4 * C1 * C1 - 9 * eccPrimeSquared) * |
388 | | - D * D * D * D / 24 + |
389 | | - (61 + 90 * T1 + 298 * C1 + 45 * T1 * T1 - |
390 | | - 252 * eccPrimeSquared - 3 * C1 * C1) * |
391 | | - D * D * D * D * D * D / 720)); |
392 | | - |
393 | | - Lat = Lat * DEGREES_PER_RADIAN; |
394 | | - |
395 | | - Long = ((D - (1 + 2 * T1 + C1) * D * D * D / 6 + |
396 | | - (5 - 2 * C1 + 28 * T1 - 3 * C1 * C1 + 8 * eccPrimeSquared + |
397 | | - 24 * T1 * T1) * |
398 | | - D * D * D * D * D / 120) / |
399 | | - cos(phi1Rad)); |
400 | | - Long = LongOrigin + Long * DEGREES_PER_RADIAN; |
401 | | - |
402 | | - gamma = atan(tanh(x / (k0 * a)) * tan(y / (k0 * a))) * DEGREES_PER_RADIAN; |
| 198 | + int zone; |
| 199 | + bool northp; |
| 200 | + double x_unused; |
| 201 | + double y_unused; |
| 202 | + int prec_unused; |
| 203 | + double k_unused; |
| 204 | + GeographicLib::MGRS::Reverse(UTMZone, zone, northp, x_unused, y_unused, prec_unused, true); |
| 205 | + GeographicLib::UTMUPS::Reverse(zone, northp, UTMEasting, UTMNorthing, Lat, Long, gamma, k_unused); |
403 | 206 | } |
404 | 207 |
|
405 | 208 | /** |
406 | | -* Converts UTM coords to lat/long. Equations from USGS Bulletin 1532 |
| 209 | +* Converts UTM coords to lat/long. |
407 | 210 | * |
408 | 211 | * East Longitudes are positive, West longitudes are negative. |
409 | 212 | * North latitudes are positive, South latitudes are negative |
410 | 213 | * Lat and Long are in fractional degrees. |
411 | | -* |
412 | | -* Written by Chuck Gantz- [email protected] |
413 | 214 | */ |
414 | 215 | static inline void UTMtoLL( |
415 | 216 | const double UTMNorthing, const double UTMEasting, |
|
0 commit comments