Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Bootloader/AP_Bootloader.cpp
9361 views
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
ArduPilot bootloader. This implements the same protocol originally
17
developed for PX4, but builds on top of the ChibiOS HAL
18
19
It does not use the full AP_HAL API in order to keep the firmware
20
size below the maximum of 16kByte required for F4 based
21
boards. Instead it uses the ChibiOS APIs directly
22
*/
23
24
#include <AP_HAL/AP_HAL.h>
25
#include "ch.h"
26
#include "hal.h"
27
#include "hwdef.h"
28
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
29
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
30
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
31
#include "support.h"
32
#include "bl_protocol.h"
33
#include "flash_from_sd.h"
34
#include "can.h"
35
#include <stdio.h>
36
#if EXT_FLASH_SIZE_MB
37
#include <AP_FlashIface/AP_FlashIface_JEDEC.h>
38
#endif
39
#include <AP_CheckFirmware/AP_CheckFirmware.h>
40
#include "network.h"
41
42
extern "C" {
43
int main(void);
44
}
45
46
struct boardinfo board_info = {
47
.board_type = APJ_BOARD_ID,
48
.board_rev = 0,
49
.fw_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + FLASH_RESERVE_END_KB + APP_START_OFFSET_KB))*1024,
50
.extf_size = (EXT_FLASH_SIZE_MB * 1024 * 1024) - (EXT_FLASH_RESERVE_START_KB + EXT_FLASH_RESERVE_END_KB) * 1024
51
};
52
53
#ifndef HAL_BOOTLOADER_TIMEOUT
54
#define HAL_BOOTLOADER_TIMEOUT 5000
55
#endif
56
57
#ifndef HAL_STAY_IN_BOOTLOADER_VALUE
58
#define HAL_STAY_IN_BOOTLOADER_VALUE 0
59
#endif
60
61
#if EXT_FLASH_SIZE_MB
62
AP_FlashIface_JEDEC ext_flash;
63
#endif
64
65
#if AP_BOOTLOADER_NETWORK_ENABLED
66
static BL_Network network;
67
#endif
68
69
int main(void)
70
{
71
#ifdef AP_BOOTLOADER_CUSTOM_HERE4
72
custom_startup();
73
#endif
74
75
flash_init();
76
77
#if AP_FLASH_ECC_CHECK_ENABLED
78
check_ecc_errors();
79
#endif
80
81
#ifdef STM32F427xx
82
if (BOARD_FLASH_SIZE > 1024 && check_limit_flash_1M()) {
83
board_info.fw_size = (1024 - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024;
84
}
85
#endif
86
87
bool try_boot = false;
88
uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;
89
90
#ifdef HAL_BOARD_AP_PERIPH_ZUBAXGNSS
91
// setup remapping register for ZubaxGNSS
92
uint32_t mapr = AFIO->MAPR;
93
mapr &= ~AFIO_MAPR_SWJ_CFG;
94
mapr |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;
95
AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP;
96
#endif
97
98
#if HAL_FLASH_PROTECTION
99
stm32_flash_unprotect_flash();
100
#endif
101
102
#if AP_BOOTLOADER_NETWORK_ENABLED
103
network.save_comms_ip();
104
#endif
105
106
#if AP_FASTBOOT_ENABLED
107
enum rtc_boot_magic m = check_fast_reboot();
108
bool was_watchdog = stm32_was_watchdog_reset();
109
if (was_watchdog) {
110
try_boot = true;
111
timeout = 0;
112
} else if (m == RTC_BOOT_HOLD) {
113
timeout = 0;
114
} else if (m == RTC_BOOT_FAST) {
115
try_boot = true;
116
timeout = 0;
117
}
118
#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES
119
else if ((m & 0xFFFFFF00) == RTC_BOOT_CANBL) {
120
try_boot = false;
121
timeout = 10000;
122
can_set_node_id(m & 0xFF);
123
}
124
if (can_check_update()) {
125
// trying to update firmware, stay in bootloader
126
try_boot = false;
127
timeout = 0;
128
}
129
#if AP_CHECK_FIRMWARE_ENABLED
130
const auto ok = check_good_firmware();
131
if (ok != check_fw_result_t::CHECK_FW_OK) {
132
// bad firmware CRC, don't try and boot
133
timeout = 0;
134
try_boot = false;
135
led_set(LED_BAD_FW);
136
}
137
#ifndef BOOTLOADER_DEV_LIST
138
else if (timeout == HAL_BOOTLOADER_TIMEOUT) {
139
// fast boot for good firmware if we haven't been told to stay
140
// in bootloader
141
try_boot = true;
142
timeout = 1000;
143
}
144
#endif // ifndef(BOOTLOADER_DEV_LIST)
145
#if AP_BOOTLOADER_NETWORK_ENABLED
146
if (ok == check_fw_result_t::CHECK_FW_OK) {
147
const auto *app_descriptor = get_app_descriptor();
148
if (app_descriptor != nullptr) {
149
network.status_printf("Firmware OK: %ld.%ld.%lx\n", app_descriptor->version_major,
150
app_descriptor->version_minor,
151
app_descriptor->git_hash);
152
}
153
} else {
154
network.status_printf("Firmware Error: %d\n", (int)ok);
155
}
156
#endif
157
#endif // AP_CHECK_FIRMWARE_ENABLED
158
159
if (was_watchdog && m != RTC_BOOT_FWOK) {
160
// we've had a watchdog within 30s of booting main CAN
161
// firmware. We will stay in bootloader to allow the user to
162
// load a fixed firmware
163
stm32_watchdog_clear_reason();
164
try_boot = false;
165
timeout = 0;
166
}
167
#elif AP_CHECK_FIRMWARE_ENABLED
168
const auto ok = check_good_firmware();
169
if (ok != check_fw_result_t::CHECK_FW_OK) {
170
// bad firmware, don't try and boot
171
timeout = 0;
172
try_boot = false;
173
led_set(LED_BAD_FW);
174
}
175
#endif
176
177
#if defined(HAL_GPIO_PIN_VBUS) && defined(HAL_ENABLE_VBUS_CHECK)
178
#if HAL_USE_SERIAL_USB == TRUE
179
else if (palReadLine(HAL_GPIO_PIN_VBUS) == 0) {
180
try_boot = true;
181
timeout = 0;
182
}
183
#endif
184
#endif
185
186
// if we fail to boot properly we want to pause in bootloader to give
187
// a chance to load new app code
188
set_fast_reboot(RTC_BOOT_OFF);
189
#endif // AP_FASTBOOT_ENABLED
190
191
#ifdef HAL_GPIO_PIN_STAY_IN_BOOTLOADER
192
// optional "stay in bootloader" pin
193
if (palReadLine(HAL_GPIO_PIN_STAY_IN_BOOTLOADER) == HAL_STAY_IN_BOOTLOADER_VALUE) {
194
try_boot = false;
195
timeout = 0;
196
}
197
#endif
198
199
#if EXT_FLASH_SIZE_MB
200
while (!ext_flash.init()) {
201
// keep trying until we get it working
202
// there's no future without it
203
chThdSleep(chTimeMS2I(20));
204
}
205
#endif
206
207
if (try_boot) {
208
jump_to_app();
209
}
210
211
#if defined(BOOTLOADER_DEV_LIST)
212
init_uarts();
213
#endif
214
#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES
215
can_start();
216
#endif
217
218
#if AP_BOOTLOADER_NETWORK_ENABLED
219
network.init();
220
#endif
221
222
#if AP_BOOTLOADER_FLASH_FROM_SD_ENABLED
223
if (flash_from_sd()) {
224
jump_to_app();
225
}
226
#endif
227
228
#if defined(BOOTLOADER_DEV_LIST)
229
while (true) {
230
bootloader(timeout);
231
jump_to_app();
232
}
233
#else
234
// CAN and network only
235
while (true) {
236
uint32_t t0 = AP_HAL::millis();
237
while (timeout == 0 || AP_HAL::millis() - t0 <= timeout) {
238
can_update();
239
chThdSleep(chTimeMS2I(1));
240
}
241
jump_to_app();
242
}
243
#endif
244
}
245
246
247
248