mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: Add handler for CAMERA_CAPTURE_STATUS request
This commit is contained in:
parent
477534b446
commit
ac313b6d7a
|
@ -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
|
||||
{
|
||||
|
|
|
@ -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
|
||||
//
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue