From 088dc9813855d7f9d8665d0aa155c7b0b0749a02 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 22 Mar 2024 15:32:02 +0900 Subject: [PATCH] AP_Mount: add HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED --- libraries/AP_Mount/AP_Mount.cpp | 2 ++ libraries/AP_Mount/AP_Mount.h | 2 ++ libraries/AP_Mount/AP_Mount_Backend.h | 2 ++ libraries/AP_Mount/AP_Mount_config.h | 5 +++++ 4 files changed, 11 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index fd8755a5a98e55..e89f0808d302ec 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -833,6 +833,7 @@ bool AP_Mount::set_lens(uint8_t instance, uint8_t lens) return backend->set_lens(lens); } +#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 // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t bool AP_Mount::set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source) @@ -843,6 +844,7 @@ bool AP_Mount::set_camera_source(uint8_t instance, uint8_t primary_source, uint8 } return backend->set_camera_source(primary_source, secondary_source); } +#endif // send camera information message to GCS void AP_Mount::send_camera_information(uint8_t instance, mavlink_channel_t chan) const diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index d2c0cec58482d6..f7c0f45ca32296 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -250,9 +250,11 @@ class AP_Mount // set camera lens as a value from 0 to 5 bool set_lens(uint8_t instance, uint8_t lens); +#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 // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t bool set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source); +#endif // send camera information message to GCS void send_camera_information(uint8_t instance, mavlink_channel_t chan) const; diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 9bcbcb024adb7c..07f12a203a947f 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -182,9 +182,11 @@ class AP_Mount_Backend // set camera lens as a value from 0 to 5 virtual bool 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 // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t virtual bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) { return false; } +#endif // send camera information message to GCS virtual void send_camera_information(mavlink_channel_t chan) const {} diff --git a/libraries/AP_Mount/AP_Mount_config.h b/libraries/AP_Mount/AP_Mount_config.h index a7b16ed63fd302..0a6d38671cb037 100644 --- a/libraries/AP_Mount/AP_Mount_config.h +++ b/libraries/AP_Mount/AP_Mount_config.h @@ -53,3 +53,8 @@ #ifndef AP_MOUNT_POI_TO_LATLONALT_ENABLED #define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024 #endif + +// set camera source is supported on gimbals that may have more than one lens +#ifndef HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED +#define HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SIYI_ENABLED || HAL_MOUNT_XACTI_ENABLED || HAL_MOUNT_VIEWPRO_ENABLED +#endif