APM:Libraries
fw_uploader.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  uploader for IOMCU partly based on px4io_uploader.cpp from px4
17  */
18 /****************************************************************************
19  *
20  * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
21  *
22  * Redistribution and use in source and binary forms, with or without
23  * modification, are permitted provided that the following conditions
24  * are met:
25  *
26  * 1. Redistributions of source code must retain the above copyright
27  * notice, this list of conditions and the following disclaimer.
28  * 2. Redistributions in binary form must reproduce the above copyright
29  * notice, this list of conditions and the following disclaimer in
30  * the documentation and/or other materials provided with the
31  * distribution.
32  * 3. Neither the name PX4 nor the names of its contributors may be
33  * used to endorse or promote products derived from this software
34  * without specific prior written permission.
35  *
36  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
37  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
38  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
39  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
40  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
41  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
42  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
43  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
44  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
45  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
46  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
47  * POSSIBILITY OF SUCH DAMAGE.
48  *
49  ****************************************************************************/
50 
51 #include <AP_HAL/AP_HAL.h>
52 
53 #if HAL_WITH_IO_MCU
54 
55 #include "AP_IOMCU.h"
56 #include <AP_ROMFS/AP_ROMFS.h>
57 #include <AP_Math/crc.h>
58 
59 #define debug(fmt, args ...) do { hal.console->printf("IOMCU: " fmt "\n", ## args); } while(0)
60 
61 extern const AP_HAL::HAL &hal;
62 
63 /*
64  upload a firmware to the IOMCU
65  */
66 bool AP_IOMCU::upload_fw(const char *filename)
67 {
68  uint32_t fw_size;
69  fw = AP_ROMFS::find_file(filename, fw_size);
70 
71  // set baudrate for bootloader
72  uart.begin(115200, 256, 256);
73 
74  bool ret = false;
75 
76  /* look for the bootloader for 150 ms */
77  for (uint8_t i = 0; i < 15; i++) {
78  ret = sync();
79  if (ret) {
80  break;
81  }
82  hal.scheduler->delay(10);
83  }
84 
85  if (!ret) {
86  debug("IO update failed sync");
87  return false;
88  }
89 
90  uint32_t bl_rev;
91  ret = get_info(INFO_BL_REV, bl_rev);
92 
93  if (!ret) {
94  debug("Err: failed to contact bootloader");
95  return false;
96  }
97  if (bl_rev > BL_REV) {
98  debug("Err: unsupported bootloader revision %u", unsigned(bl_rev));
99  return false;
100  }
101  debug("found bootloader revision: %u", unsigned(bl_rev));
102 
103  ret = erase();
104  if (!ret) {
105  debug("erase failed");
106  return false;
107  }
108 
109  ret = program(fw_size);
110  if (!ret) {
111  debug("program failed");
112  return false;
113  }
114 
115  if (bl_rev <= 2) {
116  ret = verify_rev2(fw_size);
117  } else {
118  ret = verify_rev3(fw_size);
119  }
120 
121  if (!ret) {
122  debug("verify failed");
123  return false;
124  }
125 
126  ret = reboot();
127 
128  if (!ret) {
129  debug("reboot failed");
130  return false;
131  }
132 
133  debug("update complete");
134 
135  // sleep for enough time for the IO chip to boot
136  hal.scheduler->delay(100);
137 
138  return true;
139 }
140 
141 /*
142  receive a byte from the IO bootloader
143  */
144 bool AP_IOMCU::recv_byte_with_timeout(uint8_t *c, uint32_t timeout_ms)
145 {
146  uint32_t start = AP_HAL::millis();
147  do {
148  int16_t v = uart.read();
149  if (v >= 0) {
150  *c = uint8_t(v);
151  return true;
152  }
153  hal.scheduler->delay_microseconds(50);
154  } while (AP_HAL::millis() - start < timeout_ms);
155 
156  return false;
157 }
158 
159 /*
160  receive multiple bytes from the bootloader
161  */
162 bool AP_IOMCU::recv_bytes(uint8_t *p, uint32_t count)
163 {
164  bool ret = true;
165 
166  while (count--) {
167  ret = recv_byte_with_timeout(p++, 5000);
168  if (!ret) {
169  break;
170  }
171  }
172 
173  return ret;
174 }
175 
176 /*
177  discard any pending bytes
178  */
179 void AP_IOMCU::drain(void)
180 {
181  uint8_t c;
182  bool ret;
183 
184  do {
185  ret = recv_byte_with_timeout(&c, 40);
186  } while (ret);
187 }
188 
189 /*
190  send a byte to the bootloader
191  */
192 bool AP_IOMCU::send(uint8_t c)
193 {
194  if (uart.write(c) != 1) {
195  return false;
196  }
197  return true;
198 }
199 
200 /*
201  send a buffer to the bootloader
202  */
203 bool AP_IOMCU::send(const uint8_t *p, uint32_t count)
204 {
205  bool ret = true;
206 
207  while (count--) {
208  ret = send(*p++);
209  if (!ret) {
210  break;
211  }
212  }
213 
214  return ret;
215 }
216 
217 /*
218  wait for bootloader protocol sync
219  */
220 bool AP_IOMCU::get_sync(uint32_t timeout_ms)
221 {
222  uint8_t c[2];
223  bool ret;
224 
225  ret = recv_byte_with_timeout(c, timeout_ms);
226  if (!ret) {
227  return false;
228  }
229 
230  ret = recv_byte_with_timeout(c + 1, timeout_ms);
231  if (!ret) {
232  return ret;
233  }
234 
235  if ((c[0] != PROTO_INSYNC) || (c[1] != PROTO_OK)) {
236  debug("bad sync 0x%02x,0x%02x", c[0], c[1]);
237  return false;
238  }
239 
240  return true;
241 }
242 
243 /*
244  drain then get sync with bootloader
245  */
246 bool AP_IOMCU::sync()
247 {
248  drain();
249 
250  /* complete any pending program operation */
251  for (uint32_t i = 0; i < (PROG_MULTI_MAX + 6); i++) {
252  send(0);
253  }
254 
255  send(PROTO_GET_SYNC);
256  send(PROTO_EOC);
257  return get_sync();
258 }
259 
260 /*
261  get bootloader version
262  */
263 bool AP_IOMCU::get_info(uint8_t param, uint32_t &val)
264 {
265  bool ret;
266 
267  send(PROTO_GET_DEVICE);
268  send(param);
269  send(PROTO_EOC);
270 
271  ret = recv_bytes((uint8_t *)&val, sizeof(val));
272  if (!ret) {
273  return ret;
274  }
275 
276  return get_sync();
277 }
278 
279 /*
280  erase IO firmware
281  */
282 bool AP_IOMCU::erase()
283 {
284  debug("erase...");
285  send(PROTO_CHIP_ERASE);
286  send(PROTO_EOC);
287  return get_sync(10000);
288 }
289 
290 /*
291  send new firmware to bootloader
292  */
293 bool AP_IOMCU::program(uint32_t fw_size)
294 {
295  bool ret = false;
296  uint32_t sent = 0;
297 
298  if (fw_size & 3) {
299  return false;
300  }
301 
302  debug("programming %u bytes...", (unsigned)fw_size);
303 
304  while (sent < fw_size) {
305  /* get more bytes to program */
306  uint32_t n = fw_size - sent;
307  if (n > PROG_MULTI_MAX) {
308  n = PROG_MULTI_MAX;
309  }
310 
311  send(PROTO_PROG_MULTI);
312  send(n);
313  send(&fw[sent], n);
314  send(PROTO_EOC);
315 
316  ret = get_sync(1000);
317  if (!ret) {
318  debug("Failed at %u", (unsigned)sent);
319  return false;
320  }
321 
322  sent += n;
323  }
324  debug("upload OK");
325  return true;
326 }
327 
328 /*
329  verify firmware for a rev2 bootloader
330  */
331 bool AP_IOMCU::verify_rev2(uint32_t fw_size)
332 {
333  ssize_t count;
334  bool ret;
335  size_t sent = 0;
336 
337  debug("verify...");
338 
339  send(PROTO_CHIP_VERIFY);
340  send(PROTO_EOC);
341  ret = get_sync();
342  if (!ret) {
343  return ret;
344  }
345 
346  while (sent < fw_size) {
347  /* get more bytes to verify */
348  uint32_t n = fw_size - sent;
349  if (n > 4) {
350  n = 4;
351  }
352 
353  send(PROTO_READ_MULTI);
354  send(n);
355  send(PROTO_EOC);
356 
357 
358  for (uint8_t i = 0; i<n; i++) {
359  uint8_t c;
360  ret = recv_byte_with_timeout(&c, 5000);
361  if (!ret) {
362  debug("%d: got %d waiting for bytes", sent + i, ret);
363  return ret;
364  }
365  if (c != fw[sent+i]) {
366  debug("%d: got 0x%02x expected 0x%02x", sent + i, c, fw[sent+i]);
367  return false;
368  }
369  }
370 
371  sent += count;
372 
373  ret = get_sync();
374  if (!ret) {
375  debug("timeout waiting for post-verify sync");
376  return ret;
377  }
378  }
379 
380  return true;
381 }
382 
383 /*
384  verify firmware for a rev3 bootloader
385  */
386 bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
387 {
388  bool ret;
389  uint32_t sum = 0;
390  uint32_t bytes_read = 0;
391  uint32_t crc = 0;
392  uint32_t fw_size_remote;
393  uint8_t fill_blank = 0xff;
394 
395  debug("verify...");
396 
397  ret = get_info(INFO_FLASH_SIZE, fw_size_remote);
398  send(PROTO_EOC);
399 
400  if (!ret) {
401  debug("could not read firmware size");
402  return ret;
403  }
404 
405  /* read through the firmware file again and calculate the checksum */
406  while (bytes_read < fw_size_local) {
407  uint32_t n = fw_size_local - bytes_read;
408  if (n > 4) {
409  n = 4;
410  }
411 
412  /* calculate crc32 sum */
413  sum = crc_crc32(sum, &fw[bytes_read], n);
414 
415  bytes_read += n;
416  }
417 
418  /* fill the rest with 0xff */
419  while (bytes_read < fw_size_remote) {
420  sum = crc_crc32(sum, &fill_blank, 1);
421  bytes_read++;
422  }
423 
424  /* request CRC from IO */
425  send(PROTO_GET_CRC);
426  send(PROTO_EOC);
427 
428  ret = recv_bytes((uint8_t *)(&crc), sizeof(crc));
429  if (!ret) {
430  debug("did not receive CRC checksum");
431  return ret;
432  }
433 
434  /* compare the CRC sum from the IO with the one calculated */
435  if (sum != crc) {
436  debug("CRC wrong: received: 0x%x, expected: 0x%x", (unsigned)crc, (unsigned)sum);
437  return false;
438  }
439 
440  crc_is_ok = true;
441 
442  return true;
443 }
444 
445 /*
446  reboot IO MCU
447  */
448 bool AP_IOMCU::reboot()
449 {
450  send(PROTO_REBOOT);
451  hal.scheduler->delay(200);
452  send(PROTO_EOC);
453  hal.scheduler->delay(200);
454  return true;
455 }
456 
457 #endif // HAL_WITH_IO_MCU
uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size)
Definition: crc.cpp:140
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define debug(fmt, args ...)
virtual void delay(uint16_t ms)=0
uint32_t millis()
Definition: system.cpp:157
void sync(void)
POSIX Sync all pending file changes and metadata on ALL files.
Definition: posix.c:1058
float v
Definition: Printf.cpp:15
virtual void delay_microseconds(uint16_t us)=0
static const uint8_t * find_file(const char *name, uint32_t &size)
Definition: AP_ROMFS.cpp:30
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114