Skip to content

Commit

Permalink
AP_Mount: correct compilation with HAL_MOUNT_SET_CAMERA_SOURCE_ENABLE…
Browse files Browse the repository at this point in the history
…D off
  • Loading branch information
peterbarker committed Aug 8, 2024
1 parent b8f7516 commit 9616165
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 1 deletion.
2 changes: 2 additions & 0 deletions libraries/AP_Mount/AP_Mount_Topotek.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

#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_Topotek::set_camera_source(uint8_t primary_source, uint8_t secondary_source)
Expand Down Expand Up @@ -511,6 +512,7 @@ bool AP_Mount_Topotek::set_camera_source(uint8_t primary_source, uint8_t seconda
// send pip command
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
void AP_Mount_Topotek::send_camera_information(mavlink_channel_t chan) const
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_Mount/AP_Mount_Topotek.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,11 @@

#pragma once

#include "AP_Mount_Backend_Serial.h"
#include "AP_Mount_config.h"

#if HAL_MOUNT_TOPOTEK_ENABLED

#include "AP_Mount_Backend_Serial.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
Expand Down Expand Up @@ -78,9 +79,11 @@ class AP_Mount_Topotek : public AP_Mount_Backend_Serial
// set camera picture-in-picture mode
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
// 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;
#endif

// send camera information message to GCS
void send_camera_information(mavlink_channel_t chan) const override;
Expand Down

0 comments on commit 9616165

Please sign in to comment.