Plane: Implement MSG_CAMERA_FEEDBACK on planes

This commit is contained in:
Arthur Benemann 2014-11-10 17:27:59 -08:00 committed by Randy Mackay
parent fe9e68f88c
commit 5e2d7b1eaa

View File

@ -643,6 +643,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
#endif
break;
case MSG_CAMERA_FEEDBACK:
#if CAMERA == ENABLED
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
camera.send_feedback(chan, gps, ahrs, current_loc);
#endif
break;
case MSG_BATTERY2:
CHECK_PAYLOAD_SIZE(BATTERY2);
gcs[chan-MAVLINK_COMM_0].send_battery2(battery);