File tree 3 files changed +7
-3
lines changed
3 files changed +7
-3
lines changed Original file line number Diff line number Diff line change @@ -82,10 +82,10 @@ class AP_Camera_Backend
82
82
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
83
83
virtual bool set_tracking (TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false ; }
84
84
85
- #if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
86
85
// set camera lens as a value from 0 to 5
87
86
virtual bool set_lens (uint8_t lens) { return false ; }
88
87
88
+ #if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
89
89
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
90
90
virtual bool set_camera_source (AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false ; }
91
91
#endif
Original file line number Diff line number Diff line change @@ -70,17 +70,17 @@ bool AP_Camera_Mount::set_lens(uint8_t lens)
70
70
return false ;
71
71
}
72
72
73
+ #if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
73
74
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
74
75
bool AP_Camera_Mount::set_camera_source (AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source)
75
76
{
76
- #if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
77
77
AP_Mount* mount = AP::mount ();
78
78
if (mount != nullptr ) {
79
79
return mount->set_camera_source (get_mount_instance (), (uint8_t )primary_source, (uint8_t )secondary_source);
80
80
}
81
- #endif
82
81
return false ;
83
82
}
83
+ #endif
84
84
85
85
// send camera information message to GCS
86
86
void AP_Camera_Mount::send_camera_information (mavlink_channel_t chan) const
Original file line number Diff line number Diff line change 22
22
23
23
#if AP_CAMERA_MOUNT_ENABLED
24
24
25
+ #include " AP_Camera.h"
26
+
25
27
class AP_Camera_Mount : public AP_Camera_Backend
26
28
{
27
29
public:
@@ -54,8 +56,10 @@ class AP_Camera_Mount : public AP_Camera_Backend
54
56
// set camera lens as a value from 0 to 5
55
57
bool set_lens (uint8_t lens) override ;
56
58
59
+ #if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
57
60
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
58
61
bool set_camera_source (AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) override ;
62
+ #endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
59
63
60
64
// send camera information message to GCS
61
65
void send_camera_information (mavlink_channel_t chan) const override ;
You can’t perform that action at this time.
0 commit comments