Skip to content

Commit

Permalink
AP_Mount: add HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Mar 22, 2024
1 parent 49577b8 commit 088dc98
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 0 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_Mount/AP_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -833,6 +833,7 @@ bool AP_Mount::set_lens(uint8_t instance, uint8_t lens)
return backend->set_lens(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::set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source)
Expand All @@ -843,6 +844,7 @@ bool AP_Mount::set_camera_source(uint8_t instance, uint8_t primary_source, uint8
}
return backend->set_camera_source(primary_source, secondary_source);
}
#endif

// send camera information message to GCS
void AP_Mount::send_camera_information(uint8_t instance, mavlink_channel_t chan) const
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Mount/AP_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,9 +250,11 @@ class AP_Mount
// set camera lens as a value from 0 to 5
bool set_lens(uint8_t instance, uint8_t 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 set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source);
#endif

// send camera information message to GCS
void send_camera_information(uint8_t instance, mavlink_channel_t chan) const;
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Mount/AP_Mount_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -182,9 +182,11 @@ class AP_Mount_Backend
// set camera lens as a value from 0 to 5
virtual bool 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
// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t
virtual bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) { return false; }
#endif

// send camera information message to GCS
virtual void send_camera_information(mavlink_channel_t chan) const {}
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_Mount/AP_Mount_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,3 +53,8 @@
#ifndef AP_MOUNT_POI_TO_LATLONALT_ENABLED
#define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024
#endif

// set camera source is supported on gimbals that may have more than one lens
#ifndef HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
#define HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SIYI_ENABLED || HAL_MOUNT_XACTI_ENABLED || HAL_MOUNT_VIEWPRO_ENABLED
#endif

0 comments on commit 088dc98

Please sign in to comment.