GCS_MAVLink: make send_system_time const

needed when sending from const functions
This commit is contained in:
Peter Barker 2021-10-16 10:17:03 +11:00 committed by Peter Barker
parent a01bd33f69
commit 948e00a072
2 changed files with 2 additions and 2 deletions

View File

@ -280,7 +280,7 @@ public:
virtual void send_nav_controller_output() const = 0;
virtual void send_pid_tuning() = 0;
void send_ahrs2();
void send_system_time();
void send_system_time() const;
void send_rc_channels() const;
void send_rc_channels_raw() const;
void send_raw_imu();

View File

@ -1651,7 +1651,7 @@ void GCS_MAVLINK::log_mavlink_stats()
/*
send the SYSTEM_TIME message
*/
void GCS_MAVLINK::send_system_time()
void GCS_MAVLINK::send_system_time() const
{
uint64_t time_unix = 0;
AP::rtc().get_utc_usec(time_unix); // may fail, leaving time_unix at 0