geodesy.wu_point
Convenience classes for manipulating way points and their associated Universal Transverse Mercator (UTM) coordinates.
- class geodesy.wu_point.WuPoint(waypt, utm=None)
WuPoint
represents a map way point with associated UTM information.- Parameters:
waypt – geographic_msgs/WayPoint message.
utm – Corresponding
geodesy.utm.UTMPoint
object. If None provided, the utm object will be created.
- str(wu_point)
- Returns:
String representation of
WuPoint
object.
- is2D()
- Returns:
True if no altitude provided.
- position()
- Returns:
Corresponding geographic_msgs/GeoPoint message.
- toPoint()
- Returns:
Corresponding geometry_msgs/Point message.
- toPointXY()
- Returns:
geometry_msgs/Point with X and Y coordinates, and Z coordinate of zero.
- toWayPoint()
- Returns:
Corresponding geographic_msgs/WayPoint message.
- class geodesy.wu_point.WuPointSet(points)
WuPointSet
is a container for the way points in a geographic_msgs/GeographicMap or geographic_msgs/RouteNetwork message. UTM coordinates are available for each way point, but they are evaluated lazily, only when needed.- Parameters:
points – array of geographic_msgs/WayPoint messages
WuPointSet
supports these standard container operations:- len(wu_set)
- Returns:
The number of points in the set.
- wu_set[uuid]
- Returns:
The point with key uuid. Raises a
KeyError
if uuid is not in the set.
- uuid in wu_set
- Returns:
True
if wu_set has a key uuid, elseFalse
.
- uuid not in wu_set
Equivalent to
not uuid in wu_set
.
- iter(wu_set)
- Returns:
An iterator over the points in the set.
These methods are also provided:
- distance2D(idx1, idx2)
Compute 2D Euclidean distance between points.
- Parameters:
idx1 – Index of first point.
idx2 – Index of second point.
- Returns:
Distance in meters within the UTM XY plane. Altitudes are ignored.
- distance3D(idx1, idx2)
Compute 3D Euclidean distance between points.
- Parameters:
idx1 – Index of first point.
idx2 – Index of second point.
- Returns:
Distance in meters between two UTM points, including altitudes.
- get(key, default=None)
Get point, if defined.
- index(key, default=None)
Get index of point, if defined.
- Parameters:
key – UUID of desired point.
default – value to return if no such point.
- Returns:
Index of point, if successful; otherwise default. Beware: the index may be 0, which evaluates False as a predicate, use
is not None
to test for presence.