mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOMCU: fixed a safety reset case for IOMCU reset
if IOMCU resets in flight when user had disabled the safety switch using the button then the IOCMU force safety code was not called
This commit is contained in:
parent
235c8a2d0c
commit
45d82887b3
@ -1038,6 +1038,7 @@ void AP_IOMCU::check_iomcu_reset(void)
|
|||||||
|
|
||||||
if (dt_ms < max_delay) {
|
if (dt_ms < max_delay) {
|
||||||
// all OK
|
// all OK
|
||||||
|
last_safety_off = reg_status.flag_safety_off;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
detected_io_reset = true;
|
detected_io_reset = true;
|
||||||
@ -1045,11 +1046,16 @@ void AP_IOMCU::check_iomcu_reset(void)
|
|||||||
hal.console->printf("IOMCU reset t=%u %u %u dt=%u\n",
|
hal.console->printf("IOMCU reset t=%u %u %u dt=%u\n",
|
||||||
unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms));
|
unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms));
|
||||||
|
|
||||||
if (safety_forced_off && !reg_status.flag_safety_off && hal.util->get_soft_armed()) {
|
if (last_safety_off && !reg_status.flag_safety_off && hal.util->get_soft_armed()) {
|
||||||
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
|
||||||
|
uint16_t options = boardconfig?boardconfig->get_safety_button_options():0;
|
||||||
|
if (safety_forced_off || (options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) == 0) {
|
||||||
// IOMCU has reset while armed with safety off - force it off
|
// IOMCU has reset while armed with safety off - force it off
|
||||||
// again so we can keep flying
|
// again so we can keep flying
|
||||||
force_safety_off();
|
force_safety_off();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
last_safety_off = reg_status.flag_safety_off;
|
||||||
|
|
||||||
// we need to ensure the mixer data and the rates are sent over to
|
// we need to ensure the mixer data and the rates are sent over to
|
||||||
// the IOMCU
|
// the IOMCU
|
||||||
|
@ -154,6 +154,9 @@ private:
|
|||||||
// have we forced the safety off?
|
// have we forced the safety off?
|
||||||
bool safety_forced_off;
|
bool safety_forced_off;
|
||||||
|
|
||||||
|
// was safety off on last status?
|
||||||
|
bool last_safety_off;
|
||||||
|
|
||||||
void send_servo_out(void);
|
void send_servo_out(void);
|
||||||
void read_rc_input(void);
|
void read_rc_input(void);
|
||||||
void read_servo(void);
|
void read_servo(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user