From 8d7fadfdfcfb45a15a18028b7732e4f0562dab67 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 21 Aug 2017 10:54:03 +1000 Subject: [PATCH] GCS_MAVLink: set _initialised as last thing --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 8ada9f3877..972aef064a 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -61,7 +61,6 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) chan = mav_chan; mavlink_comm_port[chan] = _port; - initialised = true; _queued_parameter = nullptr; snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan); @@ -69,6 +68,8 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan); _perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_update_name); + + initialised = true; }