Zubax / gridsens_gs2

Zubax GNSS module
https://zubax.com/products/gnss_2
GNU General Public License v3.0
50 stars 57 forks source link

Feature request: supply raw GPS time if possible #1

Closed hsteinhaus closed 9 years ago

hsteinhaus commented 9 years ago

Some software that was developed to interface with GPS receivers directly, internally works on lower-level GPS time information. For instance ArduPilot's internal realtime clock expects to be adjusted by a tuple consisting of the GPS week number plus an offset in ms since begin of GPS week. It is very hard to reconstruct this information from UTC time, as GPS time runs without any respect to leap seconds.

It would be very nice if the raw GPS time info is made public in some way.

pavel-kirienko commented 9 years ago

We can add a configuration parameter that would allow the user/autopilot to select which time grid should be preferred. Would it make sense?

https://github.com/Zubax/zubax_gnss/blob/master/firmware/src/gnss.cpp#L44

But UTC should remain a default choice anyway - here's the quote from the M8 manual:

u-blox GNSS receivers employ multiple GNSS system times and/or receiver local times (in order to support multiple GNSS systems concurrently), so users should not rely on UBX messages that report GNSS system time or receiver local time being supported in future. It is therefore recommended to give preference to those messages that report UTC time.

hsteinhaus commented 9 years ago

I think it would be cleaner to add an additional field, together with the cited comment about multi-GNSS environments. This would allow to supply the low-level GPS time to legacy software, without the risk of confusing other software layers that do not depend on raw GPS time.

pavel-kirienko commented 9 years ago

It is true that adding a dedicated field would make a cleaner solution; however, this will make the message one CAN frame longer (and it is huge already), with the downside of increased latency.

I can offer an alternative - a dedicated message, not field, for GNSS-specific timestamp.

However, first it would be interesting to know what's so specific about the internal logic of APM so it can't digest UTC time? Do you know why exactly does it need GPS? I'm asking because I want to understand if this is a common issue (in which case it's worth supporting in the standard UAVCAN message set) or just a peculiar shortcoming of the APM software design (in which case it can be considered an isolated issue that is safe to disregard).

hsteinhaus commented 9 years ago

Ok, I think it should be no big deal to subscribe on an additional message.

Regarding UTC/GPS time in APM:

The problem with APM's time is that it is expressed as a combination of GPS week number and time offset in microseconds since GPS week start: https://github.com/diydrones/ardupilot/blob/master/libraries/AP_GPS/AP_GPS.h#L126

To calculate the GPS week number from UTC, you need to know the exact number of leap seconds since the GPS epoch started (Jan/06/1980), as GPS time runs without any leap seconds per definition. Whenever a new leap second will be inserted in future, the GPS time conversion code has to be changed, which is pretty nasty IMHO.

My current hack to do this conversion can be found here: https://github.com/diydrones/ardupilot/blob/master/libraries/AP_GPS/AP_GPS_PX4.cpp#L73

pavel-kirienko commented 9 years ago

Ok, I understand the implications of the lack of leap seconds in the GPS time grid. But why does APM need the exact GPS time, and why does it care about the leap seconds? UTC can be easily represented in the equivalent form of (week number + offset + unknown number of leap seconds), as you've implemented already.

hsteinhaus commented 9 years ago

I don't know why the interface was defined that way it is (did not find any obvious reason in the source). I guess the decision must be seen with an 8 bit MCU and one single type of available GPS receivers in a single GNSS environment in mind.

Unfortunately (for us), this definition made it into the dataflash log format of APM, which is one of the most important interfaces of APM to a bunch of third-party tools. I think it is virtually impossible to change that interface - as probably more than a dozen of independent programs rely on it (many different GCSes, Log analysers, GCS proxies, Android/IOS apps etc.).

pavel-kirienko commented 9 years ago

@hsteinhaus An alternative suggestion is to extend the Fix message with a new one-byte field for the current number of leap seconds. This would be way easier both to implement and to use; and increase in the message size would be negligible.

Rules that should apply to the new field:

hsteinhaus commented 9 years ago

The suggested solution is perfect for me.

BTW, do we have a reliable method to determine in which GPS epoch we currently are before getting a GLONASS lock? Or is the GPS time relative to the start of the current epoch?

Details of the potential problem could be found here (even if the context is very different): http://www.ukiws.demon.co.uk/GFAC/documents/2014-11-29%20loss%20of%20date%20letter%20to%20fr%20makers.pdf

pavel-kirienko commented 9 years ago

u-blox receivers can handle GPS week rollover up to the year ~2029. This is an excerpt from the specification:

u-blox GNSS receivers solve this problem by assuming that all week numbers must be at least as large as a reference rollover week number. This reference rollover week number is hard-coded into the firmware at compile time and is normally set a few weeks before the s/w is completed, but it can be overridden by the wknRollover field of the UBX-CFG-NAVX5 message to any value the user wishes.

The following example illustrates how this works: Assume that the reference rollover week number set in the firmware at compile time is 1524 (which corresponds to a week in calendar year 2009, but would be transmitted by the satellites as 500). In this case, if the receiver sees transmissions containing week numbers in the range 500 ... 1023, these will be interpreted as week numbers 1524 ... 2027 (CY 2009 ... 2019), whereas transmissions with week numbers from 0 to 499 are interpreted as week numbers 2028 ... 2526 (CY 2019 ... 2029).

(chapter 7.7 - GPS Week Number Rollover)

pavel-kirienko commented 9 years ago

@hsteinhaus Please review https://github.com/UAVCAN/uavcan/blob/dsdl_review/dsdl/uavcan/equipment/gnss/300.Fix.uavcan#L18

hsteinhaus commented 9 years ago

Looks perfect for me, thanks! The change should eliminate the need for all the upgly leap second guessing from the APM GNSS driver. Of course the vehicle_gps_position_s uORB topic (PX4 firmware) needs to be adjusted accordingly.

pavel-kirienko commented 9 years ago

I'm closing this as the feature request was addressed already. GNSS firmware will be updated when UAVCAN is officially released.