APM:Libraries
DataFlash_MAVLinkLogTransfer.cpp
Go to the documentation of this file.
1 /*
2  MAVLink logfile transfer functions
3  */
4 
5 /*
6  This program is free software: you can redistribute it and/or modify
7  it under the terms of the GNU General Public License as published by
8  the Free Software Foundation, either version 3 of the License, or
9  (at your option) any later version.
10 
11  This program is distributed in the hope that it will be useful,
12  but WITHOUT ANY WARRANTY; without even the implied warranty of
13  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  GNU General Public License for more details.
15 
16  You should have received a copy of the GNU General Public License
17  along with this program. If not, see <http://www.gnu.org/licenses/>.
18  */
19 
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <DataFlash/DataFlash.h>
23 #include <GCS_MAVLink/GCS.h> // for LOG_ENTRY
24 
25 extern const AP_HAL::HAL& hal;
26 
27 // We avoid doing log messages when timing is critical:
29 {
30  if (!WritesEnabled()) {
31  // this is currently used as a proxy for "in_mavlink_delay"
32  return false;
33  }
34  if (vehicle_is_armed()) {
35  return false;
36  }
37  return true;
38 }
39 
43 void DataFlash_Class::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg)
44 {
46  return;
47  }
48  switch (msg->msgid) {
49  case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
50  handle_log_request_list(link, msg);
51  break;
52  case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
53  handle_log_request_data(link, msg);
54  break;
55  case MAVLINK_MSG_ID_LOG_ERASE:
56  handle_log_request_erase(link, msg);
57  break;
58  case MAVLINK_MSG_ID_LOG_REQUEST_END:
59  handle_log_request_end(link, msg);
60  break;
61  }
62 }
63 
67 void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg)
68 {
69  if (_log_sending_link != nullptr) {
70  link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
71  return;
72  }
73 
74  mavlink_log_request_list_t packet;
75  mavlink_msg_log_request_list_decode(msg, &packet);
76 
77  _log_listing = false;
78  _log_sending = false;
79 
81  if (_log_num_logs == 0) {
84  } else {
85  _log_next_list_entry = packet.start;
86  _log_last_list_entry = packet.end;
87 
90  }
91  if (_log_next_list_entry < 1) {
93  }
94  }
95 
96  _log_listing = true;
97  _log_sending_link = &link;
99 }
100 
101 
105 void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *msg)
106 {
107  if (_log_sending_link != nullptr) {
108  // some GCS (e.g. MAVProxy) attempt to stream request_data
109  // messages when they're filling gaps in the downloaded logs.
110  // This channel check avoids complaining to them, at the cost
111  // of silently dropping any repeated attempts to start logging
112  if (_log_sending_link->get_chan() != link.get_chan()) {
113  link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
114  }
115  return;
116  }
117 
118  mavlink_log_request_data_t packet;
119  mavlink_msg_log_request_data_decode(msg, &packet);
120 
121  _in_log_download = true;
122 
123  _log_listing = false;
124  if (!_log_sending || _log_num_data != packet.id) {
125  _log_sending = false;
126 
127  uint16_t num_logs = get_num_logs();
128  if (packet.id > num_logs || packet.id < 1) {
129  return;
130  }
131 
132  uint32_t time_utc, size;
133  get_log_info(packet.id, size, time_utc);
134  _log_num_data = packet.id;
135  _log_data_size = size;
136 
137  uint16_t end;
138  get_log_boundaries(packet.id, _log_data_page, end);
139  }
140 
141  _log_data_offset = packet.ofs;
144  } else {
146  }
147  if (_log_data_remaining > packet.count) {
148  _log_data_remaining = packet.count;
149  }
150  _log_sending = true;
151  _log_sending_link = &link;
152 
153  handle_log_send();
154 }
155 
159 void DataFlash_Class::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *msg)
160 {
161  // mavlink_log_erase_t packet;
162  // mavlink_msg_log_erase_decode(msg, &packet);
163 
164  EraseAll();
165 }
166 
170 void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_t *msg)
171 {
172  mavlink_log_request_end_t packet;
173  mavlink_msg_log_request_end_decode(msg, &packet);
174  _in_log_download = false;
175  _log_sending = false;
176  _log_sending_link = nullptr;
177 }
178 
183 {
184  if (_log_sending_link == nullptr) {
185  return;
186  }
187  if (hal.util->get_soft_armed()) {
188  // might be flying
189  return;
190  }
191  if (_log_listing) {
193  }
194  if (!_log_sending) {
195  return;
196  }
197 
198 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
199  // assume USB speeds in SITL for the purposes of log download
200  const uint8_t num_sends = 40;
201 #else
202  uint8_t num_sends = 1;
204  // when on USB we can send a lot more data
205  num_sends = 250;
206  } else if (_log_sending_link->have_flow_control()) {
207  #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
208  num_sends = 80;
209  #else
210  num_sends = 10;
211  #endif
212  }
213 #endif
214 
215  for (uint8_t i=0; i<num_sends; i++) {
216  if (_log_sending) {
217  if (!handle_log_send_data()) break;
218  }
219  }
220 }
221 
226 {
227  if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_ENTRY)) {
228  // no space
229  return;
230  }
232  // give a heartbeat a chance
233  return;
234  }
235 
236  uint32_t size, time_utc;
237  if (_log_next_list_entry == 0) {
238  size = 0;
239  time_utc = 0;
240  } else {
241  get_log_info(_log_next_list_entry, size, time_utc);
242  }
243  mavlink_msg_log_entry_send(_log_sending_link->get_chan(),
247  time_utc,
248  size);
249  if (_log_next_list_entry == _log_last_list_entry) {
250  _log_listing = false;
251  _log_sending_link = nullptr;
252  } else {
254  }
255 }
256 
261 {
262  if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_DATA)) {
263  // no space
264  return false;
265  }
267  // give a heartbeat a chance
268  return false;
269  }
270 
271  int16_t ret = 0;
272  uint32_t len = _log_data_remaining;
273  mavlink_log_data_t packet;
274 
275  if (len > 90) {
276  len = 90;
277  }
278  ret = get_log_data(_log_num_data, _log_data_page, _log_data_offset, len, packet.data);
279  if (ret < 0) {
280  // report as EOF on error
281  ret = 0;
282  }
283  if (ret < 90) {
284  memset(&packet.data[ret], 0, 90-ret);
285  }
286 
287  packet.ofs = _log_data_offset;
288  packet.id = _log_num_data;
289  packet.count = ret;
290  _mav_finalize_message_chan_send(_log_sending_link->get_chan(),
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);
296 
297  _log_data_offset += len;
298  _log_data_remaining -= len;
299  if (ret < 90 || _log_data_remaining == 0) {
300  _log_sending = false;
301  _log_sending_link = nullptr;
302  }
303  return true;
304 }
bool get_soft_armed() const
Definition: Util.h:15
uint16_t _log_next_list_entry
Definition: DataFlash.h:343
uint8_t _log_sending
Definition: DataFlash.h:337
Interface definition for the various Ground Control System.
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual bool usb_connected(void)=0
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
Definition: DataFlash.cpp:522
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
uint16_t _log_last_list_entry
Definition: DataFlash.h:346
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
Definition: DataFlash.cpp:534
uint32_t millis()
Definition: system.cpp:157
bool _in_log_download
Definition: DataFlash.h:340
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)
Definition: DataFlash.cpp:528
bool WritesEnabled() const
Definition: DataFlash.h:91
uint16_t _log_num_data
Definition: DataFlash.h:352
uint16_t _log_data_page
Definition: DataFlash.h:364
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg)
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
GCS_MAVLINK * _log_sending_link
Definition: DataFlash.h:366
uint32_t _log_data_offset
Definition: DataFlash.h:355
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg)
uint8_t _log_listing
Definition: DataFlash.h:336
uint32_t _log_data_size
Definition: DataFlash.h:358
uint16_t _log_num_logs
Definition: DataFlash.h:349
uint32_t _log_data_remaining
Definition: DataFlash.h:361
bool vehicle_is_armed() const
Definition: DataFlash.h:216
uint16_t get_num_logs(void)
Definition: DataFlash.cpp:540