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)[source]

WuPoint represents a map way point with associated UTM information.

Parameters:
str(wu_point)
Returns:String representation of WuPoint object.
is2D()[source]
Returns:True if no altitude provided.
position()[source]
Returns:Corresponding geographic_msgs/GeoPoint message.
toPoint()[source]
Returns:Corresponding geometry_msgs/Point message.
toPointXY()[source]
Returns:geometry_msgs/Point with X and Y coordinates, and Z coordinate of zero.
toWayPoint()[source]
Returns:Corresponding geographic_msgs/WayPoint message.
uuid()[source]
Returns:UUID of way point.
class geodesy.wu_point.WuPointSet(points)[source]

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, else False.
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)[source]

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)[source]

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)[source]

Get point, if defined.

Parameters:
  • keyUUID of desired point.
  • default – value to return if no such point.
Returns:

Named WuPoint, if successful; otherwise default.

index(key, default=None)[source]

Get index of point, if defined.

Parameters:
  • keyUUID 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.

next()[source]

Next iteration point.

Returns:Next WuPoint.
Raises:StopIteration when finished.

Previous topic

geodesy.utm

Next topic

Change history

This Page