diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index 5b60e40a5f..3871af21af 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -13,6 +13,31 @@ const char *AP_RTC::_clock_source_types[] = { "NONE", }; +AP_RTC::AP_RTC() +{ + AP_Param::setup_object_defaults(this, var_info); + if (_singleton != nullptr) { + // it's an error to get here. But I don't want to include + // AP_HAL here + return; + } + _singleton = this; +} + + +// table of user settable parameters +const AP_Param::GroupInfo AP_RTC::var_info[] = { + + // @Param: _TYPES + // @DisplayName: Allowed sources of RTC time + // @Description: Specifies which sources of UTC time will be accepted + // @Bitmask: 0:GPS,1:MAVLINK_SYSTEM_TIME,2:HW + // @User: Advanced + AP_GROUPINFO("_TYPES", 1, AP_RTC, allowed_types, 1), + + AP_GROUPEND +}; + void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) { if (type >= rtc_source_type) { @@ -20,6 +45,11 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) return; } + // check it's from an allowed sources: + if (!(allowed_types & (1< + #include class AP_RTC { public: - AP_RTC() { - if (_singleton != nullptr) { - // it's an error to get here. But I don't want to include - // AP_HAL here - return; - } - _singleton = this; - } + AP_RTC(); + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Int8 allowed_types; // ordering is important in source_type; lower-numbered is - // considered a better time source. + // considered a better time source. These values are documented + // and used in the parameters! enum source_type : uint8_t { - SOURCE_GPS, - SOURCE_MAVLINK_SYSTEM_TIME, - SOURCE_HW, + SOURCE_GPS = 0, + SOURCE_MAVLINK_SYSTEM_TIME = 1, + SOURCE_HW = 2, SOURCE_NONE, };