|
|
|
@ -38,13 +38,12 @@ void GCS_MAVLINK::handle_log_message(mavlink_message_t *msg, DataFlash_Class &da
@@ -38,13 +38,12 @@ void GCS_MAVLINK::handle_log_message(mavlink_message_t *msg, DataFlash_Class &da
|
|
|
|
|
handle_log_request_data(msg, dataflash); |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_MSG_ID_LOG_ERASE: |
|
|
|
|
dataflash.EraseAll(); |
|
|
|
|
handle_log_request_erase(msg, dataflash); |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_END: |
|
|
|
|
_log_sending = false; |
|
|
|
|
handle_log_request_end(msg, dataflash); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -126,6 +125,31 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
@@ -126,6 +125,31 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
|
|
|
|
|
handle_log_send(dataflash); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
handle request to erase log data |
|
|
|
|
*/ |
|
|
|
|
void GCS_MAVLINK::handle_log_request_erase(mavlink_message_t *msg, DataFlash_Class &dataflash) |
|
|
|
|
{ |
|
|
|
|
mavlink_log_request_data_t packet; |
|
|
|
|
mavlink_msg_log_request_data_decode(msg, &packet); |
|
|
|
|
if (mavlink_check_target(packet.target_system, packet.target_component)) |
|
|
|
|
return; |
|
|
|
|
|
|
|
|
|
dataflash.EraseAll(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
handle request to stop transfer and resume normal logging |
|
|
|
|
*/ |
|
|
|
|
void GCS_MAVLINK::handle_log_request_end(mavlink_message_t *msg, DataFlash_Class &dataflash) |
|
|
|
|
{ |
|
|
|
|
mavlink_log_request_data_t packet; |
|
|
|
|
mavlink_msg_log_request_data_decode(msg, &packet); |
|
|
|
|
if (mavlink_check_target(packet.target_system, packet.target_component)) |
|
|
|
|
return; |
|
|
|
|
_log_sending = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
trigger sending of log messages if there are some pending |
|
|
|
|
*/ |
|
|
|
|