Browse Source

日志时间不对,增加一些打印2

apm_2208-rover-debug
Brown.Z 3 years ago
parent
commit
3e6679cc42
  1. 4
      libraries/AP_GPS/GPS_Backend.cpp
  2. 2
      libraries/AP_Logger/AP_Logger_File.cpp
  3. 49
      libraries/AP_RTC/AP_RTC.cpp
  4. 1
      libraries/AP_RTC/AP_RTC.h

4
libraries/AP_GPS/GPS_Backend.cpp

@ -114,8 +114,8 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds) @@ -114,8 +114,8 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
// gcs().send_text(MAV_SEVERITY_INFO, "week:%d,ms:%ld",state.time_week,state.time_week_ms);
// gcs().send_text(MAV_SEVERITY_INFO, "year:%d,m:%d,d:%d \n\r",tm.tm_year,tm.tm_mon,tm.tm_mday);
// gcs().send_text(MAV_SEVERITY_INFO, "hour:%d,m:%d,s:%d \n\r",tm.tm_hour,tm.tm_min,tm.tm_sec);
gcs().send_text(MAV_SEVERITY_INFO, "unix_time:%ld\n\r",unix_time);
gcs().send_text(MAV_SEVERITY_INFO, "unix_time:%ld",unix_time);
gcs().send_text(MAV_SEVERITY_INFO,"now: %s\n",AP::rtc().get_rtc_date());
last_1s = AP_HAL::millis();
}
}

2
libraries/AP_Logger/AP_Logger_File.cpp

@ -824,6 +824,8 @@ void AP_Logger_File::start_new_log(void) @@ -824,6 +824,8 @@ void AP_Logger_File::start_new_log(void)
uint64_t utc_usec;
_need_rtc_update = !AP::rtc().get_utc_usec(utc_usec);
gcs().send_text(MAV_SEVERITY_INFO, "log utc {%d}:%lld\n",_need_rtc_update,utc_usec);
gcs().send_text(MAV_SEVERITY_INFO,"log date:%s",AP::rtc().get_rtc_date());
#endif
// create the log directory if need be

49
libraries/AP_RTC/AP_RTC.cpp

@ -4,6 +4,7 @@ @@ -4,6 +4,7 @@
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <time.h>
#include <stdio.h>
extern const AP_HAL::HAL& hal;
@ -41,20 +42,40 @@ const AP_Param::GroupInfo AP_RTC::var_info[] = { @@ -41,20 +42,40 @@ const AP_Param::GroupInfo AP_RTC::var_info[] = {
void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
{
bool need_prt = false;
static uint32_t last_1s = AP_HAL::millis();
if (AP_HAL::millis() - last_1s > 5000)
{
need_prt = true;
last_1s = AP_HAL::millis();
}
//////////////////////////////////////
const uint64_t oldest_acceptable_date_us = 1640995200ULL*1000*1000; // 2022-01-01 0:00
if (type >= rtc_source_type) {
// e.g. system-time message when we've been set by the GPS
if (need_prt)
{
gcs().send_text(MAV_SEVERITY_INFO, "type{%d} >= rtc_source_type{%d}",type , (uint8_t)rtc_source_type);
}
return;
}
// check it's from an allowed sources:
if (!(allowed_types & (1<<type))) {
if (need_prt)
{
gcs().send_text(MAV_SEVERITY_INFO, "!(allowed_types{%d}& (1<<type{%d}))",(uint8_t)allowed_types,(uint8_t)type);
}
return;
}
// don't allow old times
if (time_utc_usec < oldest_acceptable_date_us) {
if (need_prt)
{
gcs().send_text(MAV_SEVERITY_INFO, "time_utc_usec < oldest_acceptable_date_us");
}
return;
}
@ -62,6 +83,10 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) @@ -62,6 +83,10 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
const int64_t tmp = int64_t(time_utc_usec) - int64_t(now);
if (tmp < rtc_shift) {
// can't allow time to go backwards, ever
if (need_prt)
{
gcs().send_text(MAV_SEVERITY_INFO, "tmp{%lld} < rtc_shift{%lld}",tmp , rtc_shift);
}
return;
}
WITH_SEMAPHORE(rsem);
@ -75,6 +100,10 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) @@ -75,6 +100,10 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
rtc_source_type = type;
if (need_prt)
{
gcs().send_text(MAV_SEVERITY_INFO, "type:%d,in utc:%lld,rtc_shift:%lld",type,time_utc_usec,rtc_shift);
}
#if HAL_GCS_ENABLED
// update signing timestamp
GCS_MAVLINK::update_signing_timestamp(time_utc_usec);
@ -205,6 +234,26 @@ uint32_t AP_RTC::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms @@ -205,6 +234,26 @@ uint32_t AP_RTC::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms
return static_cast<uint32_t>(total_delay_ms);
}
char* AP_RTC::get_rtc_date(void)
{
uint16_t year;uint8_t mon;uint8_t mday;uint8_t hour; uint8_t min; uint8_t sec;
tm localtime_tm {}; // year is relative to 1900
uint64_t time_usec = 0;
if (get_utc_usec(time_usec)) { // may fail, leaving time_unix at 0
const time_t time_sec = time_usec / 1000000;
localtime_tm = *gmtime(&time_sec);
}
year = uint16_t(localtime_tm.tm_year + 1900); // tm_year is relative to year 1900
mon = uint8_t(localtime_tm.tm_mon + 1); // MSP requires [1-12] months
mday = uint8_t(localtime_tm.tm_mday);
hour = uint8_t(localtime_tm.tm_hour);
min = uint8_t(localtime_tm.tm_min);
sec = uint8_t(localtime_tm.tm_sec);
static char buf[50];
snprintf(buf, sizeof(buf), "%04d%02d%02d%02d%02d%02d",year,mon,mday,hour,min,sec);
return buf;
}
/*
mktime replacement from Samba

1
libraries/AP_RTC/AP_RTC.h

@ -51,6 +51,7 @@ public: @@ -51,6 +51,7 @@ public:
static AP_RTC *get_singleton() {
return _singleton;
}
char* get_rtc_date(void);
// allow threads to lock against RTC update
HAL_Semaphore &get_semaphore(void) {

Loading…
Cancel
Save