Browse Source

GCS_MAVLink: convert to using hal.serial() instead of hal.uartX

zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
6df118e7b4
  1. 2
      libraries/GCS_MAVLink/GCS.cpp
  2. 4
      libraries/GCS_MAVLink/GCS_serial_control.cpp

2
libraries/GCS_MAVLink/GCS.cpp

@ -110,7 +110,7 @@ void GCS::send_named_float(const char *name, float value) const
/* /*
install an alternative protocol handler. This allows another install an alternative protocol handler. This allows another
protocol to take over the link if MAVLink goes idle. It is used to protocol to take over the link if MAVLink goes idle. It is used to
allow for the AP_BLHeli pass-thru protocols to run on hal.uartA allow for the AP_BLHeli pass-thru protocols to run on hal.serial(0)
*/ */
bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler) bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
{ {

4
libraries/GCS_MAVLink/GCS_serial_control.cpp

@ -62,11 +62,11 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg)
break; break;
} }
case SERIAL_CONTROL_DEV_GPS1: case SERIAL_CONTROL_DEV_GPS1:
stream = port = hal.uartB; stream = port = hal.serial(3);
AP::gps().lock_port(0, exclusive); AP::gps().lock_port(0, exclusive);
break; break;
case SERIAL_CONTROL_DEV_GPS2: case SERIAL_CONTROL_DEV_GPS2:
stream = port = hal.uartE; stream = port = hal.serial(4);
AP::gps().lock_port(1, exclusive); AP::gps().lock_port(1, exclusive);
break; break;
case SERIAL_CONTROL_DEV_SHELL: case SERIAL_CONTROL_DEV_SHELL:

Loading…
Cancel
Save