AP_BoardConfig: instantiate an RTC

AP_BoardConfig: set RTC from hw clock at startup
This commit is contained in:
Peter Barker 2018-04-17 13:53:47 +10:00 committed by Andrew Tridgell
parent ece7ff874c
commit 59d1d8aecc
2 changed files with 7 additions and 0 deletions

View File

@ -21,6 +21,7 @@
#include <GCS_MAVLink/GCS.h>
#include "AP_BoardConfig.h"
#include <stdio.h>
#include <AP_RTC/AP_RTC.h>
#if HAL_WITH_UAVCAN
#include <AP_UAVCAN/AP_UAVCAN.h>
@ -227,6 +228,8 @@ void AP_BoardConfig::init()
// rebooting
hal.util->set_imu_target_temp((int8_t *)&_imu_target_temperature);
#endif
AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW);
}
// set default value for BRD_SAFETY_MASK

View File

@ -3,6 +3,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_RTC/AP_RTC.h>
#if defined(HAL_NEEDS_PARAM_HELPER)
#include <AP_Param_Helper/AP_Param_Helper.h>
@ -214,4 +215,7 @@ private:
// HAL specific parameters
AP_Param_Helper param_helper{false};
#endif
// real-time-clock; private because access is via the singleton
AP_RTC rtc;
};