diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index ac044a4058..2d94914a45 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -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); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 3af0b21c59..715da8a5e8 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -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 diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 68b30fff4a..ab8abbdb7d 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -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; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 0a09d8f55d..f0d9dadaec 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -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