diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 9b199c4639..ef9f9928ef 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -573,6 +573,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, switch(id) { case MSG_HEARTBEAT: CHECK_PAYLOAD_SIZE(HEARTBEAT); + gcs[chan-MAVLINK_COMM_0].last_heartbeat_time = hal.scheduler->millis(); send_heartbeat(chan); break; @@ -692,6 +693,12 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, send_hwstatus(chan); break; + case MSG_FENCE_STATUS: + case MSG_WIND: + case MSG_RANGEFINDER: + // unused + break; + case MSG_RETRY_DEFERRED: break; // just here to prevent a warning } @@ -862,14 +869,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { }; -GCS_MAVLINK::GCS_MAVLINK() : - packet_drops(0), - waypoint_send_timeout(1000), // 1 second - waypoint_receive_timeout(1000) // 1 second -{ - AP_Param::setup_object_defaults(this, var_info); -} - void GCS_MAVLINK::init(AP_HAL::UARTDriver* port) { @@ -997,6 +996,10 @@ GCS_MAVLINK::data_stream_send(void) return; } + if (!in_mavlink_delay && !motors.armed()) { + handle_log_send(DataFlash); + } + gcs_out_of_time = false; if (_queued_parameter != NULL) { @@ -2004,6 +2007,12 @@ mission_failed: break; } + case MAVLINK_MSG_ID_LOG_REQUEST_LIST ... MAVLINK_MSG_ID_LOG_REQUEST_END: + if (!in_mavlink_delay && !motors.armed()) { + handle_log_message(msg, DataFlash); + } + break; + /* To-Do: add back support for polygon type fence #if AC_FENCE == ENABLED // receive an AP_Limits fence point from GCS and store in EEPROM