Sub: Use HAL system_time_was_set

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2018-03-09 13:15:08 -03:00 committed by Jacob Walser
parent 72234031c0
commit db6bb3de4f
2 changed files with 1 additions and 3 deletions

View File

@ -228,7 +228,6 @@ private:
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // true if we are currently performing the motors test
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t system_time_set : 1; // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // home status (unset, set, locked)
uint8_t at_bottom : 1; // true if we are at the bottom

View File

@ -135,7 +135,7 @@ bool Sub::far_from_EKF_origin(const Location& loc)
void Sub::set_system_time_from_GPS()
{
// exit immediately if system time already set
if (ap.system_time_set) {
if (hal.util->system_time_was_set()) {
return;
}
@ -149,7 +149,6 @@ void Sub::set_system_time_from_GPS()
// update signing timestamp
GCS_MAVLINK::update_signing_timestamp(gps_timestamp);
ap.system_time_set = true;
Log_Write_Event(DATA_SYSTEM_TIME_SET);
}
}