From 6f2a88f707932303a3351daad22569365cf62cbd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 24 Aug 2024 12:26:35 +0900 Subject: [PATCH] AP_Camera: support send-thermal-range --- libraries/AP_Camera/AP_Camera.cpp | 21 +++++++++++++++++++++ libraries/AP_Camera/AP_Camera.h | 5 +++++ libraries/AP_Camera/AP_Camera_Backend.h | 5 +++++ libraries/AP_Camera/AP_Camera_Mount.cpp | 13 +++++++++++++ libraries/AP_Camera/AP_Camera_Mount.h | 5 +++++ libraries/AP_Camera/AP_Camera_config.h | 5 +++++ 6 files changed, 54 insertions(+) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index c37243723e..06a1147dc2 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -461,6 +461,12 @@ bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message ms CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS); send_camera_capture_status(chan); break; +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + case MSG_CAMERA_THERMAL_RANGE: + CHECK_PAYLOAD_SIZE2(CAMERA_THERMAL_RANGE); + send_camera_thermal_range(chan); + break; +#endif default: // should not reach this; should only be called for specific IDs @@ -615,6 +621,21 @@ void AP_Camera::send_camera_capture_status(mavlink_channel_t chan) } } +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Camera::send_camera_thermal_range(mavlink_channel_t chan) +{ + WITH_SEMAPHORE(_rsem); + + // call each instance + for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->send_camera_thermal_range(chan); + } + } +} +#endif + /* update; triggers by distance moved and camera trigger */ diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 28a27b0fa3..37f3394227 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -240,6 +240,11 @@ private: // send camera capture status message to GCS void send_camera_capture_status(mavlink_channel_t chan); +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(mavlink_channel_t chan); +#endif + HAL_Semaphore _rsem; // semaphore for multi-thread access AP_Camera_Backend *primary; // primary camera backed bool _is_in_auto_mode; // true if in AUTO mode diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index d52944f5c0..c9b55949e6 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -126,6 +126,11 @@ public: // send camera capture status message to GCS virtual void send_camera_capture_status(mavlink_channel_t chan) const; +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + virtual void send_camera_thermal_range(mavlink_channel_t chan) const {}; +#endif + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index b472d068eb..9599097d8c 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -109,6 +109,19 @@ void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const } } +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Camera_Mount::send_camera_thermal_range(mavlink_channel_t chan) const +{ +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + mount->send_camera_thermal_range(get_mount_instance(), chan); + } +#endif +} +#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + #if AP_CAMERA_SCRIPTING_ENABLED // change camera settings not normally used by autopilot bool AP_Camera_Mount::change_setting(CameraSetting setting, float value) diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index b3dd450652..19e56ff3c0 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -70,6 +70,11 @@ public: // send camera capture status message to GCS void send_camera_capture_status(mavlink_channel_t chan) const override; +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(mavlink_channel_t chan) const override; +#endif + #if AP_CAMERA_SCRIPTING_ENABLED // change camera settings not normally used by autopilot bool change_setting(CameraSetting setting, float value) override; diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index 24b51275be..6ff54ec978 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -50,6 +50,11 @@ #define AP_CAMERA_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED #endif +// send thermal range is supported on a few thermal cameras but all are within mounts +#ifndef AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +#define AP_CAMERA_SEND_THERMAL_RANGE_ENABLED AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +#endif + #ifndef HAL_RUNCAM_ENABLED #define HAL_RUNCAM_ENABLED 1 #endif