mirror of https://github.com/ArduPilot/ardupilot
Plane: append MOUNT_STATUS message to STREAM_EXTRA3 messages
This commit is contained in:
parent
9b5684d007
commit
9ae443f2a2
|
@ -636,6 +636,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||||
gcs[chan-MAVLINK_COMM_0].send_ahrs2(ahrs);
|
gcs[chan-MAVLINK_COMM_0].send_ahrs2(ahrs);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_MOUNT_STATUS:
|
||||||
|
#if MOUNT == ENABLED
|
||||||
|
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
|
||||||
|
camera_mount.status_msg(chan);
|
||||||
|
#endif // MOUNT == ENABLED
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_HWSTATUS:
|
case MSG_HWSTATUS:
|
||||||
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||||
send_hwstatus(chan);
|
send_hwstatus(chan);
|
||||||
|
@ -898,6 +905,7 @@ GCS_MAVLINK::data_stream_send(void)
|
||||||
send_message(MSG_WIND);
|
send_message(MSG_WIND);
|
||||||
send_message(MSG_RANGEFINDER);
|
send_message(MSG_RANGEFINDER);
|
||||||
send_message(MSG_SYSTEM_TIME);
|
send_message(MSG_SYSTEM_TIME);
|
||||||
|
send_message(MSG_MOUNT_STATUS);
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
send_message(MSG_TERRAIN);
|
send_message(MSG_TERRAIN);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1490,12 +1498,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
camera_mount.control_msg(msg);
|
camera_mount.control_msg(msg);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_MOUNT_STATUS:
|
|
||||||
{
|
|
||||||
camera_mount.status_msg(msg, chan);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif // MOUNT == ENABLED
|
#endif // MOUNT == ENABLED
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_RADIO:
|
case MAVLINK_MSG_ID_RADIO:
|
||||||
|
|
Loading…
Reference in New Issue