From ef3306d4081c69f210e3490ac4ab36afa0efdf36 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Feb 2019 10:46:06 +1100 Subject: [PATCH] Copter: fixed crash on mavlink send before pos_control is allocated --- ArduCopter/GCS_Mavlink.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 4455257da4..fdfdcdd684 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -120,6 +120,9 @@ void GCS_MAVLINK_Copter::send_position_target_global_int() void GCS_MAVLINK_Copter::send_nav_controller_output() const { + if (!copter.ap.initialised) { + return; + } const Vector3f &targets = copter.attitude_control->get_att_target_euler_cd(); const Copter::Mode *flightmode = copter.flightmode; mavlink_msg_nav_controller_output_send(