Skip to content

Commit 8d465b6

Browse files
committed
AP_Camera: correct compilation when HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED 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
1 parent 860498d commit 8d465b6

File tree

3 files changed

+7
-3
lines changed

3 files changed

+7
-3
lines changed

libraries/AP_Camera/AP_Camera_Backend.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,10 +82,10 @@ class AP_Camera_Backend
8282
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
8383
virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; }
8484

85-
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
8685
// set camera lens as a value from 0 to 5
8786
virtual bool set_lens(uint8_t lens) { return false; }
8887

88+
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
8989
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
9090
virtual bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false; }
9191
#endif

libraries/AP_Camera/AP_Camera_Mount.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,17 +70,17 @@ bool AP_Camera_Mount::set_lens(uint8_t lens)
7070
return false;
7171
}
7272

73+
#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
7374
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
7475
bool AP_Camera_Mount::set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source)
7576
{
76-
#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
7777
AP_Mount* mount = AP::mount();
7878
if (mount != nullptr) {
7979
return mount->set_camera_source(get_mount_instance(), (uint8_t)primary_source, (uint8_t)secondary_source);
8080
}
81-
#endif
8281
return false;
8382
}
83+
#endif
8484

8585
// send camera information message to GCS
8686
void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const

libraries/AP_Camera/AP_Camera_Mount.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222

2323
#if AP_CAMERA_MOUNT_ENABLED
2424

25+
#include "AP_Camera.h"
26+
2527
class AP_Camera_Mount : public AP_Camera_Backend
2628
{
2729
public:
@@ -54,8 +56,10 @@ class AP_Camera_Mount : public AP_Camera_Backend
5456
// set camera lens as a value from 0 to 5
5557
bool set_lens(uint8_t lens) override;
5658

59+
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
5760
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
5861
bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) override;
62+
#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
5963

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

0 commit comments

Comments
 (0)