From 154b212545f2a823917da8d97f9389eb58225034 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 17 Aug 2017 20:04:42 +1000 Subject: [PATCH] GCS_MAVLink: move serial_control case to base class --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++++ libraries/GCS_MAVLink/GCS_serial_control.cpp | 14 +++++++++++--- 3 files changed, 16 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 73dadb4627..7f1d6f66e0 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -267,7 +267,7 @@ protected: void handle_common_camera_message(const mavlink_message_t *msg); void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const; void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio); - void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps); + void handle_serial_control(const mavlink_message_t *msg); void handle_common_message(mavlink_message_t *msg); void handle_setup_signing(const mavlink_message_t *msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index df85ff2f95..2e8df732e4 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1832,6 +1832,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg) handle_common_mission_message(msg); break; + case MAVLINK_MSG_ID_SERIAL_CONTROL: + handle_serial_control(msg); + break; + case MAVLINK_MSG_ID_GPS_RTCM_DATA: /* fall through */ case MAVLINK_MSG_ID_GPS_INPUT: diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 75fc2ca34a..8ab05d0911 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; /** handle a SERIAL_CONTROL message */ -void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) +void GCS_MAVLINK::handle_serial_control(const mavlink_message_t *msg) { mavlink_serial_control_t packet; mavlink_msg_serial_control_decode(msg, &packet); @@ -40,6 +40,8 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) return; } + AP_GPS *gps = get_gps(); + bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0; switch (packet.device) { @@ -53,11 +55,17 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) break; case SERIAL_CONTROL_DEV_GPS1: stream = port = hal.uartB; - gps.lock_port(0, exclusive); + if (gps == nullptr) { + return; + } + gps->lock_port(0, exclusive); break; case SERIAL_CONTROL_DEV_GPS2: stream = port = hal.uartE; - gps.lock_port(1, exclusive); + if (gps == nullptr) { + return; + } + gps->lock_port(1, exclusive); break; case SERIAL_CONTROL_DEV_SHELL: stream = hal.util->get_shell_stream();