From 3a113a31bb25a67fec80c36c865e3faf665588de Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 2 Oct 2019 15:15:27 +0900 Subject: [PATCH] GCS_MAVLink: minor fix to set_message_interval --- libraries/GCS_MAVLink/GCS_Common.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index af7282bd3f..b13e302d14 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2265,9 +2265,9 @@ MAV_RESULT GCS::set_message_interval(uint8_t port_num, uint32_t msg_id, int32_t { uint8_t channel = get_channel_from_port_number(port_num); - if (channel < MAVLINK_COMM_NUM_BUFFERS && chan(channel) != nullptr) - { + if ((channel < MAVLINK_COMM_NUM_BUFFERS) && (chan(channel) != nullptr)) { chan(channel)->set_message_interval(msg_id, interval_us); + return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; @@ -2275,8 +2275,9 @@ MAV_RESULT GCS::set_message_interval(uint8_t port_num, uint32_t msg_id, int32_t uint8_t GCS::get_channel_from_port_number(uint8_t port_num) { + const AP_HAL::UARTDriver *u = AP::serialmanager().get_serial_by_id(port_num); for (uint8_t i=0; iget_uart() == AP::serialmanager().get_serial_by_id(port_num)) { + if (chan(i)->get_uart() == u) { return i; } }