From 5375980aa6de8bedbeaec1343aff1f4fafddebe5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 1 Feb 2021 13:26:27 -0300 Subject: [PATCH] AP_Camera: Add missing const in member functions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- libraries/AP_Camera/AP_Camera.cpp | 2 +- libraries/AP_Camera/AP_Camera.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 3aae01ec9b..77df416474 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -318,7 +318,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo /* Send camera feedback to the GCS */ -void AP_Camera::send_feedback(mavlink_channel_t chan) +void AP_Camera::send_feedback(mavlink_channel_t chan) const { const AP_AHRS &ahrs = AP::ahrs(); diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 82ea7d6cff..395d437741 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -39,7 +39,7 @@ public: // MAVLink methods void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg); - void send_feedback(mavlink_channel_t chan); + void send_feedback(mavlink_channel_t chan) const; // Command processing void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);