49     case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
    52     case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
    55     case MAVLINK_MSG_ID_LOG_ERASE:
    58     case MAVLINK_MSG_ID_LOG_REQUEST_END:
    70         link.
send_text(MAV_SEVERITY_INFO, 
"Log download in progress");
    74     mavlink_log_request_list_t packet;
    75     mavlink_msg_log_request_list_decode(msg, &packet);
   113             link.
send_text(MAV_SEVERITY_INFO, 
"Log download in progress");
   118     mavlink_log_request_data_t packet;
   119     mavlink_msg_log_request_data_decode(msg, &packet);
   128         if (packet.id > num_logs || packet.id < 1) {
   132         uint32_t time_utc, size;
   172     mavlink_log_request_end_t packet;
   173     mavlink_msg_log_request_end_decode(msg, &packet);
   198 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL   200     const uint8_t num_sends = 40;
   202     uint8_t num_sends = 1;
   207     #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX   215     for (uint8_t i=0; i<num_sends; i++) {
   236     uint32_t size, time_utc;
   273     mavlink_log_data_t packet;
   284         memset(&packet.data[ret], 0, 90-ret);
   291                                     MAVLINK_MSG_ID_LOG_DATA,
   292                                     (
const char *)&packet,
   293                                     MAVLINK_MSG_ID_LOG_DATA_MIN_LEN,
   294                                     MAVLINK_MSG_ID_LOG_DATA_LEN,
   295                                     MAVLINK_MSG_ID_LOG_DATA_CRC);
 bool get_soft_armed() const
uint16_t _log_next_list_entry
bool should_handle_log_message()
MAVLink transport control class. 
Interface definition for the various Ground Control System. 
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- 
virtual bool usb_connected(void)=0
bool handle_log_send_data()
mavlink_channel_t get_chan() const
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
void handle_log_send_listing()
#define HAVE_PAYLOAD_SPACE(chan, id)
uint16_t _log_last_list_entry
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg)
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
bool WritesEnabled() const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg)
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg)
uint32_t get_last_heartbeat_time() const
GCS_MAVLINK * _log_sending_link
uint32_t _log_data_offset
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg)
uint32_t _log_data_remaining
bool vehicle_is_armed() const
uint16_t get_num_logs(void)