AP_GPS: rename macros to avoid conflicts

these macros were also defined in NuttX in clock.h
This commit is contained in:
Andrew Tridgell 2017-05-05 20:09:29 +10:00
parent 45f27ceb9c
commit 3687b6bdf0
4 changed files with 8 additions and 8 deletions

View File

@ -328,7 +328,7 @@ bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
*/
uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
{
uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * MSEC_PER_WEEK + gps_ms;
uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;
return fix_time_ms;
}
@ -765,8 +765,8 @@ void AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms
istate.num_sats = _num_sats;
istate.last_gps_time_ms = tnow;
uint64_t gps_time_ms = time_epoch_ms - UNIX_OFFSET_MSEC;
istate.time_week = gps_time_ms / MSEC_PER_WEEK;
istate.time_week_ms = gps_time_ms - istate.time_week * MSEC_PER_WEEK;
istate.time_week = gps_time_ms / AP_MSEC_PER_WEEK;
istate.time_week_ms = gps_time_ms - istate.time_week * AP_MSEC_PER_WEEK;
timing[instance].last_message_time_ms = tnow;
timing[instance].last_fix_time_ms = tnow;
_type[instance].set(GPS_TYPE_HIL);

View File

@ -36,7 +36,7 @@
// the number of GPS leap seconds
#define GPS_LEAPSECONDS_MILLIS 18000ULL
#define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
#define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
class DataFlash_Class;
class AP_GPS_Backend;

View File

@ -252,8 +252,8 @@ AP_GPS_SBP2::_attempt_state_update()
return false;
} else if (last_pos_llh.tow == last_vel_ned.tow
&& (distMod(last_gps_time.tow, last_vel_ned.tow, MSEC_PER_WEEK) < 10000)
&& (distMod(last_dops.tow, last_vel_ned.tow, MSEC_PER_WEEK) < 60000)
&& (distMod(last_gps_time.tow, last_vel_ned.tow, AP_MSEC_PER_WEEK) < 10000)
&& (distMod(last_dops.tow, last_vel_ned.tow, AP_MSEC_PER_WEEK) < 60000)
&& (last_vel_ned.tow > last_full_update_tow || (last_gps_time.wn > last_full_update_wn && last_vel_ned.tow < last_full_update_tow))) {
//We have an aligned VEL and LLH, and a recent DOPS and TIME.

View File

@ -105,8 +105,8 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
ret -= 272764785UL;
// get GPS week and time
state.time_week = ret / SEC_PER_WEEK;
state.time_week_ms = (ret % SEC_PER_WEEK) * MSEC_PER_SEC;
state.time_week = ret / AP_SEC_PER_WEEK;
state.time_week_ms = (ret % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC;
state.time_week_ms += msec;
}