|
|
|
@ -201,6 +201,14 @@ void DataFlash_MAVLink::free_all_blocks()
@@ -201,6 +201,14 @@ void DataFlash_MAVLink::free_all_blocks()
|
|
|
|
|
_latest_block_len = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void DataFlash_MAVLink::stop_logging() |
|
|
|
|
{ |
|
|
|
|
if (_sending_to_client) { |
|
|
|
|
_sending_to_client = false; |
|
|
|
|
_last_response_time = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan, |
|
|
|
|
mavlink_message_t* msg, |
|
|
|
|
uint32_t seqno) |
|
|
|
@ -210,10 +218,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
@@ -210,10 +218,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
|
|
|
|
|
} |
|
|
|
|
if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) { |
|
|
|
|
Debug("Received stop-logging packet"); |
|
|
|
|
if (_sending_to_client) { |
|
|
|
|
_sending_to_client = false; |
|
|
|
|
_last_response_time = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
|
stop_logging(); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_START) { |
|
|
|
|