CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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