GCS_MAVLink: Add UART option to not override streamrates

This commit is contained in:
Stephen Dade 2021-11-28 20:43:04 +11:00 committed by Peter Barker
parent dbd6cd1a58
commit 038ae432ab
1 changed files with 4 additions and 1 deletions

View File

@ -3559,7 +3559,10 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
break;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
handle_request_data_stream(msg);
// only pass if override is not selected
if (!(_port->get_options() & _port->OPTION_NOSTREAMOVERRIDE)) {
handle_request_data_stream(msg);
}
break;
case MAVLINK_MSG_ID_DATA96: