AP_NavEKF3: make send_status_report const

This commit is contained in:
Peter Barker 2019-12-10 18:04:21 +11:00 committed by Randy Mackay
parent 060c851709
commit 9ed37e4486
4 changed files with 4 additions and 4 deletions

View File

@ -1440,7 +1440,7 @@ void NavEKF3::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const
}
// send an EKF_STATUS_REPORT message to GCS
void NavEKF3::send_status_report(mavlink_channel_t chan)
void NavEKF3::send_status_report(mavlink_channel_t chan) const
{
if (core) {
core[primary].send_status_report(chan);

View File

@ -335,7 +335,7 @@ public:
void getFilterStatus(int8_t instance, nav_filter_status &status) const;
// send an EKF_STATUS_REPORT message to GCS
void send_status_report(mavlink_channel_t chan);
void send_status_report(mavlink_channel_t chan) const;
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required

View File

@ -551,7 +551,7 @@ void NavEKF3_core::getFilterGpsStatus(nav_gps_status &faults) const
}
// send an EKF_STATUS message to GCS
void NavEKF3_core::send_status_report(mavlink_channel_t chan)
void NavEKF3_core::send_status_report(mavlink_channel_t chan) const
{
// prepare flags
uint16_t flags = 0;

View File

@ -327,7 +327,7 @@ public:
void getFilterStatus(nav_filter_status &status) const;
// send an EKF_STATUS_REPORT message to GCS
void send_status_report(mavlink_channel_t chan);
void send_status_report(mavlink_channel_t chan) const;
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required