Browse Source

授权码日期修改为由GPS周与周毫秒获取

master
yaozb 5 years ago
parent
commit
4e6fcb1128
  1. 18
      ArduCopter/system.cpp
  2. 6
      libraries/AP_GPS/AP_GPS.cpp
  3. 2
      libraries/AP_GPS/AP_GPS.h
  4. 1
      libraries/AP_GPS/GPS_Backend.cpp

18
ArduCopter/system.cpp

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
#include "Copter.h"
#include <AP_BLHeli/AP_BLHeli.h>
#include <sys/time.h>
#include <time.h>
/*****************************************************************************
* The init_ardupilot function processes everything we need for an in - air restart
* We will determine later if we are actually on the ground and process a
@ -335,12 +336,21 @@ bool Copter::position_ok() const @@ -335,12 +336,21 @@ bool Copter::position_ok() const
bool Copter::deadline_ok()
{
int32_t deadline =0;
copter.get_deadline_params(deadline);
int32_t gps_date =0;
AP::gps().get_gps_headline_value(gps_date);
if ((deadline - gps_date) >= 0)
if((AP::gps().time_week() ==0)||(AP::gps().time_week_ms() ==0)){
return false;
}
uint64_t timestamp = AP::gps().time_epoch_convert(AP::gps().time_week(),AP::gps().time_week_ms())/1000;
//tick -timestamp - uint:s
time_t tick = (time_t)timestamp;
tm gpstime = *localtime(&tick);
uint16_t year = gpstime.tm_year+1900;
uint8_t month = gpstime.tm_mon+1;
uint8_t day = gpstime.tm_mday;
gps_date = year*10000+month*100+day;
if (deadline>= gps_date)
{
return true;
}

6
libraries/AP_GPS/AP_GPS.cpp

@ -1179,11 +1179,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages() @@ -1179,11 +1179,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
}
}
void AP_GPS::get_gps_headline_value(int32_t & gps_date_time){
gps_date_time = state[GPS_BLENDED_INSTANCE].zr_date_timestamp;
}
/*
return the expected lag (in seconds) in the position and velocity readings from the gps
return true if the GPS hardware configuration is known or the delay parameter has been set
@ -1600,7 +1596,6 @@ void AP_GPS::calc_blended_state(void) @@ -1600,7 +1596,6 @@ void AP_GPS::calc_blended_state(void)
// use data from highest weighted sensor
state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
state[GPS_BLENDED_INSTANCE].time_week_ms = state[best_index].time_week_ms;
state[GPS_BLENDED_INSTANCE].zr_date_timestamp = state[best_index].zr_date_timestamp;
} else {
// use week number from highest weighting GPS (they should all have the same week number)
state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
@ -1612,7 +1607,6 @@ void AP_GPS::calc_blended_state(void) @@ -1612,7 +1607,6 @@ void AP_GPS::calc_blended_state(void)
}
}
state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0;
state[GPS_BLENDED_INSTANCE].zr_date_timestamp = state[best_index].zr_date_timestamp;
}
// calculate a blended value for the timing data and lag

2
libraries/AP_GPS/AP_GPS.h

@ -154,7 +154,6 @@ public: @@ -154,7 +154,6 @@ public:
bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available
uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
uint32_t uart_timestamp_ms; ///< optional timestamp from set_uart_timestamp()
uint32_t zr_date_timestamp; //2020-03-26 = 20200326
// all the following fields must only all be filled by RTK capable backend drivers
uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
uint16_t rtk_week_number; ///< GPS Week Number of last baseline
@ -438,7 +437,6 @@ public: @@ -438,7 +437,6 @@ public:
// handle possibly fragmented RTCM injection data
void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len);
void get_gps_headline_value(int32_t & gps_date_time);
protected:
// configuration parameters

1
libraries/AP_GPS/GPS_Backend.cpp

@ -94,7 +94,6 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds) @@ -94,7 +94,6 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
rmon += 12;
year -= 1;
}
state.zr_date_timestamp =(year+2000)*10000+mon*100+day; //FIXME only calcute onecs
// get time in seconds since unix epoch
uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day;

Loading…
Cancel
Save