Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/AP_Periph.cpp
9410 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
AP_Periph main firmware
17
18
To flash this firmware on Linux use:
19
20
st-flash write build/f103-periph/bin/AP_Periph.bin 0x8006000
21
22
*/
23
#include <AP_HAL/AP_HAL.h>
24
#include <AP_HAL/AP_HAL_Boards.h>
25
#include "AP_Periph.h"
26
#include <stdio.h>
27
28
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
29
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
30
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
31
#include <AP_HAL_ChibiOS/I2CDevice.h>
32
#endif
33
34
#ifndef HAL_PERIPH_HWESC_SERIAL_PORT
35
#define HAL_PERIPH_HWESC_SERIAL_PORT 3
36
#endif
37
38
// not only will the code not compile without features this enables,
39
// but it forms part of a series of measures to give a robust recovery
40
// mechanism on AP_Periph if a bad flash occurs.
41
#ifndef AP_CHECK_FIRMWARE_ENABLED
42
#error AP_CHECK_FIRMWARE_ENABLED must be enabled
43
#endif
44
45
extern const AP_HAL::HAL &hal;
46
47
AP_Periph_FW periph;
48
49
void setup();
50
void loop();
51
52
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
53
54
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
55
void stm32_watchdog_init() {}
56
void stm32_watchdog_pat() {}
57
#endif
58
59
void setup(void)
60
{
61
periph.init();
62
}
63
64
void loop(void)
65
{
66
periph.update();
67
}
68
69
static uint32_t start_ms;
70
71
AP_Periph_FW::AP_Periph_FW()
72
{
73
if (_singleton != nullptr) {
74
AP_HAL::panic("AP_Periph_FW must be singleton");
75
}
76
_singleton = this;
77
}
78
79
#if HAL_LOGGING_ENABLED
80
const struct LogStructure AP_Periph_FW::log_structure[] = {
81
LOG_COMMON_STRUCTURES,
82
};
83
#endif
84
85
void AP_Periph_FW::init()
86
{
87
#if AP_SIM_ENABLED
88
sitl.init();
89
#endif
90
91
// always run with watchdog enabled. This should have already been
92
// setup by the bootloader, but if not then enable now
93
#ifndef DISABLE_WATCHDOG
94
stm32_watchdog_init();
95
#endif
96
97
stm32_watchdog_pat();
98
99
#if !HAL_GCS_ENABLED
100
hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32);
101
#endif
102
hal.serial(3)->begin(115200, 128, 256);
103
104
load_parameters();
105
106
stm32_watchdog_pat();
107
108
can_start();
109
110
#if HAL_GCS_ENABLED
111
stm32_watchdog_pat();
112
gcs().init();
113
#endif
114
serial_manager.init();
115
116
#if AP_PERIPH_NETWORKING_ENABLED
117
networking_periph.init();
118
#endif
119
120
#if HAL_GCS_ENABLED
121
gcs().setup_console();
122
gcs().setup_uarts();
123
gcs().send_text(MAV_SEVERITY_INFO, "AP_Periph GCS Initialised!");
124
#endif
125
126
stm32_watchdog_pat();
127
128
#ifdef HAL_BOARD_AP_PERIPH_ZUBAXGNSS
129
// setup remapping register for ZubaxGNSS
130
uint32_t mapr = AFIO->MAPR;
131
mapr &= ~AFIO_MAPR_SWJ_CFG;
132
mapr |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;
133
AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP;
134
#endif
135
136
#if HAL_LOGGING_ENABLED
137
logger.init(g.log_bitmask, log_structure, ARRAY_SIZE(log_structure));
138
#endif
139
140
check_firmware_print();
141
142
if (hal.util->was_watchdog_reset()) {
143
printf("Reboot after watchdog reset\n");
144
}
145
146
#if AP_STATS_ENABLED
147
node_stats.init();
148
#endif
149
150
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
151
serial_options.init();
152
#endif
153
154
#if AP_PERIPH_GPS_ENABLED
155
gps.set_default_type_for_gps1(HAL_GPS1_TYPE_DEFAULT);
156
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
157
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
158
#if HAL_LOGGING_ENABLED
159
#define MASK_LOG_GPS (1<<2)
160
gps.set_log_gps_bit(MASK_LOG_GPS);
161
#endif
162
gps.init();
163
}
164
#endif // AP_PERIPH_GPS_ENABLED
165
166
#if AP_DAC_ENABLED
167
dac.init();
168
#endif
169
170
#if AP_PERIPH_MAG_ENABLED
171
compass.init();
172
#endif
173
174
#if AP_PERIPH_BARO_ENABLED
175
baro.init();
176
#endif
177
178
#if AP_PERIPH_IMU_ENABLED
179
if (g.imu_sample_rate) {
180
imu.init(g.imu_sample_rate);
181
if (imu.get_accel_count() > 0 || imu.get_gyro_count() > 0) {
182
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Periph_FW::can_imu_update, void), "IMU_UPDATE", 16384, AP_HAL::Scheduler::PRIORITY_CAN, 0);
183
}
184
}
185
#endif
186
187
#if AP_PERIPH_BATTERY_ENABLED
188
battery_lib.init();
189
#endif
190
191
#if AP_PERIPH_RCIN_ENABLED
192
rcin_init();
193
#endif
194
195
#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || AP_PERIPH_RC_OUT_ENABLED
196
hal.rcout->init();
197
#endif
198
199
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
200
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
201
#endif
202
203
#if AP_PERIPH_RC_OUT_ENABLED
204
rcout_init();
205
#endif
206
207
#if AP_PERIPH_ADSB_ENABLED
208
adsb_init();
209
#endif
210
211
#if AP_PERIPH_EFI_ENABLED
212
if (efi.enabled() && g.efi_port >= 0) {
213
auto *uart = hal.serial(g.efi_port);
214
if (uart != nullptr) {
215
uart->begin(g.efi_baudrate);
216
serial_manager.set_protocol_and_baud(g.efi_port, AP_SerialManager::SerialProtocol_EFI, g.efi_baudrate);
217
efi.init();
218
}
219
}
220
#endif
221
222
#if AP_KDECAN_ENABLED
223
kdecan.init();
224
#endif
225
226
#if AP_PERIPH_AIRSPEED_ENABLED
227
#if (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && (HAL_USE_I2C == TRUE)
228
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
229
if (pins_enabled) {
230
ChibiOS::I2CBus::set_bus_to_floating(0);
231
#ifdef HAL_GPIO_PIN_LED_CAN_I2C
232
palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1);
233
#endif
234
} else {
235
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
236
airspeed.init();
237
}
238
#else
239
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
240
airspeed.init();
241
#endif
242
243
#endif
244
245
#if AP_PERIPH_RANGEFINDER_ENABLED
246
bool have_rangefinder = false;
247
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
248
if ((rangefinder.get_type(i) != RangeFinder::Type::NONE) && (g.rangefinder_port[i] >= 0)) {
249
// init uart for serial rangefinders
250
auto *uart = hal.serial(g.rangefinder_port[i]);
251
if (uart != nullptr) {
252
uart->begin(g.rangefinder_baud[i]);
253
serial_manager.set_protocol_and_baud(g.rangefinder_port[i], AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud[i]);
254
have_rangefinder = true;
255
}
256
}
257
}
258
if (have_rangefinder) {
259
// Can only call rangefinder init once, subsequent inits are blocked
260
rangefinder.init(ROTATION_NONE);
261
}
262
#endif
263
264
#if AP_PERIPH_PROXIMITY_ENABLED
265
if (proximity.get_type(0) != AP_Proximity::Type::None && g.proximity_port >= 0) {
266
auto *uart = hal.serial(g.proximity_port);
267
if (uart != nullptr) {
268
uart->begin(g.proximity_baud);
269
serial_manager.set_protocol_and_baud(g.proximity_port, AP_SerialManager::SerialProtocol_Lidar360, g.proximity_baud);
270
proximity.init();
271
}
272
}
273
#endif
274
275
#if AP_PERIPH_PWM_HARDPOINT_ENABLED
276
pwm_hardpoint_init();
277
#endif
278
279
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
280
hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));
281
#endif
282
283
#if AP_PERIPH_ESC_APD_ENABLED
284
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
285
const uint8_t port = g.esc_serial_port[i];
286
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports
287
apd_esc_telem[i] = NEW_NOTHROW ESC_APD_Telem (hal.serial(port), g.pole_count[i]);
288
}
289
}
290
#endif
291
292
#if AP_PERIPH_MSP_ENABLED
293
if (g.msp_port >= 0) {
294
msp_init(hal.serial(g.msp_port));
295
}
296
#endif
297
298
#if AP_TEMPERATURE_SENSOR_ENABLED
299
temperature_sensor.init();
300
#endif
301
302
#if HAL_NMEA_OUTPUT_ENABLED
303
nmea.init();
304
#endif
305
306
#if AP_PERIPH_RPM_ENABLED
307
rpm_sensor.init();
308
#endif
309
310
#if AP_PERIPH_NOTIFY_ENABLED
311
notify.init();
312
#endif
313
314
#if AP_PERIPH_RELAY_ENABLED
315
relay.init();
316
#endif
317
318
#if AP_SCRIPTING_ENABLED
319
scripting.init();
320
#endif
321
322
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
323
actuator_telem.init();
324
#endif
325
326
start_ms = AP_HAL::millis();
327
}
328
329
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || AP_PERIPH_NOTIFY_ENABLED
330
/*
331
rotating rainbow pattern on startup
332
*/
333
void AP_Periph_FW::update_rainbow()
334
{
335
#if AP_PERIPH_NOTIFY_ENABLED
336
if (notify.get_led_len() != 8) {
337
return;
338
}
339
#endif
340
static bool rainbow_done;
341
if (rainbow_done) {
342
return;
343
}
344
uint32_t now = AP_HAL::millis();
345
if (now - start_ms > 1500) {
346
rainbow_done = true;
347
#if AP_PERIPH_NOTIFY_ENABLED
348
periph.notify.handle_rgb(0, 0, 0);
349
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
350
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);
351
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
352
#endif
353
return;
354
}
355
static uint32_t last_update_ms;
356
const uint8_t step_ms = 30;
357
if (now - last_update_ms < step_ms) {
358
return;
359
}
360
const struct {
361
uint8_t red;
362
uint8_t green;
363
uint8_t blue;
364
} rgb_rainbow[] = {
365
{ 255, 0, 0 },
366
{ 255, 127, 0 },
367
{ 255, 255, 0 },
368
{ 0, 255, 0 },
369
{ 0, 0, 255 },
370
{ 75, 0, 130 },
371
{ 143, 0, 255 },
372
{ 0, 0, 0 },
373
};
374
last_update_ms = now;
375
static uint8_t step;
376
const uint8_t nsteps = ARRAY_SIZE(rgb_rainbow);
377
float brightness = 0.3;
378
for (uint8_t n=0; n<8; n++) {
379
uint8_t i = (step + n) % nsteps;
380
#if AP_PERIPH_NOTIFY_ENABLED
381
periph.notify.handle_rgb(
382
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
383
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,
384
#endif
385
rgb_rainbow[i].red*brightness,
386
rgb_rainbow[i].green*brightness,
387
rgb_rainbow[i].blue*brightness);
388
}
389
step++;
390
391
#if defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
392
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
393
#endif
394
}
395
#endif // AP_PERIPH_NOTIFY_ENABLED
396
397
398
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
399
void AP_Periph_FW::show_stack_free()
400
{
401
const uint32_t isr_stack_size = uint32_t((const uint8_t *)&__main_stack_end__ - (const uint8_t *)&__main_stack_base__);
402
can_printf("ISR %u/%u", unsigned(stack_free(&__main_stack_base__)), unsigned(isr_stack_size));
403
404
for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) {
405
uint32_t total_stack;
406
if (tp->wabase == (void*)&__main_thread_stack_base__) {
407
// main thread has its stack separated from the thread context
408
total_stack = uint32_t((const uint8_t *)&__main_thread_stack_end__ - (const uint8_t *)&__main_thread_stack_base__);
409
} else {
410
// all other threads have their thread context pointer
411
// above the stack top
412
total_stack = uint32_t(tp) - uint32_t(tp->wabase);
413
}
414
can_printf("%s STACK=%u/%u\n", tp->name, unsigned(stack_free(tp->wabase)), unsigned(total_stack));
415
}
416
}
417
#endif
418
419
420
421
void AP_Periph_FW::update()
422
{
423
#if AP_STATS_ENABLED
424
node_stats.update();
425
#endif
426
427
static uint32_t last_led_ms;
428
uint32_t now = AP_HAL::millis();
429
if (now - last_led_ms > 1000) {
430
last_led_ms = now;
431
#ifdef HAL_GPIO_PIN_LED
432
if (!no_iface_finished_dna) {
433
palToggleLine(HAL_GPIO_PIN_LED);
434
}
435
#endif
436
#if 0
437
#if AP_PERIPH_GPS_ENABLED
438
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
439
#endif
440
#if AP_PERIPH_MAG_ENABLED
441
const Vector3f &field = compass.get_field();
442
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
443
#endif
444
#if AP_PERIPH_BARO_ENABLED
445
hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
446
#endif
447
#if AP_PERIPH_RANGEFINDER_ENABLED
448
hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors());
449
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
450
AP_RangeFinder_Backend *backend = rangefinder.get_backend(i);
451
if (backend == nullptr) {
452
continue;
453
}
454
hal.serial(0)->printf("RNG %u %ucm\n", i, uint16_t(backend->distance()*100));
455
}
456
#endif
457
hal.scheduler->delay(1);
458
#endif
459
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
460
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
461
#endif
462
463
#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
464
check_for_serial_reboot_cmd(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT);
465
#endif
466
467
#if AP_PERIPH_RC_OUT_ENABLED
468
rcout_init_1Hz();
469
#endif
470
471
#if AP_DAC_ENABLED
472
dac.update();
473
#endif
474
475
GCS_SEND_MESSAGE(MSG_HEARTBEAT);
476
GCS_SEND_MESSAGE(MSG_SYS_STATUS);
477
}
478
479
static uint32_t last_error_ms;
480
const auto &ierr = AP::internalerror();
481
if (now - last_error_ms > 5000 && ierr.errors()) {
482
// display internal errors as DEBUG every 5s
483
last_error_ms = now;
484
can_printf("IERR 0x%x %u", unsigned(ierr.errors()), unsigned(ierr.last_error_line()));
485
}
486
487
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
488
static uint32_t last_debug_ms;
489
if (debug_option_is_set(DebugOptions::SHOW_STACK) && now - last_debug_ms > 5000) {
490
last_debug_ms = now;
491
show_stack_free();
492
}
493
#endif
494
495
if (debug_option_is_set(DebugOptions::AUTOREBOOT) && AP_HAL::millis() > 15000) {
496
// attempt reboot with HOLD after 15s
497
periph.prepare_reboot();
498
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
499
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_HOLD));
500
NVIC_SystemReset();
501
#endif
502
}
503
504
#if AP_PERIPH_BATTERY_ENABLED
505
if (now - battery.last_read_ms >= 100) {
506
// update battery at 10Hz
507
battery.last_read_ms = now;
508
battery_lib.read();
509
}
510
#endif
511
512
#if AP_PERIPH_RCIN_ENABLED
513
rcin_update();
514
#endif
515
516
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
517
actuator_telem.update();
518
#endif
519
520
#if AP_PERIPH_BATTERY_BALANCE_ENABLED
521
batt_balance_update();
522
#endif
523
524
static uint32_t fiftyhz_last_update_ms;
525
if (now - fiftyhz_last_update_ms >= 20) {
526
// update at 50Hz
527
fiftyhz_last_update_ms = now;
528
#if AP_PERIPH_NOTIFY_ENABLED
529
notify.update();
530
#endif
531
#if HAL_GCS_ENABLED
532
gcs().update_receive();
533
gcs().update_send();
534
#endif
535
}
536
537
#if HAL_NMEA_OUTPUT_ENABLED
538
nmea.update();
539
#endif
540
541
#if AP_TEMPERATURE_SENSOR_ENABLED
542
temperature_sensor.update();
543
#endif
544
545
#if AP_PERIPH_RPM_ENABLED
546
if (now - rpm_last_update_ms >= 100) {
547
rpm_last_update_ms = now;
548
rpm_sensor.update();
549
}
550
#endif
551
552
#if HAL_LOGGING_ENABLED
553
logger.periodic_tasks();
554
#endif
555
556
can_update();
557
558
#if AP_PERIPH_NETWORKING_ENABLED
559
networking_periph.update();
560
#endif
561
562
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || AP_PERIPH_NOTIFY_ENABLED
563
update_rainbow();
564
#endif
565
#if AP_PERIPH_ADSB_ENABLED
566
adsb_update();
567
#endif
568
#if AP_PERIPH_BATTERY_TAG_ENABLED
569
battery_tag.update();
570
#endif
571
#if AP_PERIPH_BATTERY_BMS_ENABLED
572
battery_bms.update();
573
#endif
574
}
575
576
#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
577
// check for uploader.py reboot command
578
void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index)
579
{
580
// These are the string definitions in uploader.py
581
// NSH_INIT = bytearray(b'\x0d\x0d\x0d')
582
// NSH_REBOOT_BL = b"reboot -b\n"
583
// NSH_REBOOT = b"reboot\n"
584
585
// This is the command sequence that is sent from uploader.py
586
// self.__send(uploader.NSH_INIT)
587
// self.__send(uploader.NSH_REBOOT_BL)
588
// self.__send(uploader.NSH_INIT)
589
// self.__send(uploader.NSH_REBOOT)
590
591
for (uint8_t i=0; i<hal.num_serial; i++) {
592
if (serial_index >= 0 && serial_index != i) {
593
// a specific serial port was selected but this is not it
594
continue;
595
}
596
597
auto *uart = hal.serial(i);
598
if (uart == nullptr || !uart->is_initialized()) {
599
continue;
600
}
601
602
uint32_t available = MIN(uart->available(), 1000U);
603
while (available-- > 0) {
604
const char reboot_string[] = "\r\r\rreboot -b\n\r\r\rreboot\n";
605
const char reboot_string_len = sizeof(reboot_string)-1; // -1 is to remove the null termination
606
static uint16_t index[hal.num_serial];
607
608
uint8_t data;
609
if (!uart->read(data)) {
610
// read error
611
continue;
612
}
613
if (index[i] >= reboot_string_len || (uint8_t)data != reboot_string[index[i]]) {
614
// don't have a perfect match, start over
615
index[i] = 0;
616
continue;
617
}
618
index[i]++;
619
if (index[i] == reboot_string_len) {
620
// received reboot msg. Trigger a reboot and stay in the bootloader
621
prepare_reboot();
622
hal.scheduler->reboot(true);
623
}
624
}
625
}
626
}
627
#endif // HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
628
629
// prepare for a safe reboot where PWMs and params are gracefully disabled
630
// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) minus the actual reboot
631
void AP_Periph_FW::prepare_reboot()
632
{
633
#if AP_PERIPH_RC_OUT_ENABLED
634
// force safety on
635
hal.rcout->force_safety_on();
636
#endif
637
638
// flush pending parameter writes
639
AP_Param::flush();
640
641
// do not process incoming mavlink messages while we delay:
642
hal.scheduler->register_delay_callback(nullptr, 5);
643
644
// delay to give the ACK a chance to get out, the LEDs to flash,
645
// the IO board safety to be forced on, the parameters to flush,
646
hal.scheduler->expect_delay_ms(100);
647
hal.scheduler->delay(40);
648
hal.scheduler->expect_delay_ms(0);
649
}
650
651
/*
652
reboot, optionally holding in bootloader. For scripting
653
*/
654
void AP_Periph_FW::reboot(bool hold_in_bootloader)
655
{
656
prepare_reboot();
657
hal.scheduler->reboot(hold_in_bootloader);
658
}
659
660
AP_Periph_FW *AP_Periph_FW::_singleton;
661
662
AP_Periph_FW& AP::periph()
663
{
664
return *AP_Periph_FW::get_singleton();
665
}
666
667
AP_HAL_MAIN();
668
669