AP_Mount: correct compilation with HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED off

This commit is contained in:
Peter Barker 2024-08-09 07:58:13 +10:00 committed by Peter Barker
parent a014bcb5bd
commit 53e9fe0805
2 changed files with 6 additions and 1 deletions

View File

@ -464,6 +464,7 @@ bool AP_Mount_Topotek::set_lens(uint8_t lens)
return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, lens); return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, 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 // 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 // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t
bool AP_Mount_Topotek::set_camera_source(uint8_t primary_source, uint8_t secondary_source) bool AP_Mount_Topotek::set_camera_source(uint8_t primary_source, uint8_t secondary_source)
@ -511,6 +512,7 @@ bool AP_Mount_Topotek::set_camera_source(uint8_t primary_source, uint8_t seconda
// send pip command // send pip command
return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, pip_setting); return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, pip_setting);
} }
#endif // HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
// send camera information message to GCS // send camera information message to GCS
void AP_Mount_Topotek::send_camera_information(mavlink_channel_t chan) const void AP_Mount_Topotek::send_camera_information(mavlink_channel_t chan) const

View File

@ -18,10 +18,11 @@
#pragma once #pragma once
#include "AP_Mount_Backend_Serial.h" #include "AP_Mount_config.h"
#if HAL_MOUNT_TOPOTEK_ENABLED #if HAL_MOUNT_TOPOTEK_ENABLED
#include "AP_Mount_Backend_Serial.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
@ -78,9 +79,11 @@ public:
// set camera picture-in-picture mode // set camera picture-in-picture mode
bool set_lens(uint8_t lens) override; bool set_lens(uint8_t lens) override;
#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 // 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 // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t
bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override; bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override;
#endif
// send camera information message to GCS // send camera information message to GCS
void send_camera_information(mavlink_channel_t chan) const override; void send_camera_information(mavlink_channel_t chan) const override;