Skip to content

Commit

Permalink
AP_Camera: correct compilation when HAL_MOUNT_SET_CAMERA_SOURCE_ENABL…
Browse files Browse the repository at this point in the history
…ED 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
  • Loading branch information
peterbarker committed Apr 14, 2024
1 parent a4ec91c commit 5a21d0c
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 3 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,10 @@ class AP_Camera_Backend
// 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
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Camera/AP_Camera_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

#if AP_CAMERA_MOUNT_ENABLED

#include "AP_Camera.h"

class AP_Camera_Mount : public AP_Camera_Backend
{
public:
Expand Down Expand Up @@ -54,8 +56,10 @@ class AP_Camera_Mount : public AP_Camera_Backend
// 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;
Expand Down

0 comments on commit 5a21d0c

Please sign in to comment.