Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
GeographicLib::LambertConformalConic Class Reference

Lambert conformal conic projection. More...

#include <LambertConformalConic.hpp>

Public Member Functions

void Forward (real lon0, real lat, real lon, real &x, real &y, real &gamma, real &k) const
 
void Forward (real lon0, real lat, real lon, real &x, real &y) const
 
 LambertConformalConic (real a, real f, real stdlat, real k0)
 
 LambertConformalConic (real a, real f, real stdlat1, real stdlat2, real k1)
 
 LambertConformalConic (real a, real f, real sinlat1, real coslat1, real sinlat2, real coslat2, real k1)
 
void Reverse (real lon0, real x, real y, real &lat, real &lon, real &gamma, real &k) const
 
void Reverse (real lon0, real x, real y, real &lat, real &lon) const
 
void SetScale (real lat, real k=real(1))
 
Inspector functions
Math::real MajorRadius () const
 
Math::real Flattening () const
 
Math::real OriginLatitude () const
 
Math::real CentralScale () const
 

Static Public Member Functions

static const LambertConformalConicMercator ()
 

Private Types

typedef Math::real real
 

Private Member Functions

real Deatanhe (real x, real y) const
 
void Init (real sphi1, real cphi1, real sphi2, real cphi2, real k1)
 

Static Private Member Functions

static real Dasinh (real x, real y, real hx, real hy)
 
static real Dexp (real x, real y)
 
static real Dhyp (real x, real y, real hx, real hy)
 
static real Dlog1p (real x, real y)
 
static real Dsinh (real x, real y, real sx, real sy, real cx, real cy)
 
static real Dsn (real x, real y, real sx, real sy)
 
static real hyp (real x)
 

Private Attributes

real _a
 
real _drhomax
 
real _e2
 
real _es
 
real _f
 
real _fm
 
real _k0
 
real _lat0
 
real _n
 
real _nc
 
real _nrho0
 
real _psi0
 
real _scale
 
real _scbet0
 
real _scchi0
 
real _sign
 
real _t0nm1
 
real _tchi0
 
real ahypover_
 
real eps_
 
real epsx_
 

Static Private Attributes

static const int numit_ = 5
 

Detailed Description

Lambert conformal conic projection.

Implementation taken from the report,

This is a implementation of the equations in Snyder except that divided differences have been used to transform the expressions into ones which may be evaluated accurately and that Newton's method is used to invert the projection. In this implementation, the projection correctly becomes the Mercator projection or the polar stereographic projection when the standard latitude is the equator or a pole. The accuracy of the projections is about 10 nm (10 nanometers).

The ellipsoid parameters, the standard parallels, and the scale on the standard parallels are set in the constructor. Internally, the case with two standard parallels is converted into a single standard parallel, the latitude of tangency (also the latitude of minimum scale), with a scale specified on this parallel. This latitude is also used as the latitude of origin which is returned by LambertConformalConic::OriginLatitude. The scale on the latitude of origin is given by LambertConformalConic::CentralScale. The case with two distinct standard parallels where one is a pole is singular and is disallowed. The central meridian (which is a trivial shift of the longitude) is specified as the lon0 argument of the LambertConformalConic::Forward and LambertConformalConic::Reverse functions.

This class also returns the meridian convergence gamma and scale k. The meridian convergence is the bearing of grid north (the y axis) measured clockwise from true north.

There is no provision in this class for specifying a false easting or false northing or a different latitude of origin. However these are can be simply included by the calling function. For example the Pennsylvania South state coordinate system (EPSG:3364) is obtained by:

// Example of using the GeographicLib::LambertConformalConic class
#include <iostream>
#include <exception>
using namespace std;
using namespace GeographicLib;
int main() {
try {
// Define the Pennsylvania South state coordinate system EPSG:3364
// http://www.spatialreference.org/ref/epsg/3364/
const double
f = 1/298.257222101, // GRS80
lat1 = 40 + 58/60.0, lat2 = 39 + 56/60.0, // standard parallels
k1 = 1, // scale
lat0 = 39 + 20/60.0, lon0 =-77 - 45/60.0, // origin
fe = 600000, fn = 0; // false easting and northing
// Set up basic projection
const LambertConformalConic PASouth(a, f, lat1, lat2, k1);
double x0, y0;
// Transform origin point
PASouth.Forward(lon0, lat0, lon0, x0, y0);
x0 -= fe; y0 -= fn;
{
// Sample conversion from geodetic to PASouth grid
double lat = 39.95, lon = -75.17; // Philadelphia
double x, y;
PASouth.Forward(lon0, lat, lon, x, y);
x -= x0; y -= y0;
cout << x << " " << y << "\n";
}
{
// Sample conversion from PASouth grid to geodetic
double x = 820e3, y = 72e3;
double lat, lon;
x += x0; y += y0;
PASouth.Reverse(lon0, x, y, lat, lon);
cout << lat << " " << lon << "\n";
}
}
catch (const exception& e) {
cerr << "Caught exception: " << e.what() << "\n";
return 1;
}
}

ConicProj is a command-line utility providing access to the functionality of LambertConformalConic and AlbersEqualArea.

Definition at line 63 of file LambertConformalConic.hpp.

Member Typedef Documentation

Definition at line 65 of file LambertConformalConic.hpp.

Constructor & Destructor Documentation

GeographicLib::LambertConformalConic::LambertConformalConic ( real  a,
real  f,
real  stdlat,
real  k0 
)

Constructor with a single standard parallel.

Parameters
[in]aequatorial radius of ellipsoid (meters).
[in]fflattening of ellipsoid. Setting f = 0 gives a sphere. Negative f gives a prolate ellipsoid.
[in]stdlatstandard parallel (degrees), the circle of tangency.
[in]k0scale on the standard parallel.
Exceptions
GeographicErrif a, (1 − f) a, or k0 is not positive.
GeographicErrif stdlat is not in [−90°, 90°].

Definition at line 16 of file src/LambertConformalConic.cpp.

GeographicLib::LambertConformalConic::LambertConformalConic ( real  a,
real  f,
real  stdlat1,
real  stdlat2,
real  k1 
)

Constructor with two standard parallels.

Parameters
[in]aequatorial radius of ellipsoid (meters).
[in]fflattening of ellipsoid. Setting f = 0 gives a sphere. Negative f gives a prolate ellipsoid.
[in]stdlat1first standard parallel (degrees).
[in]stdlat2second standard parallel (degrees).
[in]k1scale on the standard parallels.
Exceptions
GeographicErrif a, (1 − f) a, or k1 is not positive.
GeographicErrif stdlat1 or stdlat2 is not in [−90°, 90°], or if either stdlat1 or stdlat2 is a pole and stdlat1 is not equal stdlat2.

Definition at line 40 of file src/LambertConformalConic.cpp.

GeographicLib::LambertConformalConic::LambertConformalConic ( real  a,
real  f,
real  sinlat1,
real  coslat1,
real  sinlat2,
real  coslat2,
real  k1 
)

Constructor with two standard parallels specified by sines and cosines.

Parameters
[in]aequatorial radius of ellipsoid (meters).
[in]fflattening of ellipsoid. Setting f = 0 gives a sphere. Negative f gives a prolate ellipsoid.
[in]sinlat1sine of first standard parallel.
[in]coslat1cosine of first standard parallel.
[in]sinlat2sine of second standard parallel.
[in]coslat2cosine of second standard parallel.
[in]k1scale on the standard parallels.
Exceptions
GeographicErrif a, (1 − f) a, or k1 is not positive.
GeographicErrif stdlat1 or stdlat2 is not in [−90°, 90°], or if either stdlat1 or stdlat2 is a pole and stdlat1 is not equal stdlat2.

This allows parallels close to the poles to be specified accurately. This routine computes the latitude of origin and the scale at this latitude. In the case where lat1 and lat2 are different, the errors in this routines are as follows: if dlat = abs(lat2lat1) ≤ 160° and max(abs(lat1), abs(lat2)) ≤ 90 − min(0.0002, 2.2 × 10−6(180 − dlat), 6 &times 10−8 dlat2) (in degrees), then the error in the latitude of origin is less than 4.5 × 10−14d and the relative error in the scale is less than 7 × 10−15.

Definition at line 68 of file src/LambertConformalConic.cpp.

Member Function Documentation

Math::real GeographicLib::LambertConformalConic::CentralScale ( ) const
inline
Returns
central scale for the projection. This is the scale on the latitude of origin.

Definition at line 306 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dasinh ( real  x,
real  y,
real  hx,
real  hy 
)
inlinestaticprivate

Definition at line 125 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::Deatanhe ( real  x,
real  y 
) const
inlineprivate

Definition at line 133 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dexp ( real  x,
real  y 
)
inlinestaticprivate

Definition at line 105 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dhyp ( real  x,
real  y,
real  hx,
real  hy 
)
inlinestaticprivate

Definition at line 89 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dlog1p ( real  x,
real  y 
)
inlinestaticprivate

Definition at line 100 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dsinh ( real  x,
real  y,
real  sx,
real  sy,
real  cx,
real  cy 
)
inlinestaticprivate

Definition at line 114 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::Dsn ( real  x,
real  y,
real  sx,
real  sy 
)
inlinestaticprivate

Definition at line 93 of file LambertConformalConic.hpp.

Math::real GeographicLib::LambertConformalConic::Flattening ( ) const
inline
Returns
f the flattening of the ellipsoid. This is the value used in the constructor.

Definition at line 291 of file LambertConformalConic.hpp.

void GeographicLib::LambertConformalConic::Forward ( real  lon0,
real  lat,
real  lon,
real x,
real y,
real gamma,
real k 
) const

Forward projection, from geographic to Lambert conformal conic.

Parameters
[in]lon0central meridian longitude (degrees).
[in]latlatitude of point (degrees).
[in]lonlongitude of point (degrees).
[out]xeasting of point (meters).
[out]ynorthing of point (meters).
[out]gammameridian convergence at point (degrees).
[out]kscale of projection at point.

The latitude origin is given by LambertConformalConic::LatitudeOrigin(). No false easting or northing is added and lat should be in the range [−90°, 90°]. The error in the projection is less than about 10 nm (10 nanometers), true distance, and the errors in the meridian convergence and scale are consistent with this. The values of x and y returned for points which project to infinity (i.e., one or both of the poles) will be large but finite.

Definition at line 331 of file src/LambertConformalConic.cpp.

void GeographicLib::LambertConformalConic::Forward ( real  lon0,
real  lat,
real  lon,
real x,
real y 
) const
inline

LambertConformalConic::Forward without returning the convergence and scale.

Definition at line 262 of file LambertConformalConic.hpp.

static real GeographicLib::LambertConformalConic::hyp ( real  x)
inlinestaticprivate

Definition at line 71 of file LambertConformalConic.hpp.

void GeographicLib::LambertConformalConic::Init ( real  sphi1,
real  cphi1,
real  sphi2,
real  cphi2,
real  k1 
)
private

Definition at line 102 of file src/LambertConformalConic.cpp.

Math::real GeographicLib::LambertConformalConic::MajorRadius ( ) const
inline
Returns
a the equatorial radius of the ellipsoid (meters). This is the value used in the constructor.

Definition at line 285 of file LambertConformalConic.hpp.

const LambertConformalConic & GeographicLib::LambertConformalConic::Mercator ( )
static

A global instantiation of LambertConformalConic with the WGS84 ellipsoid, stdlat = 0, and k0 = 1. This degenerates to the Mercator projection.

Definition at line 324 of file src/LambertConformalConic.cpp.

Math::real GeographicLib::LambertConformalConic::OriginLatitude ( ) const
inline
Returns
latitude of the origin for the projection (degrees).

This is the latitude of minimum scale and equals the stdlat in the 1-parallel constructor and lies between stdlat1 and stdlat2 in the 2-parallel constructors.

Definition at line 300 of file LambertConformalConic.hpp.

void GeographicLib::LambertConformalConic::Reverse ( real  lon0,
real  x,
real  y,
real lat,
real lon,
real gamma,
real k 
) const

Reverse projection, from Lambert conformal conic to geographic.

Parameters
[in]lon0central meridian longitude (degrees).
[in]xeasting of point (meters).
[in]ynorthing of point (meters).
[out]latlatitude of point (degrees).
[out]lonlongitude of point (degrees).
[out]gammameridian convergence at point (degrees).
[out]kscale of projection at point.

The latitude origin is given by LambertConformalConic::LatitudeOrigin(). No false easting or northing is added. The value of lon returned is in the range [−180°, 180°]. The error in the projection is less than about 10 nm (10 nanometers), true distance, and the errors in the meridian convergence and scale are consistent with this.

Definition at line 373 of file src/LambertConformalConic.cpp.

void GeographicLib::LambertConformalConic::Reverse ( real  lon0,
real  x,
real  y,
real lat,
real lon 
) const
inline

LambertConformalConic::Reverse without returning the convergence and scale.

Definition at line 272 of file LambertConformalConic.hpp.

void GeographicLib::LambertConformalConic::SetScale ( real  lat,
real  k = real(1) 
)

Set the scale for the projection.

Parameters
[in]lat(degrees).
[in]kscale at latitude lat (default 1).
Exceptions
GeographicErrk is not positive.
GeographicErrif lat is not in [−90°, 90°].

Definition at line 441 of file src/LambertConformalConic.cpp.

Member Data Documentation

real GeographicLib::LambertConformalConic::_a
private

Definition at line 67 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_drhomax
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_e2
private

Definition at line 67 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_es
private

Definition at line 67 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_f
private

Definition at line 67 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_fm
private

Definition at line 67 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_k0
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_lat0
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_n
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_nc
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_nrho0
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_psi0
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_scale
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_scbet0
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_scchi0
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_sign
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_t0nm1
private

Definition at line 68 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::_tchi0
private

Definition at line 69 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::ahypover_
private

Definition at line 66 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::eps_
private

Definition at line 66 of file LambertConformalConic.hpp.

real GeographicLib::LambertConformalConic::epsx_
private

Definition at line 66 of file LambertConformalConic.hpp.

const int GeographicLib::LambertConformalConic::numit_ = 5
staticprivate

Definition at line 70 of file LambertConformalConic.hpp.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:57:59