Browse Source

GCS_MAVLink: avoid using global chan to uart mapping

This is an instance method, so it has a pointer to its own
uart
mission-4.1.18
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
c3e70e477d
  1. 13
      libraries/GCS_MAVLink/GCS_Param.cpp

13
libraries/GCS_MAVLink/GCS_Param.cpp

@ -102,21 +102,20 @@ GCS_MAVLINK::queued_param_send() @@ -102,21 +102,20 @@ GCS_MAVLINK::queued_param_send()
*/
bool GCS_MAVLINK::have_flow_control(void)
{
if (!valid_channel(chan)) {
if (_port == nullptr) {
return false;
}
if (mavlink_comm_port[chan] == nullptr) {
return false;
if (_port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) {
return true;
}
if (chan == MAVLINK_COMM_0) {
// assume USB console has flow control
return hal.gpio->usb_connected() || mavlink_comm_port[chan]->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE;
} else {
// all other channels
return mavlink_comm_port[chan]->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE;
return hal.gpio->usb_connected();
}
return false;
}

Loading…
Cancel
Save