mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: support for virtual hardware safety switch
This commit is contained in:
parent
907977b2f2
commit
326ba5b974
@ -200,6 +200,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
|||||||
|
|
||||||
AP_GROUPINFO("EFI_TYPE", 58, SITL, efi_type, SITL::EFI_TYPE_NONE),
|
AP_GROUPINFO("EFI_TYPE", 58, SITL, efi_type, SITL::EFI_TYPE_NONE),
|
||||||
|
|
||||||
|
AP_GROUPINFO("SAFETY_STATE", 59, SITL, _safety_switch_state, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -292,6 +292,19 @@ 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 = (uint8_t)AP_HAL::Util::SAFETY_ARMED;
|
||||||
|
}
|
||||||
|
bool force_safety_on() {
|
||||||
|
_safety_switch_state = (uint8_t)AP_HAL::Util::SAFETY_DISARMED;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
uint16_t irlock_port;
|
uint16_t irlock_port;
|
||||||
|
|
||||||
void simstate_send(mavlink_channel_t chan);
|
void simstate_send(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user