API review
Proposer: Bill Morris
Reviewers:
- Ken Tossell
- Jack O'Quin
- Chad Rockey
- Eric Perko
- Rene Wagner
- Mike Sokolsky
- Tully Foote
Contents
Overview
There is a growing need for a standard GPS message. This will allow for the development of inter-operable navigation algorithms and ground station control systems.
Status Basic
Proposed Basic Status
- STATUS_AGPS_FIX for fake cellular GPS?
uint16 satellites_visible uint16 STATUS_NO_FIX=0 # Unable to fix position uint16 STATUS_FIX=1 # Normal fix uint16 STATUS_DGPS_FIX=3 # Fixed with DGPS uint16 STATUS_WAAS_FIX=5 # Fixed with WAAS uint16 status
Status Advanced
UMD/gpsd
Header header # Satellites used in solution uint16 satellites_used # Number of satellites int32[] satellite_used_prn # PRN identifiers\ # Satellites visible uint16 satellites_visible int32[] satellite_visible_prn # PRN identifiers int32[] satellite_visible_z # Elevation of satellites int32[] satellite_visible_azimuth # Azimuth of satellites int32[] satellite_visible_snr # Signal-to-noise ratios (dB) # Measurement status uint16 STATUS_NO_FIX=0 # Unable to fix position uint16 STATUS_FIX=1 # Normal fix uint16 STATUS_DGPS_FIX=3 # Fixed with DGPS uint16 STATUS_WAAS_FIX=5 # Fixed with WAAS uint16 status uint16 SOURCE_NONE=0 # No information is available uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_sourc e] uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive point s uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect uint16 SOURCE_ALTIMETER=8 # Using an altimeter uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors uint16 SOURCE_GYRO=32 # Using gyroscopes uint16 SOURCE_ACCEL=64 # Using accelerometers uint16 motion_source # Source for speed, climb and track uint16 orientation_source # Source for device orientation uint16 position_source # Source for position
Position
The position returned by the GPS
- heading/elevation/bank angles vs. dip, pitch, roll
UMD/gpsd
Header header # Latitude (degrees). Positive is north of equator; negative is south. float64 latitude # Longitude (degrees). Positive is east of prime meridian, negative south. float64 longitude # Altitude (meters). Positive is above reference (e.g., sea level). float64 altitude # Direction (degrees from north) float64 track # Ground speed (meters/second) float64 speed # Vertical speed (meters/second) float64 climb # Device orientation (units in degrees) float64 pitch float64 roll float64 dip # GPS time float64 time # Total (positional-temporal) dilution of precision float64 gdop # Positional (3D) dilution of precision float64 pdop # Horizontal dilution of precision float64 hdop # Vertical dilution of precision float64 vdop # Temporal dilution of precision float64 tdop # Spherical position uncertainty (meters) [epe] float64 err # Horizontal position uncertainty (meters) [eph] float64 err_horz # Vertical position uncertainty (meters) [epv] float64 err_vert # Track uncertainty (degrees) [epd] float64 err_track # Ground speed uncertainty (meters/second) [eps] float64 err_speed # Vertical speed uncertainty (meters/second) [epc] float64 err_climb # Temporal uncertainty [ept] float64 err_time # Orientation uncertainty (degrees) float64 err_pitch float64 err_roll float64 err_dip
Question / concerns / comments
(Mike) Jack invited my input on this, just so others don't think I'm coming in completely out of the blue
(Jack) Most of the units (except latitude and longitude) should conform to the ROS units standard, REP 103. Latitude and longitude should clearly remain in fractional degrees, as is standard for GPS. But, I think angles should be in radians (or perhaps use a quaternion). Time should use the ROS time class.
(Chad) I don't think a proper GPS topic should really output orientation. I do agree with lat/long in degrees and height/standard deviations in degrees as opposed to dilution of precision.
(Jack) To get this done in time for the Diamondback release, we're going to need to focus the discussion. I am personally interested in defining some common mapping messages (landmarks, way-points, etc.), if possible. But, we're going to need a concrete proposal rather quickly for those to be ready in time for Diamondback. Unless, there's a strong consensus, that will probably have to be postponed until the next release.
(Chad) I think we should probably hold off. I'm not sure if there is an immediate need for waypoints to be broadcast in GPS coordinates. Do we have any motion planners that will easily accept these without conversion to meters?
(Jack) I just added a preliminary conclusion that we should continue the mapping work separately from this GPS API. If anyone objects, please speak up.
(Chad) A standard GPS message should really only contain values relating to the satellites, the lat/long/height, and the standard deviations (hopefully in meters). Adding in psuedo orientations, speeds, headings, gyros, etc encroaches on other already defined topics such as IMU, Odom, and Twist. These values can also be of poor quality and GPS manufacturers may not all implement the calculations of these values the same way.
(Mike) Sorry, I'm having trouble getting bullets to do what I want. I completely agree with restricting the message to position information, including track may or may not be a good idea, but roll/pitch etc... shouldn't be there unless you want to throw in all possible relevent information, IMU, DMI, etc...
(Eric) I've put together what I believe to be the minimum useful definition for a GPS message. Any other data that was in the GPSd messages could either go on a separate topic using an existing message type such as Twist or Quaternion (though orientation likely needs a QuaternionStampedWithCovariance to be really useful). They are as follows: sensor_msgs/GPSFix.msg
# Specified in WGS84 # # If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the GPS receiver, just put those along the diagonal) # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the data a covariance will have to be assumed or gotten from some other source Header header sensor_msgs/GPSStatus status # Position information # Latitude [degrees]. Positive is north of equator; negative is south. float64 latitude # Longitude [degrees]. Positive is east of prime meridian; negative is west. float64 longitude # Altitude [m]. Positive is above reference ellipsoid float64 altitude # Position covariance [m^2] float64[9] position_covariance # Row major about latitude, longitude, altitude
- sensor_msgs/GPSStatus.msg
# Note that you whether to output a DGPS fix is not only determined by both the fix type and the last time DGPS corrections were received. For example, if the last time a good set of corrections were received was more than, say, 15 seconds ago, you should fall back to a standard fix. A similar rule should apply for WAAS. # A fix is valid if the status field is >= 0 int8 STATUS_NO_FIX = -1 # Unable to fix position int8 STATUS_FIX = 0 # Normal fix int8 STATUS_SBAS_FIX = 1 # Fixed with some sort of SBAS (e.g. WAAS) int8 STATUS_DGPS_FIX = 2 # Fixed with DGPS int8 status
(Rene) A few comments:
- I like the fact that the GPSFix.msg includes the status field.
- The reference for the altitude field should be uniquely and well defined (as opposed to the "e.g."). I believe this should probably be the reference ellipsoid.
(Eric) Good point. Looks like WGS84 uses the ellipsoid but the ubiquitous NMEA uses average sea level. There is a conversion between them. I updated the above message to reflect the exact reference.
- Similarly, what is the exact definition of the position_covariance field, i.e. what is the assumed probability distribution? Getting this right is somewhat tricky: The position is given in lat/lon/alt which means that (ignoring altitude) you're on the surface of the ellipsoid but AFAIK there's no well defined, standard probability density function for this coordinate system. Given the unit of m^2 I guess you actually mean some sort of local, Cartesian coordinate system, say with the tangential plane as the x-y-plane, but in any case I think this needs more thought and a clear definition/specification.
(Eric) Ummm, Gaussian as usual? There is an assumption here that the variance is in some local frame. If your variance is actually large enough that the ellipsoid shape matters, I doubt your position fix is of much use to me. In all seriousness, it could use a more clear definition and spec. I like using the covariance like that as it can hold both the error information on just the lat/long/alt or it can hold the full covariance if there is a Kalman Filter doing the estimation of lat/long/alt that is being output. 3 error fields would lose the ability to send out the full covariance.
(Rene) [Background: No matter how far from the mean, a Gaussian approaches, but never reaches zero. On an ellipsoid surface the Gaussian would wrap around infinitely. There are workarounds but none of them are pretty.] I agree with the use of a covariance matrix and we seem to agree that the coordinate system this lives in must be local. Now we need a definition. Does the tangential plane plus z-up approach I outlined above sound viable? Is this compatible with how receivers typically output internal covariance matrices?
- I disagree with dropping the DOP fields. Many receivers don't output covariance information, only DOP. Converting from DOP to covariance info in this case is problematic since one wouldn't be able to differentiate this from the true covariance of the position estimate. So, I guess we need both.
(Eric) Since DOP doesn't have a clear meaning outside of the GPS driver world, I think covariance is more useful. For example, can we use DOP if I wanted to feed GPS fixes into a robot position estimation EKF that also handled an IMU, wheel odometry, etc? I think covariance is much more usable to other algorithms and the driver should be in charge of converting from whatever the receiver says (either DOP, covariance or both) into one good guess at the actual covariance and then output that.
(Rene) Covariance is more useful. The point is: It isn't always available. Consumer grade receivers (to the best of my knowledge) only output DOP. As for conversion from DOP to covariance, these are qualitatively different: DOP is computed solely from the geometrical configuration (as seen by the receiver) of the satellites used in the positioning solution. So, it's merely a lower bound on the expected error but doesn't necessarily reflect the magnitude of the actual error. On the other hand, I would expect a covariance matrix to reflect the precision of the actual position estimate. Long story short: There appears to be consensus that pseudo values/guesswork are undesirable (orientation from consecutive positioning solutions, etc.), yet a conversion from DOP to covariance would add another such pseudo value.
(Eric) Actually, I don't think covariance would be some pseudo value. Any driver that runs some sort of statistical filter on the raw data will be able to provide some sort of covariance information. The pseudo values we were talking about above were things that a position fix can't tell you directly; for example, in order to calculate a heading you must find the vector between two or more position fixes since 1 single fix can't tell you that. I suppose it is true that covariance is going to depend on multiple fixes as well if, for example, the driver is using a Kalman Filter. One problem I have with DOP is that I don't see a use for it outside a GPS driver or filter. For example, how would you fuse a GPS fix with DOP values with odometry data with covariance on it? DOP is just saying that, in the best case, your error could be this tiny in the best case but it could also be larger, correct? I think the idea was to let the driver handle DOP and whatever else however they want and then just generate a covariance, as that is a pretty generic way of representing error.
(Rene) It is clearly not possible to recover covariance from position output since this has already been low-pass filtered by the receiver-internal filter/process model. The only viable approach I can think of would be based on raw pseudo-ranges and end up re-calculating the positioning solution. Of course this is purely hypothetical since virtually all consumer grade receivers do not provide access to pseudo ranges. You get the positioning solution in WGS84 or ECEF and DOP and that's pretty much it. Now there are three options: a) Forward position/DOP as is and leave the covariance empty because there's no meaningful way to calculate it. b) Specify how to calculate covariance from DOP and add a flag to indicate it is fake rather than true covariance. c) State that consumer grade GPS receivers will not be supported by standard ROS GPS infrastructure.
(Eric) So, say we include DOP and only have a driver set the covariance if it gets that data directly from a high-end receiver. How would another node use a position fix with DOP information? I think a compelling use for GPS right now is outdoor localization and I'm unsure how I would combine a GPS fix without covariance info with other sensors such as an IMU or Odometry. Ideas? Also, is DOP completely system agnostic or will the meaning of say, a DOP of 2, change between GLONASS and GPS?
(Eric) As mentioned above, the idea was that, at some point, we were going to need covariance information assigned to the fix information in order to actually use it. In my opinion, the best place to do that would be the driver itself as that gives the people working most closely with the hardware the chance to figure out the best way to calculate covariance for their particular piece of hardware depending on whether it outputs pseudoranges, low-pass filtered fixes w/ DOP, etc.
(Rene) As the deadline approaches... How about if we go with option b) above, i.e., have the driver do the conversion to a covariance matrix but flag it as COVARIANCE_FROM_DOP (as opposed to, say, ESTIMATED_COVARIANCE in the usual case)? That way we would use a generic representation but avoid implying a level of quality that isn't there. Additionally, I would add the requirement that drivers document how exactly they calculate the covariance matrix (so we don't have to specify it as part of this standardization effort) and that any input which goes into those equations be included in logged ROS topics (using standardized messages if applicable, driver-specific ones otherwise) to make sure that we don't accidentally lose information. Does that sound like a plan that people can live with?
(Jack) Good idea.
(Chad) Localization filters will be at the mercy of the covariance matrix either way, so if they are forced to use it, then is there a point in specifying the covariance source? Are there applications that will specifically decide to NOT use a COVARIANCE_FROM_DOP?
(Rene) The filter may want to deliberately reduce the expected precision, say by multiplying with a "degrading factor" that depends on other sensors. A strategy that in my experience works quite well is to check whether the robot is stationary, moves approximately along a straight line, or turns based on odometry and apply different degrading factors in each of these cases. A GPS Kalman filter that processes pseudo-ranges would figure out on its own that the precision of its position estimate differs in each of these situations while DOP calculations ignore motion of the receiver. The idea is then, simply, to emulate motion induced influences on the covariance matrix. Note that this is a very application specific heuristic and that odometry is just one possible source of sensor data that may be used for it.
(Chad) I found a source here that claims you can use DOP to multiply the expected optimal measurement accuracy of your GPS: http://www.pobonline.com/Articles/Column/f785817cac0f6010VgnVCM100000f932a8c0____ "As an example, let’s say the measurement accuracy is 1 meter. If DOP is 1, then the positioning accuracy is 1 meter. What happens when the DOP is 5? The best positioning accuracy is 5 meters." So it looks like we can take the optimal case (DGPS, WAAS, Omnistar, etc) covariance matrix and multiply that by DOP^2. So this could still be done by the driver.
- Satellite info isn't optional either. In practice I've found it crucial to check how many satellites where used in a position solution and what their geometric configuration was before incorporating this as a valid solution. I would suggest a separate sensor_msgs/GPSSatellite.msg:
int32 prn # PRN identifier int32 z # elevation int32 azimuth int32 snr # signal-to-noise ratio (dB)
- and two additional fields in GPSStatus
GPSSatellite gps_satellites_used GPSSatellite gps_satellites_visible_but_unused
(Eric) I agree with the need to check satellites. However, I think this is really a driver level thing and not something that an algorithm that wants to use GPS needs to know. Can you even deal with it in a receiver-independent manner (ie do all receivers see the same number or ratio of satellites to be good or bad?)? The idea was that the driver is the only one that needs to know this and can set the status field accordingly instead of just passing along whatever the receiver says. This way, all that a processing algorithm actually needs to do is check the status field to know if the fix is good or not; the driver has used all available information to make the best guess at the status. In this case, only the driver needs to be aware of the satellites used vs visible and, therefore, they don't need to be broadcast out on a sensor_msgs/GPSFix message.
(Rene) The physics involved are the same irrespective of the receiver. A status field makes the situation look either clearly "black" or "white", I'm interested in different shades of gray. If covariance info is available this is less of an issue, but that isn't always available (see above).
- Finally, WAAS is only available in North America. So, this either needs to be SBAS (satellite based augmentation system) to cover any system of this kind or we need another option for the European EGNOS (and others if any). Also, I wonder if it might be worth making GPSStatus.status a bit field to allow for the combination of multiple options.
(Eric) I agree regarding the naming of WAAS and changed it in my message definitions
(Eric) What would be the point of making it a combination of multiple options? Is there more that would be useful to encode there besides whether a fix is good or bad (that would be whether or not the status is negative) and then what type of fix?
(Mike) I was also a little surprised at the WAAS/DGPS labels. For us there has definitely been utility in knowing the state of multiple options, we've used the Omnistar service in addition to a VHF RTK correction. If we lose Omnistar things are very bad, but RTK frequently drops out and it's nice to know when that happens. For an algorithm operating on generic input, however, it might be useful to know there's more precision expected than a standard GPS fix but most information should come from the covariance in the Position message. If you leave open generic fix bits ( DGPS1_FIX DGPS2_FIX DGPS3_FIX DGPS4_FIX), processing algorithms could just look at the OR of the fields to see if there's additional correction or not, and leave it up to implementations to locally use them for some other meaning, if needed. That seems like a good comprimise for the variety of systems using multiple satellite and/or ground-based DGPS signals.
(Eric) My problem with just generic fix bits is that we haven't said how they should be interpreted (by virtue of being generic). My rationale for the fix type bits is not to tell some algorithm what exactly we are using for generating the fix, but to give an easy way to make sure that there is probably enough precision. For example, if we know we need cm standard deviations on GPS when processing, all we need to do is check for STATUS_DGPS_FIX as opposed to checking the covariance matrix components. Perhaps those would be better renamed to reflect some assumed level of precision such as STATUS_LOW_PRECISION, STATUS_MEDIUM_PRECISION, STATUS_HIGH_PRECISION, etc. The question is: should a processing algorithm (such as navigation) care about exactly which method you are using for correction or just that you are using some method that ought to give the necessary level of precision (regular vs DPGS fixes for example) and then check the covariance for exactly the precision? Should we provide those generic bits in an advanced status message used for displaying low level GPS info or is knowing whether there is Omnistar or VHF RTK useful for a navigation algorithm?
(Mike) In theory I like the LOW/MEDIUM/HIGH designation, but in practice what do they mean? Just because you're receiving a certain correction signal doesn't mean you end up with a given precision depending on the environment. It seems to be a source-agnostic algorithm will just depend on covariance information if available, so I was more concerned with reporting for system status and display, so this might be more appropriate in the proposed message a couple comments down for display/logging/diagnostics. Then all this would require was FIX/NO_FIX.
(Rene) I agree with pseudo orientations/speeds being problematic. If, however, Doppler observables are actually measured by the receiver I want to know about that.
(Eric) What are some examples of these Doppler observables? And would they make sense in other existing message types or do they make more sense getting put into a GPSFix?
(Rene) The idea is to measure the Doppler effect on the GPS radio signals. This requires carrier phase tracking and is only precise at higher velocities, but if available provides a 3D velocity vector. The interesting thing is that it is unaffected by atmospheric effects and thus precise even if SBAS/DGPS are unavailable.
(Jack) I like the GPSFix message Eric posted. I agree that it should convert device-dependent data into a generic form suitable for navigation nodes.
(Mike) I'm also pretty happy with the smaller message GPSFix.
(Jack) I am beginning to think there could also be a separate detailed status message, not for navigation but for user displays, logging in bag files, etc. Perhaps most of the desire for detailed satellite information could be satisfied with that.
(Eric) I was thinking that having a driver dependent diagnostic messages (using standard ROS diagnostics stuff) might work for this, but if we want a GPS status GUI we would need to have a specific format for the information. As long as it is a separate message only used for visualization/diagnostics, I'm fine with a detailed status message. My only thought is that it should not be used by any non-visualization or diagnostic nodes. For example, if you are a navigation node and must listen to the advanced status field to know if a fix is good, then the driver has a bug and should be patched so that STATUS_FIX is only set if the fix is good.
(Jack) That was my intention as well.
(Rene) Assuming the data we are talking about is both well-defined and driver/receiver-independent (such as satellite info), what harm does it do if we include it in the GPSStatus message? We could have generic display and analysis nodes (which was one of the original stated goals on the mailing list thread) and one wouldn't need to match between messages from different topics just to get at some extra info. I am not saying every consumer of GPSFix/GPSStatus has to process all data included but I think it should be available. We should also consider cases where a third-party provides the GPS driver node: I certainly wouldn't want to deal with vendor specific data types just to get at standard diagnostics.
(Eric) One part of it was to cut down on extra data transfer/work in the driver node. If we only need those extra fields for GUIs and diagnostics, we shouldn't have to send data for them when we aren't running a GUI or diagnostics. A second part was, as mentioned above, to prevent people from using diagnostics data while actually processing fixes outside of the driver level.
(Rene) Diagnostics are particularly important in post-mortem analysis. I.e., the driver will need to send these extra fields via ROS messages anyway to make sure they are logged so that you can later answer questions like "Where there really so few satellites visible or why was the position so imprecise?". You really want as much information as possible if things have gone wrong. Currently, I'm a little worried we will end up with a standardized GPS message that's dumbed down so much that it's only useful with very specific (high-end) receivers under very specific (best-case) circumstances.
(Jack) I'd like to consider recommendations for the Header field. The header.stamp should be GPS time as reported by the device if possible, otherwise system time when the driver received it. What header.frame_id should we recommend? Perhaps something like /WGS84 or /wgs84?
(Eric) Wouldn't having a recommended header.frame_id get confusing if we had multiple GPS's on a robot? I'm wondering why we want to recommend one at all - do we anticipate a processing node using that data for anything besides information like "here is how my GPS sensor is mounted relative to base_link"?
(Jack) Good point. I hadn't thought about that, because our (expensive) GPS provides data already calibrated to the vehicle's frame of reference. I guess the frame of the position fix would be a better recommendation. The WGS-84 frame is understood by the message definition. I was imagining that some devices might use NADS instead, which they could report that way. As long as we require the driver to convert to WGS-84, that should not be necessary.
(Eric) Ya, as discussed on the ros-users thread I think we need to pick one good GPS frame to keep all of the standard ROS messages in. It's going to be tricky if a navigation node needs to handle multiple datums and ellipsoids properly vs stating "all standard ROS GPS messages will be in WGS-84". Now, I'm not really familiar with GPS datums beyond here's a Lat/Long and how you get the distance between two GPS points, so if there would be a better one to standardize on, we should discuss that before the review ends.
(Eric) Should we had a separate GPS time to the GPSFix message? I'd think header.stamp should represent the time that the message was first received by some ROS node (whether a driver or a GPSd -> GPSFix node). Do we have any guarantees on how close GPS time and robot system time should be? If not, having that header be GPS time could definitely screw up tf and anything that assumed it needs data that is x old. For example, if GPS time and ROS time get desynced, the data could be very new in ROS time, but we wouldn't use it due to the offset between GPS time and ROS time.
(Jack) You are right that system time and GPS time will not generally be synchronized. Does that mean the clients will need to run a phase-locked loop to convert between the two? Perhaps that would better be done in the driver.
(Eric) I think that whatever happens should be done at the driver level. I can't see a navigation node wanting to handle the difference between ROS time and GPS time. Perhaps GPS time would be a good field to add to that status_advanced packet? Seems like a reasonable thing for doing diagnostics. Also, with the amount of stuff that should probably happen at a driver level, perhaps we should put together a list of things that it might make sense to put into some sort of GPSDriver base class so that, for example, there is a standard GPS to ROS time conversion as opposed to every driver writer doing it themselves.
(Jack) Yep. Juggling clock drift in the navigation layer would be a disaster. So, it's got to be handled in the driver. I don't see much point in having a separate time stamp for when the driver published the message. Who cares? The important time was when the fix was valid. I've been lazy about that in my Applanix driver, just publishing the time when the driver received the data packet, since I did not want to bother with clock synchronization issues. I think I understand how it's done, but have never written a PLL and might not get it right the first try. As you suggest, we should provide a general time synchronizer package for all GPS drivers to use. That would be generally useful, anyway. For the detailed status message, it might be worth providing the original unsynchronized GPS time. But, I don't see why a navigation client would need that.
(Mike) It seems to me that the GPS time itself is a pretty useful field, there are plenty of applications for just GPS time for stationary devices. I'd almost prefer to see the raw time available in the GPSFix message for this reason. If it's supposed to purely be a navigation message than definitely time in one of the status messages. For positioning, we've definitely been bitten at times by taking the message publication time of a pose rather than the GPS time. I will definitely agree on the utility of having a common GPS<->system time conversion, although that can get a little hairy to do well.
(Eric) The message should be applicable to a stationary system as well, but honestly, isn't the point of GPS to tell you where you are? And you don't really need to be told where you are if you never move :). I don't think you would get bitten by the message publication time if you only updated it whenever you got a new fix vs. updating the timestamp at some fixed period regardless of whether you got a new fix value.
(Mike) Timing is a very big part of GPS, I realize that most frequently in mobile robotics it's used for localization, but I've worked with a lot of fixed devices that have GPS antennas purely for timing information. Even with mobile applications if you have more than one platform GPS is an easy and accurate way to syncronize them. I'd consider the raw GPS time just as fundamental as lat/lon information. I agree that a general localization/navigation algorithm shouldn't have to care about system/gps time syncronization, but that doesn't seem like a good reason to exclude time from the main GPS packet. There are many different ways to handle a system with multiple time references, and I'm completely for providing some useful default tools for projects that don't want to worry about it, but it would also be nice to keep things simple for people who do want to manage timing in some other way. For a high-end receiver, i.e. Novatel/Applanix and the like, they can provide updated coordinates at far faster than the gps fix rate based on tight-coupling with the IMU and/or RTK, so publishing at 100 - 250 Hz is pretty realistic.
(Eric) Good points. I guess the important thing here is whether it actually belongs in the GPSFix message or in another message. And to answer that, the question is, if you have an application that cares about GPS time (or can update at those very high rates), are you going to be happy with just FIX/NO_FIX, covariance and position or will you want more data out of the GPS unit anyways? Also, what happens when the GPS is publishing some other message to represent estimated velocities? Would you timestamp that with GPS time as well? Besides providing an independent timing source for multiple systems to synchronize their clocks from, what use is there for GPS time that the standard (assume synchronized) system time as returned from ROS::Time::now() wouldn't give you? I've never directly needed to use GPS timestamps, so I'm curious as to what they might be good for that I've not thought of.
(Rene) There can be significant, non-constant delay between the radio signals reaching the receiver and the receiver producing a positioning solution. The timestamp needs to reflect the physical event rather than the time of arrival at the driver to make sensor fusion possible. I've found that using GPS time for GPS message timestamps and synchronizing system time to GPS time is the easiest way to implement this.
(Tully) I agree that this is an important issue. But I think that the complexity of it can be handled in the GPS driver and the dualality of time should not be exposed to the rest of the system. The driver can determine the offset to it's best ability and then publish the "corrected" timestamp in rostime, compensating for the delay in transmission caused by the link between the GPS and driver. The IMU driver does exactly this already. However I think that the GPS time should be part of a more advanced GPSDiagnostic type message as suggested above.
(Mike) There's another big question regarding source that I haven't seen discussed here which also might influence naming. Everything in the messages currently assume the position's source is from the GPS constellation, including their names. A more generably applicable message might be called GNSSFix, and the status message would include a service field. This might also influence any specific satellite data provided in an advanced status field.
# Defines the source of the GNSS signal(s) used by the receiver. # BeiDou included in SERVICE_COMPASS int8 SERVICE_GPS=1 int8 SERVICE_GLONASS=2 int8 SERVICE_COMPASS=4 int8 SERVICE_GALILEO=8 int8 service
(Eric) Good point. Seems fine to rename the messages to GNSSFix and GNSSStatus and having the exact service type defined in an advanced status message. I don't think it would need to go in the simple messages, since, ideally, an algorithm that just wants a position fix doesn't care which service generated that fix.
(Jack) Agreed. Are there any other fields that make sense for other services?
(Jack) There have been no objections to defining a detailed status message for diagnostic and GUI display purposes. It should contain interesting and generic data not needed for a navigation client and hence not part of the GNSSFix message. It is not clear to me exactly what that message should contain in addition to the satellite information described above.
- Would someone please propose an example of this message?
Refocusing the discussion
(Tully) As we're approaching the deadline and we've got a pretty good discussion going above I'm going to try to refine what I've seen above into something concrete we can continue discussing.
(Eric) Good idea... a note is that I believe the proper acronym is GNSS, not GNS (see http://en.wikipedia.org/wiki/Global_navigation_satellite_system and above messages).
(Jack) I checked the existing message names in common_msgs, and they are all CamelCase, even when the name is an acronym, like Imu. Acronyms are mostly avoided, so I suggest using names like SatelliteFix and SatelliteStatus.
(Rene) I don't have a strong opinion on this, but SatelliteFix sounds a little too unspecific to me. Following the Imu precedent we could go with GnssFix. If the acronym really is an issue, at least make it NavigationSatelliteFix.
(Jack) That's OK with me, though prefer something shorter. How about NavSatFix, NavSatStatus etc.? NavSat is a pretty common abbreviation for these systems in the US, and apparently used in other countries too.
GNSFix.msg
From my reading we have a consensus to have sensor_msgs/GNSFix.msg as below pending finalization of the uncertainty representation.
# Specified in WGS84 # # If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the GPS receiver, just put those along the diagonal) # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the data a covariance will have to be assumed or gotten from some other source Header header sensor_msgs/GNSStatus status # Position information # Latitude [degrees]. Positive is north of equator; negative is south. float64 latitude # Longitude [degrees]. Positive is east of prime meridian; negative is west. float64 longitude # Altitude [m]. Positive is above reference ellipsoid float64 altitude # Position covariance [m^2] float64[9] position_covariance # Row major about latitude, longitude, altitude
GNSStatus.msg
This is the new version of GPSStatus globalized and adding service field as proposed by Mike.
- sensor_msgs/GNSStatus.msg
# Note that you whether to output a DGPS fix is not only determined by both the fix type and the last time DGPS corrections were received. For example, if the last time a good set of corrections were received was more than, say, 15 seconds ago, you should fall back to a standard fix. A similar rule should apply for WAAS. # A fix is valid if the status field is >= 0 int8 STATUS_NO_FIX = -1 # Unable to fix position int8 STATUS_FIX = 0 # Normal fix int8 STATUS_SBAS_FIX = 1 # Fixed with some sort of SBAS (e.g. WAAS) int8 STATUS_DGPS_FIX = 2 # Fixed with DGPS int8 status # Defines the source of the GNSS signal(s) used by the receiver. # BeiDou included in SERVICE_COMPASS int8 SERVICE_GPS=1 int8 SERVICE_GLONASS=2 int8 SERVICE_COMPASS=4 int8 SERVICE_GALILEO=8 int8 service
(Eric) Is the service field supposed to be a bitmask? If so, shouldn't it be a uint[8,16,32,etc] field? And documented as such? I'm assuming that's why the default values are powers of 2.
(Mike) Yes, probably it should be a uint8. I'd still like to clarify what the STATUS field should represent beyond if there is a fix or not. Whether the correction signal comes from a ground-based radio or space-based radio doesn't give a good indication of its accuracy. I'd suggest simply having a single STATUS_DIFFERENTIAL_FIX=1 field to indicate that there is a correction being applied.
Diagnostics
- It would be good for device specific diagnostics to be published using the standard diagnostics channels.
However it sounds like people would like an independently published GNSAdvancedStatus message of some form with things like the satellite information. How do these generalize to other GNS systems? I haven't seen a concrete proposal so I'm going to throw this down as a straw man. However we may consider holding off on this part until the next round since it gets more complicated and the above messages are much more important for compatibility.
(Eric) I'd think some things can generalize well (satellite elevation and azimuth, as well as fields like DOP that are derived from the geometrical configuration of the satellites are things that I would assume generalize). Others like identifiers probably don't generalize so well. It might be nice to try to make sure they have similar identifiers and types such that we could reuse, say, a visualization such as the one Novatel's CDU uses to display satellite positions (example: http://img1.afzhan.com/2/2008/633632194628593750.jpg)
(Eric) Perhaps this advanced status would be better off starting in some gps_tools or gps_drivers_common package/stack, as it is intended to be for diagnostics and GUIs only?
I'm going to suggest should we have a advanced status message which is service specific such that there is a different one for GPS vs Galileo, vs Glonass. I think that if we try to keep things entirely generic it will end up being useless.
(Mike) I might suggest waiting for another release to define these, I think there's some danger in making things extremely complex with different messages for different systems. You'll need to check the Status message to figure out which system messages you should be listening for, and generic status modules would have to listen to all the different Sattelite messages and recombine similar data again. There should be some pretty common elements between all the existing/planned systems, and with a bit of research it should be possible to come up with a reasonably generic single message to describe things. I don't know any particular details about the Galileo and Compass messages, but given some time a much simpler solution could be found. How do people feel about leaving it open vs. having a definition that could change in a future release?
sensor_msgs/GPSSattelite.msg
int32 prn # PRN identifier int32 z # elevation int32 azimuth int32 snr # signal-to-noise ratio (dB)
GPSAdvancedStatus
Header header GNSStatus status # put status here too since it's in a different channel than GNSFix uint32 gps_weeks Time gps_seconds # Total (positional-temporal) dilution of precision float64 gdop # Positional (3D) dilution of precision float64 pdop # Horizontal dilution of precision float64 hdop # Vertical dilution of precision float64 vdop # Temporal dilution of precision float64 tdop # Spherical position uncertainty (meters) [epe] float64 err GPSSatellite gps_satellites_used GPSSatellite gps_satellites_visible_but_unused
(Mike) I'm going to continue the time discussion down here. I don't think you should have to use a specific method of time syncroniziation just because you choose a specific receiver, and writing a receiver driver doesn't mean you should have to implement time synchronization. If I want to build a standalone driver that takes GPS time and calculates offset and drift for another clock (say the computer's,) and not include it in the GPS driver, I'd want both the GPS time and the system timestamp when it was read from the device in one message, and currently I don't have any way to access that since the header timestamp in both Fix and advancedStatus will have been fiddled with by the driver in some unspecified way. I'm trying to think of some other way to handle this besides adding yet another time field to the advanced status message. GPS time is reasonably complex to handle, so I'm happy at this point keeping it in the advanced message, but it should be represented as weeks/seconds. I've changed the definition above to reflect this.
Review discussion
New points raised in review discussion e-mails.
(Rene) given the current message definition, checking for unknown covariance requires checking all matrix entries. Maybe we should add something like this:
uint8 COVARIANCE_TYPE_UNKNOWN = 0 uint8 COVARIANCE_TYPE_APPROXIMATED = 1 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 uint8 COVARIANCE_TYPE_KNOWN = 3 uint8 position_covariance_type
- That way the message is self-contained in the sense that you know what you get. A filter can easily identify the unknown covariance case, process approximated covariance only if explicitly instructed to do so, pop up a warning if just the diagonal is known, and require the true covariance, say, if safety is an issue.
- None of this implies any underlying calculation method; it just describes the data and should prevent unexpected behavior if you swap GPS receivers/drivers.
Meeting agenda
(Jack) We need final approvals by 22 October 2010 for inclusion in the common_msgs stack for Diamondback. Let's shoot for an initial approval vote Wednesday morning, 20 October. That leaves two days to resolve any final issues that remain.
(Jack, 20 October) I am starting to wrap up this review, polling the reviewers directly via e-mail.
(Jack, 22 October) As moderator, I declare this review closed and the new API approved.
Conclusion
Review conclusions (pending final approval):
Add GNSSFix and GNSSStatus messages to sensor_msgs for this release.
Change message names to NavSatFix and NavSatStatus.
Expand service bitmap to uint16.
The driver should provide the time of the actual fix in ROS system time.
Document singularities at the poles for the coordinate system the position_covariance matrix lives in (tangential plane through position defines x-y plane, x/y-axes aligned with circles of latitude/longitude, z-up into space).
position_covariance components are in ENU (East, North, Up) frame of reference.
Resolve covariance-from-DOP discussion by adding position_covariance_type.
Resolve status field discussion in favor of retaining the GNSSStatus values (above), but renaming STATUS_DGPS_FIX to the more generic STATUS_GBAS_FIX for ground-based augmentation.
Future releases:
Separately continue work on mapping messages. They may not belong in sensor_msgs at all, but some common definitions would be valuable. Since there were no objections, I deleted those sections from this review page.
Define a separate detailed status message for reporting individual satellites, etc. in the next release.