geodesy.utm

Universal Transverse Mercator coordinate module.

todo:add Universal Polar Stereographic (UPS) support
class geodesy.utm.UTMPoint(easting=nan, northing=nan, altitude=nan, zone=0, band=' ')[source]

Universal Transverse Mercator (UTM) point class.

For outdoor robotics applications, Euclidean projections like UTM are easier to work with than latitude and longitude. This system is slightly more general than strict UTM. It is based on the Military Grid Reference System (MGRS), which can be extended to cover the poles, allowing well-defined transformations for every latitude and longitude.

This implementation uses the pyproj wrapper for the PROJ.4 Cartographic Projections Library.

Parameters:
  • easting – UTM easting (meters)
  • northing – UTM northing (meters)
  • altitude – altitude above the WGS84 ellipsoid (meters), none if NaN.
  • zone – UTM longitude zone
  • band – MGRS latitude band letter
gridZone()[source]
Returns:(zone, band) tuple.
is2D()[source]
Returns:True if altitude is not defined.
toMsg()[source]
Returns:corresponding geographic_msgs/GeoPoint message.
Todo:clamp message longitude to [-180..180]
toPoint()[source]
Returns:corresponding geometry_msgs/Point message.
Todo:clamp message longitude to [-180..180]
valid()[source]
Returns:True if this is a valid UTM point.
geodesy.utm.fromLatLong(latitude, longitude, altitude=nan)[source]

Generate UTMPoint from latitude, longitude and (optional) altitude.

Latitude and longitude are expressed in degrees, relative to the WGS84 ellipsoid.

Parameters:
  • latitude – [degrees], negative is South.
  • longitude – [degrees], negative is West.
  • altitude – [meters], negative is below the ellipsoid.
Returns:

UTMPoint object.

geodesy.utm.fromMsg(msg)[source]
Parameters:msggeographic_msgs/GeoPoint message.
Returns:UTMPoint object.
geodesy.utm.gridZone(lat, lon)[source]

Find UTM zone and MGRS band for latitude and longitude.

Parameters:
  • lat – latitude in degrees, negative is South.
  • lon – longitude in degrees, negative is West.
Returns:

(zone, band) tuple.

Raises:

ValueError if lon not in [-180..180] or if lat has no corresponding band letter.

Todo:

handle polar (UPS) zones: A, B, Y, Z.