mirror of https://github.com/ArduPilot/ardupilot
SITL: act on safety switch being enabled in SITL by zeroing outputs
This commit is contained in:
parent
2c9551a25a
commit
6b87318062
|
@ -240,7 +240,7 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
|
||||||
|
|
||||||
AP_GROUPINFO("EFI_TYPE", 58, SIM, efi_type, SIM::EFI_TYPE_NONE),
|
AP_GROUPINFO("EFI_TYPE", 58, SIM, efi_type, SIM::EFI_TYPE_NONE),
|
||||||
|
|
||||||
AP_GROUPINFO("SAFETY_STATE", 59, SIM, _safety_switch_state, 0),
|
// 59 was SAFETY_STATE
|
||||||
|
|
||||||
// motor harmonics
|
// motor harmonics
|
||||||
AP_GROUPINFO("VIB_MOT_HMNC", 60, SIM, vibe_motor_harmonics, 1),
|
AP_GROUPINFO("VIB_MOT_HMNC", 60, SIM, vibe_motor_harmonics, 1),
|
||||||
|
|
|
@ -392,19 +392,6 @@ public:
|
||||||
AP_Float hdg; // 0 to 360
|
AP_Float hdg; // 0 to 360
|
||||||
} opos;
|
} opos;
|
||||||
|
|
||||||
AP_Int8 _safety_switch_state;
|
|
||||||
|
|
||||||
AP_HAL::Util::safety_state safety_switch_state() const {
|
|
||||||
return (AP_HAL::Util::safety_state)_safety_switch_state.get();
|
|
||||||
}
|
|
||||||
void force_safety_off() {
|
|
||||||
_safety_switch_state.set((uint8_t)AP_HAL::Util::SAFETY_ARMED);
|
|
||||||
}
|
|
||||||
bool force_safety_on() {
|
|
||||||
_safety_switch_state.set((uint8_t)AP_HAL::Util::SAFETY_DISARMED);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t irlock_port;
|
uint16_t irlock_port;
|
||||||
|
|
||||||
time_t start_time_UTC;
|
time_t start_time_UTC;
|
||||||
|
|
Loading…
Reference in New Issue