mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
SITL: params always use set method
This commit is contained in:
parent
8618b085be
commit
79b44b2517
@ -387,10 +387,10 @@ public:
|
|||||||
return (AP_HAL::Util::safety_state)_safety_switch_state.get();
|
return (AP_HAL::Util::safety_state)_safety_switch_state.get();
|
||||||
}
|
}
|
||||||
void force_safety_off() {
|
void force_safety_off() {
|
||||||
_safety_switch_state = (uint8_t)AP_HAL::Util::SAFETY_ARMED;
|
_safety_switch_state.set((uint8_t)AP_HAL::Util::SAFETY_ARMED);
|
||||||
}
|
}
|
||||||
bool force_safety_on() {
|
bool force_safety_on() {
|
||||||
_safety_switch_state = (uint8_t)AP_HAL::Util::SAFETY_DISARMED;
|
_safety_switch_state.set((uint8_t)AP_HAL::Util::SAFETY_DISARMED);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user