Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
px4_flash.c
Go to the documentation of this file.
1/*
2 * Copyright (C) Kevin van Hecke
3 *
4 * This file is part of paparazzi
5 *
6 * paparazzi 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 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi 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 paparazzi; see the file COPYING. If not, see
18 * <http://www.gnu.org/licenses/>.
19 */
29#include "mcu_periph/sys_time_arch.h"
31
32// Serial Port
33#include "mcu_periph/uart.h"
35
36#include "mcu.h"
37#include "led.h"
38#include "mcu_arch.h"
39
40#ifdef STM32_MCU_ARCH_H // scb_reset_system from OpenCM3
41#include <libopencm3/cm3/scb.h>
42#endif
43
44#include "mcu_periph/sys_time.h"
45#ifdef INTER_MCU_AP
47// define coms link for px4io f1
48#define PX4IO_PORT (&((PX4IO_UART).device))
49#endif
50
51#define FLASH_PORT (&((FLASH_UART).device))
52
53#ifndef PX4_IO_FORCE_PROG
54#define PX4_IO_FORCE_PROG FALSE
55#elif (PX4_IO_FORCE_PROG == TRUE)
56PRINT_CONFIG_MSG("Using PX4_IO force program. Don't forget to re-program AP with this option off!");
57#endif
58
59// weird that these below are not in protocol.h, which is from the firmware px4 repo
60// below is copied from qgroundcontrol:
61#define PROTO_INSYNC 0x12
62#define PROTO_EOC 0x20
63// Reply bytes
64#define PROTO_OK 0x10
65#define PROTO_FAILED 0x11
66#define PROTO_INVALID 0x13
67// Command bytes
68#define PROTO_GET_SYNC 0x21
69#define PROTO_GET_DEVICE 0x22
70#define PROTO_CHIP_ERASE 0x23
71#define PROTO_CHIP_VERIFY 0x24
72#define PROTO_PROG_MULTI 0x27
73#define PROTO_GET_CRC 0x29
74#define PROTO_BOOT 0x30
75
78
79void px4flash_init(void)
80{
81 setToBootloaderMode = false;
82#ifdef INTER_MCU_AP
83 px4ioRebootTimeout = false;
84 px4iobl_tid = sys_time_register_timer(12.0, NULL); //20 (fbw pprz bl timeout)-5 (px4 fmu bl timeout) - 3 (uncertainty and random delays)
85#endif
86}
87
89{
90#ifdef INTER_MCU_AP
94 //for unknown reasons, 1500000 baud does not work reliably after prolonged times.
95 //I suspect a temperature related issue, combined with the fbw f1 crystal which is out of specs
96 //After a initial period on 1500000, revert to 230400
97 //We still start at 1500000 to remain compatible with original PX4 firmware. (which always runs at 1500000)
99 }
100 if (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
101 if (!setToBootloaderMode) {
102 //ignore anything coming from IO if not in bootloader mode (which should be nothing)
103 } else {
104 //relay everything from IO to the laptop
105 while (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
106 unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
107 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, b);
108 }
109 }
110 }
111#endif
112
113 //TODO: check if bootloader timeout was surpassed
114 if (FLASH_PORT->char_available(FLASH_PORT->periph) && !setToBootloaderMode) {
115 //check whether this is flash related communication, and for who (ap/fbw)
116 int state = 0;
118 unsigned char b = FLASH_PORT->get_byte(FLASH_PORT->periph);
119 switch (state) {
120 case (0) :
121 if (b == 'p') { state++; } else { return; }
122 break;
123 case (1) :
124 if (b == 'p') { state++; } else { return; }
125 break;
126 case (2) :
127 if (b == 'r') { state++; } else { return; }
128 break;
129 case (3) :
130 if (b == 'z') { state++; } else { return; }
131 break;
132 default :
133 break;
134 }
135 }
136
137 if (state != 4) {return;}
138 //TODO: check if/how this interferes with flashing original PX4 firmware
139 unsigned char target = FLASH_PORT->get_byte(FLASH_PORT->periph);
140 if (target == '1') { //target ap
141 //the target is the ap, so reboot to PX4 bootloader
142#if defined(CHIBIOS_MCU_ARCH_H)
144#elif defined(STM32_MCU_ARCH_H)
146#endif
147 } else { // target fbw
148#ifdef INTER_MCU_AP
149 //the target is the fbw, so reboot the fbw and switch to relay mode
150
151 //first check if the bootloader has not timeout:
152 if (px4ioRebootTimeout) {
153 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'T');
154 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'I');
155 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'M');
156 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'E');
157 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'O');
158 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'U');
159 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'T'); // use 7 chars as answer
160 return;
161 }
162
163 //stop all intermcu communication:
165
167
168 /*
169 * The PX4_IO_FORCE_PROG define is very usefull, if for whatever reason the (normal, not bootloader) firmware on the IO chip became disfunct.
170 * In that case:
171 * 1. enable this define
172 * 2. build and upload the fmu f4 chip (ap target in pprz center)
173 * 3. build the io code, and convert the firmware using the following command:
174 * $(PAPARAZZI_SRC)/sw/tools/px4/px_mkfw.py --prototype $(PAPARAZZI_SRC)/sw/tools/px4/px4io-v2.prototype --image $(PAPARAZZI_HOME)/var/aircrafts/<AC_NAME>/fbw/fbw.bin > $(PAPARAZZI_HOME)/var/aircrafts/<AC_NAME>/fbw/fbw.px4
175 * 4. Start the following command:
176 * $(PAPARAZZI_SRC)/sw/tools/px4/px_uploader.py --port "/dev/ttyACM0" $(PAPARAZZI_SRC)/var/aircrafts/<AC_NAME>/fbw/fbw.px4
177 * Optional 5&6:
178 * 5a. Either, boot the Pixhawk (reconnect usb) holding the IO reset button until the FMU led stops blinking fast (i.e. exits its own bootloader)
179 * 5b Or, press the IO reset button on the pixhawk
180 * 6. Watch the output of the command of step 4, it should recognize the IO bootloader and start flashing. If not try repeating step 5a.
181 * 7. Don forget to disable the define and upload the ap again :)
182 */
183
184#if !PX4_IO_FORCE_PROG
185 //send the reboot to bootloader command:
186 static struct IOPacket dma_packet;
187 dma_packet.count_code = 0x40 + 0x01;
188 dma_packet.crc = 0;
193 struct IOPacket *pkt = &dma_packet;
194 uint8_t *p = (uint8_t *)pkt;
195 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[0]);
196 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[1]);
197 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[2]);
198 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[3]);
199 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[4]);
200 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, p[5]);
201
202 sys_time_usleep(5000); // this seems to be close to the minimum delay necessary to process this packet at the IO side
203 //the pixhawk IO chip should respond with:
204 // 0x00 ( PKT_CODE_SUCCESS )
205 // 0xe5
206 // 0x32
207 // 0x0a
208 //After that, the IO chips reboots into bootloader mode, in which it will stay for a short period
209 //The baudrate in bootloader mode ic changed to 115200 (normal operating baud is 1500000, at least for original pixhawk fmu firmware)
210
211 //state machine
212 state = 0;
214
215 unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
216 switch (state) {
217 case (0) :
218 if (b == PKT_CODE_SUCCESS) { state++; } else { state = 0; }
219 break;
220 case (1) :
221 if (b == 0xe5) { state++; } else { state = 0; }
222 break;
223 case (2) :
224 if (b == 0x32) { state++; } else { state = 0; }
225 break;
226 case (3) :
227 if (b == 0x0a) { state++; } else { state = 0; }
228 break;
229 default :
230 break;
231 }
232 }
233#else
234 state = 4;
235#endif
236 if (state == 4) {
238 /* look for the bootloader for 150 ms */
239 int ret = 0;
240 for (int i = 0; i < 15 && !ret ; i++) {
241 sys_time_usleep(10000);
242
243 //send a get_sync command in order to keep the io in bootloader mode
244 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, PROTO_GET_SYNC);
245 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, PROTO_EOC);
246
247 //get_sync should be replied with, so check if that happens and
248 //all other bytes are discarded, hopefully those were not important
249 //(they may be caused by sending multiple syncs)
250 while (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
251 unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
252
253 if (b == PROTO_INSYNC) {
254 sys_time_usleep(10000);
255 if(PX4IO_PORT->char_available(PX4IO_PORT->periph)){
256 b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
257 if (b == PROTO_OK)
258 {
259 setToBootloaderMode = true;
260 ret = 1;
261 break;
262 }
263 }
264 }
265 }
266 }
268 //if successfully entered bootloader mode, clear any remaining bytes (which may have a function, but I did not check)
269 while (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {PX4IO_PORT->get_byte(PX4IO_PORT->periph);}
270 // FBW OK OK hollay hollay :)
271 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'F');
272 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'B');
273 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'W');
274 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'O');
275 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'K');
276 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'O');
277 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'K'); // use 7 chars as answer
278 } else {
279 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'E'); //TODO: find out what the PX4 protocol for error feedback is...
280 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
281 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
282 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'O');
283 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
284 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, ':');
285 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, '2'); // use 7 chars as answer
286 }
287 } else {
288 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'E'); //TODO: find out what the PX4 protocol for error feedback is...
289 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
290 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
291 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'O');
292 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, 'R');
293 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, ':');
294 FLASH_PORT->put_byte(FLASH_PORT->periph, 0, '1'); // use 7 chars as answer
295 }
296#endif
297 }
298 } else if (FLASH_PORT->char_available(FLASH_PORT->periph)) {
299#ifdef INTER_MCU_AP
300 //already in bootloader mode, just directly relay data
301 while (FLASH_PORT->char_available(FLASH_PORT->periph)) {
302 unsigned char b = FLASH_PORT->get_byte(FLASH_PORT->periph);
303 PX4IO_PORT->put_byte(PX4IO_PORT->periph, 0, b);
304 }
305#endif
306 }
307}
308
void sys_time_usleep(uint32_t us)
sys_time_usleep(uint32_t us)
#define B230400
Definition uart_arch.h:49
#define B115200
Definition uart_arch.h:48
void mcu_reboot(enum reboot_state_t reboot_state)
Reboot the MCU.
Definition mcu_arch.c:206
@ MCU_REBOOT_BOOTLOADER
Go to bootloader.
Definition mcu.h:46
struct State state
Definition state.c:36
static float p[2][2]
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
void intermcu_set_enabled(bool value)
enable/disable intermcu link
Inter-MCU on the AP side.
arch independent LED (Light Emitting Diodes) API
void uart_periph_set_baudrate(struct uart_periph *periph, uint32_t baud)
Definition uart_arch.c:280
uint16_t foo
Definition main_demo5.c:58
Arch independent mcu ( Micro Controller Unit ) utilities.
static int char_available(struct linkdev *d)
PX4IO interface protocol.
#define PKT_CODE_SUCCESS
Definition protocol.h:234
#define PX4IO_REBOOT_BL_MAGIC
Definition protocol.h:182
#define PX4IO_P_SETUP_REBOOT_BL
Definition protocol.h:181
#define PX4IO_PAGE_SETUP
Definition protocol.h:151
uint8_t count_code
Definition protocol.h:220
static uint8_t crc_packet(struct IOPacket *pkt)
Definition protocol.h:282
#define PROTO_GET_SYNC
NOP for re-establishing sync.
Definition px4_flash.c:68
void px4flash_event(void)
Definition px4_flash.c:88
bool px4ioRebootTimeout
Definition px4_flash.c:77
#define PROTO_OK
INSYNC/OK - 'ok' response.
Definition px4_flash.c:64
void px4flash_init(void)
Definition px4_flash.c:79
#define PROTO_EOC
end of command
Definition px4_flash.c:62
bool setToBootloaderMode
Definition px4_flash.c:76
#define PROTO_INSYNC
'in sync' byte sent before status
Definition px4_flash.c:61
#define FLASH_PORT
Definition px4_flash.c:51
#define TRUE
Definition std.h:4
#define FALSE
Definition std.h:5
tid_t sys_time_register_timer(float duration, sys_time_cb cb)
Register a new system timer.
Definition sys_time.c:43
void sys_time_cancel_timer(tid_t id)
Cancel a system timer by id.
Definition sys_time.c:76
Architecture independent timing functions.
static bool sys_time_check_and_ack_timer(tid_t id)
Check if timer has elapsed.
Definition sys_time.h:123
int8_t tid_t
sys_time timer id type
Definition sys_time.h:60
struct target_t target
Definition target_pos.c:65
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
arch independent USB API
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
float b
Definition wedgebug.c:202