mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
001e516fa7
commit
5375980aa6
|
@ -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();
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue