AP_Mount: Add handler for CAMERA_CAPTURE_STATUS request

This commit is contained in:
Nick Exton 2023-09-12 12:23:17 +10:00 committed by Randy Mackay
parent 477534b446
commit ac313b6d7a
3 changed files with 16 additions and 0 deletions

View File

@ -850,6 +850,16 @@ void AP_Mount::send_camera_settings(uint8_t instance, mavlink_channel_t chan) co
backend->send_camera_settings(chan);
}
// send camera capture status message to GCS
void AP_Mount::send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const
{
auto *backend = get_instance(instance);
if (backend == nullptr) {
return;
}
backend->send_camera_capture_status(chan);
}
// get rangefinder distance. Returns true on success
bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const
{

View File

@ -256,6 +256,9 @@ public:
// send camera settings message to GCS
void send_camera_settings(uint8_t instance, mavlink_channel_t chan) const;
// send camera capture status message to GCS
void send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const;
//
// rangefinder
//

View File

@ -182,6 +182,9 @@ public:
// send camera settings message to GCS
virtual void send_camera_settings(mavlink_channel_t chan) const {}
// send camera capture status message to GCS
virtual void send_camera_capture_status(mavlink_channel_t chan) const {}
#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// get poi information. Returns true on success and fills in gimbal attitude, location and poi location
bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc);