From 5a21d0cb8a859b293eea087fb8c9be150c0ca910 Mon Sep 17 00:00:00 2001 From: Peter Barker <pbarker@barker.dropbear.id.au> Date: Fri, 12 Apr 2024 10:50:27 +1000 Subject: [PATCH] AP_Camera: correct compilation when HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED not set - need the include because an enumeration is used in the header (relied on the include previously being made by a file including this header) - set_lens is not part of set-camera-source, so shouldn't be excluded - exclude entire method, not body of method based on the include --- libraries/AP_Camera/AP_Camera_Backend.h | 2 +- libraries/AP_Camera/AP_Camera_Mount.cpp | 4 ++-- libraries/AP_Camera/AP_Camera_Mount.h | 4 ++++ 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 425b7dc40f..41d383527e 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -82,10 +82,10 @@ public: // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; } -#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // set camera lens as a value from 0 to 5 virtual bool set_lens(uint8_t lens) { return false; } +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type virtual bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false; } #endif diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index c3d8669194..29f0759116 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -70,17 +70,17 @@ bool AP_Camera_Mount::set_lens(uint8_t lens) return false; } +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type bool AP_Camera_Mount::set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { -#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED AP_Mount* mount = AP::mount(); if (mount != nullptr) { return mount->set_camera_source(get_mount_instance(), (uint8_t)primary_source, (uint8_t)secondary_source); } -#endif return false; } +#endif // send camera information message to GCS void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index 56c607fb47..d001cb979d 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -22,6 +22,8 @@ #if AP_CAMERA_MOUNT_ENABLED +#include "AP_Camera.h" + class AP_Camera_Mount : public AP_Camera_Backend { public: @@ -54,8 +56,10 @@ public: // set camera lens as a value from 0 to 5 bool set_lens(uint8_t lens) override; +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) override; +#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override;