diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index f2b505de25..812af67b55 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -281,7 +281,7 @@ void AP_Periph_FW::update() #endif #ifdef HAL_PERIPH_ENABLE_RC_OUT - SRV_Channels::enable_aux_servos(); + rcout_init_1Hz(); #endif } @@ -319,6 +319,7 @@ void AP_Periph_FW::update() #endif } +#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT // check for uploader.py reboot command void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index) { @@ -362,16 +363,18 @@ void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index) } index[i]++; if (index[i] == reboot_string_len) { - // received reboot msg - reboot(true); + // received reboot msg. Trigger a reboot and stay in the bootloader + prepare_reboot(); + hal.scheduler->reboot(true); } } } } +#endif // HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT -// trigger a safe reboot where PWMs and params are gracefully disabled -// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) -void AP_Periph_FW::reboot(bool hold_in_bootloader) +// prepare for a safe reboot where PWMs and params are gracefully disabled +// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) minus the actual reboot +void AP_Periph_FW::prepare_reboot() { #ifdef HAL_PERIPH_ENABLE_NOTIFY // Notify might want to blink some LEDs: @@ -379,8 +382,10 @@ void AP_Periph_FW::reboot(bool hold_in_bootloader) notify.update(); #endif +#ifdef HAL_PERIPH_ENABLE_RC_OUT // force safety on hal.rcout->force_safety_on(); +#endif // flush pending parameter writes AP_Param::flush(); @@ -389,9 +394,8 @@ void AP_Periph_FW::reboot(bool hold_in_bootloader) hal.scheduler->register_delay_callback(nullptr, 5); // delay to give the ACK a chance to get out, the LEDs to flash, - // the IO board safety to be forced on, the parameters to flush, ... - hal.scheduler->delay(200); - - hal.scheduler->reboot(hold_in_bootloader); + // the IO board safety to be forced on, the parameters to flush, + hal.scheduler->delay(40); } + AP_HAL_MAIN(); diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index fc8064e234..fd783e4bb4 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -46,9 +46,11 @@ public: void can_battery_update(); void load_parameters(); + void prepare_reboot(); +#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT void check_for_serial_reboot_cmd(const int8_t serial_index); - void reboot(bool hold_in_bootloader); +#endif AP_SerialManager serial_manager; @@ -133,6 +135,7 @@ public: SRV_Channels servo_channels; void rcout_init(); + void rcout_init_1Hz(); void rcout_esc(int16_t *rc, uint8_t num_channels); void rcout_srv(const uint8_t actuator_id, const float command_value); void rcout_update(); diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 57f97576a9..814427ef36 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -389,6 +389,7 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* // instant reboot, with backup register used to give bootloader // the node_id + periph.prepare_reboot(); #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(ins))); NVIC_SystemReset(); @@ -772,6 +773,7 @@ static void onTransferReceived(CanardInstance* ins, case UAVCAN_PROTOCOL_RESTARTNODE_ID: printf("RestartNode\n"); hal.scheduler->delay(10); + periph.prepare_reboot(); #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS NVIC_SystemReset(); #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index 3738b2f52c..17d2e22305 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -34,6 +34,9 @@ extern const AP_HAL::HAL &hal; void AP_Periph_FW::rcout_init() { + // start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system + hal.rcout->force_safety_on(); + for (uint8_t i=0; i