mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Rover: add MOUNT_STATUS to STREAM_EXTRA3
This commit is contained in:
parent
8ef2948f27
commit
48c00728a7
@ -516,6 +516,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
send_rangefinder(chan);
|
||||
break;
|
||||
|
||||
case MSG_MOUNT_STATUS:
|
||||
#if MOUNT == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
|
||||
camera_mount.status_msg(chan);
|
||||
#endif // MOUNT == ENABLED
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU2:
|
||||
case MSG_LIMITS_STATUS:
|
||||
case MSG_FENCE_STATUS:
|
||||
@ -746,6 +753,7 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
send_message(MSG_HWSTATUS);
|
||||
send_message(MSG_RANGEFINDER);
|
||||
send_message(MSG_SYSTEM_TIME);
|
||||
send_message(MSG_MOUNT_STATUS);
|
||||
}
|
||||
}
|
||||
|
||||
@ -1102,12 +1110,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
camera_mount.control_msg(msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MOUNT_STATUS:
|
||||
{
|
||||
camera_mount.status_msg(msg, chan);
|
||||
break;
|
||||
}
|
||||
#endif // MOUNT == ENABLED
|
||||
|
||||
case MAVLINK_MSG_ID_RADIO:
|
||||
|
Loading…
Reference in New Issue
Block a user