Stack Proposal

Proposer: Jack O'Quin

Present at review:

  • Chad Rockey
  • Piyush Khandelwal
  • Eric Perko
  • Michael Carroll
  • Tully Foote
  • Ken Tossell
  • William Woodall

This is to define initial APIs for the proposed cartograpy stack.

There is now a git repository with a stack named geographic_info. To make updates, add yourself as a member of the Geographic Information SIG.

ROS Message / Service Types

ROS Message Types ROS Service Types
BoundingBox
GeoPath
GeoPoint
GeoPointStamped
GeoPose
GeoPoseStamped
GeoPoseWithCovariance
GeoPoseWithCovarianceStamped
GeographicMap
GeographicMapChanges
KeyValue
MapFeature
RouteNetwork
RoutePath
RouteSegment
WayPoint
GetGeoPath
GetGeographicMap
GetRoutePlan
UpdateGeographicMap

Question / concerns / comments

Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.

  • (Jack) This stack will contain a cartography_msgs package to support geographic mapping interfaces. See the ROS Message Types section for details.

    • (Eric) I don't think any of those messages are appropriate for geometry_msgs. They don't have any geometric meaning outside of basically WGS84 coordinate space.

    • (Tully) I agree with Eric that they probably shouldn't move into geometry_msgs package, but definitely could be promoted into common_msgs stack. It'll be a lot easier to develop the package in this stack and then promote the package into common_msgs than rename all the messages and their usages.

    • (Jack) I agree about moving the whole package to common_msgs to avoid changing all the references.

  • (Michael) It seems like UTM would be significantly more useful in a lot of waypoint-based navigation applications.

    • (Chad) I'm not sure where to put the UTM support. It's obviously needed for some final navigation purposes (like a wrapper around the nav stack), but if we allowed their use here through a flag, etc., we'd end up with very complicated code.

      • (Eric) I agree that we need to pick one reference frame. I think WGS84 is good enough for the waypoints - especially since the NavSatFix messages use WGS84.

      • (Jack) I've been giving this issue some thought. One idea is to keep lat/long as the canonical format for all the ROS messages, while providing a set of C++ classes for UTM. One advantage of defining non-message C++ classes is that we can define constructors to convert from the message types and methods to convert back. We can't do that directly with the ROS messages, since they need to be transformed into many languages.

    • (Eric) A very important part of this entire stack/repository is to provide tools to convert between these different coordinate systems. UTM would likely be very useful - so providing a tool to convert from UTM-to-WGS84 and back is definitely a must have before we could officially release anything.

      • (Ken T) I think the stack should also include support for further calculation using both WGS 84 and UTM. E.g., float distance(A:GeoPoint, B:GeoPoint, coord:[any|UTM|WGS84]), quaternion direction(A, B, coord) where coord specifies the coordinate system in which the calculation should take place, possibly with a default ('any') option that could either mean UTM or "UTM within a single zone or overlapping zones; otherwise WGS84." Also useful would be "ignore altitude." For even more complication, the stack could offer a "through the earth" version of WGS 84 distance. Does this sound like too much? If so, the relevant namespace could have WGS84distance() and UTMdistance() but no "choose the best way" distance.

    • (Jack) We will provide UTM conversions. This is a translation from Ellipsoidal geometry (GeoPoint) to Euclidean geometry (geometry_msgs/Point). We need to carefully distinguish the two. Using different types should help.

      • (Ken T) I would support a new type (UTMPoint) that encodes northing, easting, altitude and the UTM zone, since Point doesn't have any space to store zone information. "geometry_msgs/Point point; uint8 zone; bool northsouth" (or use the zone letter instead of N/S)

        • (Jack) Sounds good to me. Go ahead an define the message. Would we need a separate UTMPose?

          • (Piyush) I like the idea of having a UTM based pose message. Would it make sense for the (GeoPose) message to contain both (UTMPoint) and (GeoPoint)?

          • (Jack) I added a UTMPose message. It remains to be seen whether we really need those messages.

        • (Chad) I'm hesitant to add another waypoint type. Any code using these to navigate will have to chose one or the other to operate or convert to one standard first anyway while possibly ignoring the other. UTM is a one-to-one conversion with WGS84 right? If there's no ambiguity (besides the poles), we should be careful.

          • (Ken T) They are one-to-one in conversion between valid (Lat, Lon) pairs and (North, East, Zone) triples, but if you leave off the zone, there are many different Lat/Lon pairs that match each Northing/Easting pair.

          • (Jack) Actually, UTM is not defined north on 84 degrees latitude or south of -80 degrees. Universal Polar Stereo (UPS) extends the Cartesian grid system to those areas. The MGRS band letter gives us the option to support both, the polar bands are A, B (South pole), and Y, Z (North pole). Do we need to worry about the poles? Probably the best reason to include UPS is so the transforms between lat/lon and UTM/UPS are one-to-one and onto.

        • (Jack) What I did before was define a message with both the (lat, lon) and UTM coordinates. That was inelegant (since they are redundant), but quite useful.

  • (Ken T) How should the user specify a null value for altitude? NaN was discussed in the e-mail thread but I didn't see a resolution.

    • (Eric) Why not specify as part of the waypoint how close we want the platform to get. These correspond to, for example, the xy_goal_tolerance and yaw_goal_tolerance for base_local_planner. This helps with two issues:

      1. Null for altitude... just set that to 0 and set the constraints to +/- Inf if you really don't care what altitude the robot gets to. Perhaps we could then use NaN as a special value for "maintain current altitude" +/- the constraint values?
      2. Different goal constraints for different waypoints. This will allow us to define waypoints that are like... get within 5 meters of this point vs. get within 5cm of this point. I prefer describing this in the waypoint than as say, parameters to a navigation algorithm.
        • (Ken T) Would you specify the tolerance separately for X, Y, Z? If so, how do you express "within 5 m" without also matching a distance of 5*sqrt(2) or 5*sqrt(3)? (Or does that matter?) Seems like there could be a large number of useful waypoint shapes with very complicated functions to describe them. Would an axis-aligned ellipsoid be general enough to work in most situations?

          • (Eric) I was going for a simple interpretation of constraint here with one constraint per coordinate. I'm not sure I see the "large number of useful waypoint shapes" you mention. I would expect that complicated path shapes could be approximated well with a sequence of waypoints, each with it's own axis-aligned tolerance ellipsoid. I see this being useful - for example, on a road the waypoints may need to have tighter tolerances (and overall path tolerance) than when the vehicle is driving across a desert.

      3. (Tully) I don't think that planning constraints should be encoded in Waypoints. There is a possibility that you want to encode dilution of position information. But the planning tolerance is only valid for communicating plans. Things like a trace of my past path do not want to have to define and record a "planning tolerance" to be able to record a set of waypoints. There are many other use cases for waypoints which are not directly a plan ahead of a vehicle. Also you may have different tolerances for different plans, but they can share the same waypoint.

        • (Jack) I agree completely. A map may define thousands of way-points, while a plan often needs to reference only a few dozen. We could call these plan way-points GoalPoint or CheckPoint. I would like one of these larger messages to contain the tolerances Eric mentions as well as the simple WayPoint.

    • (Chad) I think NaN is fine for undefined/don't care altitudes.

    • (Ken T) What if a robot has no altitude sensors and only knows that it's on the ground?

      • (Chad) I think the use case with only lat and long defined and NaN for altitude would be fine here. We might be able to treat NaN like a wildcard value of constraints. For instance, Lat:X Long:Y Height:NaN could be go to this position and ignore height, this could work for flying vehicles as well. The opposite possibility would be Lat: NaN Long:NaN and Height:N meters corresponding to go to the easiest/any location but make sure you have this height.

        • (Ken T) Not sure if this is ever used, but would there be a case in which you'd want to tell a flying vehicle, "Hover 3 m above the ground at XY"? Or would that kind of request be unusual enough that ground altitude shouldn't be part of a generic waypoint?

    • (Jack) Let's write some code to experiment with the NaN approach, to see how well it works in practice.

  • (Ken T) Will there be any guidance on a process for generating the UUID?

    • (Jack) We should probably have some discussion about it. Mainly, it needs to be unique. There are lots of implementations available in nearly every language. There is a boost::uuid package in C++. I see no reason for us to provide yet another implementation.

  • (Chad) Not sure if this belongs here, but I support git for the version control on our kforge repo. 0+ for Mercurial and 0- for SVN.

    • (Jack) I would already have created the repo had it not been for a limitation of git. Apparently, using git forces us to create a separate repo for each stack. If anyone knows another way to get around this limitation, please let me know right away.

      • (Ken T) Yeah, that's necessary with git, but it's not often a problem. Mainly, it just means that you lose some automatic history if you move a package between stacks, and you'll need to have more lines in your .rosinstall file.

    • (Jack) The Geographic Information project now exists on kforge. The stack and git repository are named geographic_info, and the package is geographic_msgs.

  • (Chad) We also need to define names for the repository, stacks, and packages.

    • (Chad) I think the repo should be called "geographic_information". Stretching "information" to cover waypoints isn't difficult, since it's still information. :P

    • (Chad) Cartography still suggests making maps to me. Maybe we could call this stack geo_msgs with waypoint_msgs as the package?

      • (Eric) I agree that cartography sounds like making maps. Heck... Wikipedia defines Cartography as "the study and practice of making maps"... I don't think we are doing that... yet :)

    • (Jack) If we are using git, we don't need a repository name, each stack will have its own name. I have no problem renaming cartography to geographic_information, and renaming the cartography_msgs package to geography_msgs. I like the brevity of geo_msgs, but some might confuse it with geometry_msgs. I expect these messages to have larger scope than just way-points.

  • (Jack) We need to define the orientation of a GeoPose properly. I don't completely understand the math, but intuition suggests that there are serious issues around the poles. Even a normal orientation pointing from one GeoPoint to another is probably not completely clear without discussion of tangent planes, etc. Can we finesse this whole issue by converting the points to UTM and defining the pose in terms of the relevant zone?

    • (Piyush) I see that the GeoPose message has been created. Was this issue around the pole?

    • (Jack) We need an unambiguous mathematical definition of the orientation quaternion. Even apart from the poles there are several possible interpretations. Does the GeoPose to another GeoPoint go through the earth? Follow a great circle route? How are different altitudes handled? The more I think about this, the less I understand what it means.

    • (Jack) I propose that GeoPose be defined in terms of great circle headings. For most robotics, that is probably overkill. Even for vehicles navigating very long paths, the great circle route is problematic because the heading changes continuously. It may be more practical to achieve such paths as a sequence of rhumb line headings. That can probably be done by making each segment short enough to use a UTM heading with sufficient accuracy.

    • (Jack) Since great circle geometry is essentially two-dimensional within the sphere or ellipsoid, how should we define GeoPose in three dimensions? One choice is a horizontal coordinate system, with each altitude defining its own ellipsoid.

    • (Jack) Much as I like quaternions, they are wrong for GeoPose orientation. They work great for 3D Euclidean space, but lat/lon is not Euclidean. So, what should we use? There seem to be various conventions. I'd like to stick with the ENU frame of reference for consistency (although I realize aerospace prefers NED). How about roll, pitch and yaw in the local ENU frame?

      • (Chad) We can still use quaternions defined in a tangential ENU frame correct?

      • (Jack) I think so. Latitude and longitude are in degrees, while altitude is in meters. It's not a clean fit. What advantages do quaternions offer for GeoPose?

        • (Eric) I'd think whatever they normally offer over roll-pitch-yaw - no gimbal lock, used throughout ROS (and libraries like Bullet or Eigen), etc.

  • (Jack) I moved the message definitions to the actual repository. We can access them via the wiki API page.

  • (Jack) I also defined a UTMPoint message. In addition to the UTM zone number, it has an extra field for the Military Grid Reference System latitude band. This is not strictly necessary, but can be useful for some applications. If the band letter is blank, the location is still well-defined by easting, northing and zone.

  • (Jack) Seems like we should create a utm_tools package. Once we agree on the name, we can add it to the git repo. I suspect we also need another package for purely lat/lon geometry functions. What should that be called?

    • (Chad) utm_tools sounds just fine to me. Maybe we could call the other package lat_long_tools, although it seems a bit clunky. If only conversion tools end up in utm_tools, maybe we could just merge both into coordinate_tools, conversion_tools, geography_tools, etc.?

    • (Jack) A separate utm_tools is good if there are some Geographic Navigation users who do not need it. I don't know if that is the case, but it seems likely.

    • (Eric) I like the idea of a conversion_tools package that provides libraries and nodes for converting between different coordinate systems. I don't see a need for separate utm_tools and lat_long_tools packages - if we can provide essentially seamless conversion between the two representations, I don't think we need explicit packages for tools that work with UTM vs tools that work with lat/long.

      • (Jack) How about coordinate_conversions? I don't suppose that package will be so large as to become a problem for those needing only some types.

    • (Jack) I've mostly been thinking in terms of C++ functions for these tools, but Python implementations would also be valuable.

    • (William) This has pretty much been done for us, the Proj.4 library provides exhaustive conversions from any projection and map datum to any other. I have personally used its Python bindings pyproj to convert back and forth from UTM to LatLong. I would think we only need to provide a wrapper for some convenience. I would love to help when implementation time comes along for these tools. Here is an example of converting from UTM2LatLong in Python: utm.py.

      • (Jack) Thanks, that looks like an excellent reference.

    • (Jack) I propose geodesy as the name of the coordinate transforms package. Geodesy includes transforms between the geoid (a sophisticated representation of "sea level") and various reference ellipsiods, like WGS-84. Defining latitude and longitude for messages in terms of WGS-84 makes sense, but we should also include transforms between that and UTM, as well as other ellipsoids, like NAD-83. Other geodesy functions include determining the coordinates of a point from another point plus direction and distance; and the inverse problem of determining direction and distance between two points (tricky to define, not generally unique).

  • (Chad) Okay, so this discussion has gotten very large. I think we should wrap these topics up and move the ones that still need work to the mailing list.

    • (Jack) I personally prefer a mailing list for detailed discussions. The wiki is too awkward. I think this is too detailed for ros-users, however. There is already a geographicinfo-devel mailing list on kforge, we could use that.

      • (Eric) Agreed. Jack, perhaps you can summarize some of the issues still on this wikipage and update the conclusions section. Afterwards, we can declare the review "complete" and refer further discussion to the geographicinfo-devel mailing list.

Meeting agenda

This discussion has gotten lengthy due to the level of detail. There is general agreement on how to proceed. Further issues will be resolved on the geographicinfo-devel mailing list and with experimental code in the git repository.

Conclusion

  • /!\ Call the basic stack geographic_info.

  • /!\ Call the messages package geographic_msgs.

  • /!\ Use a NaN value for altitude when it is not specified.

  • /!\ Delete UTMPoint and UTMPose ROS messages. Messages should always use GeoPoint and GeoPose, with conversion to UTM via the geodesy/utm.h C++ header functions and classes.

  • {X} Should GeoPose use a quaternion? If so, how is it defined? If not, what orientation should it use?


Wiki: geographic_info/Reviews/2011-06-18_Proposal (last edited 2013-05-13 16:08:51 by JackOQuin)