mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: Add Camera_Mount handler for CAMERA_CAPTURE_STATUS request
This commit is contained in:
parent
ac313b6d7a
commit
2f9b9e2452
|
@ -88,4 +88,13 @@ void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// send camera capture status message to GCS
|
||||||
|
void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const
|
||||||
|
{
|
||||||
|
AP_Mount* mount = AP::mount();
|
||||||
|
if (mount != nullptr) {
|
||||||
|
return mount->send_camera_capture_status(get_mount_instance(), chan);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||||
|
|
|
@ -59,6 +59,9 @@ public:
|
||||||
|
|
||||||
// send camera settings message to GCS
|
// send camera settings message to GCS
|
||||||
void send_camera_settings(mavlink_channel_t chan) const override;
|
void send_camera_settings(mavlink_channel_t chan) const override;
|
||||||
|
|
||||||
|
// send camera capture status message to GCS
|
||||||
|
void send_camera_capture_status(mavlink_channel_t chan) const override;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue