mirror of https://github.com/ArduPilot/ardupilot
Copter: send a camera_feedback message when there is a camera trigger
This commit is contained in:
parent
b48edf479b
commit
b587025ad1
|
@ -593,6 +593,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_CAMERA_FEEDBACK:
|
||||||
|
#if CAMERA == ENABLED
|
||||||
|
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
|
||||||
|
camera.send_feedback(chan, gps, ahrs, current_loc);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MSG_STATUSTEXT:
|
case MSG_STATUSTEXT:
|
||||||
CHECK_PAYLOAD_SIZE(STATUSTEXT);
|
CHECK_PAYLOAD_SIZE(STATUSTEXT);
|
||||||
send_statustext(chan);
|
send_statustext(chan);
|
||||||
|
|
|
@ -925,6 +925,7 @@ static void do_take_picture()
|
||||||
{
|
{
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera.trigger_pic();
|
camera.trigger_pic();
|
||||||
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||||
if (should_log(MASK_LOG_CAMERA)) {
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue