mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
AP_HAL: add force_safety_on method
This commit is contained in:
parent
2efeb768e0
commit
033b14db16
@ -60,6 +60,13 @@ public:
|
|||||||
*/
|
*/
|
||||||
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) {}
|
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) {}
|
||||||
|
|
||||||
|
/*
|
||||||
|
force the safety switch on, disabling PWM output from the IO board
|
||||||
|
return false (indicating failure) by default so that boards with no safety switch
|
||||||
|
do not need to implement this method
|
||||||
|
*/
|
||||||
|
virtual bool force_safety_on(void) { return false; }
|
||||||
|
|
||||||
/*
|
/*
|
||||||
force the safety switch off, enabling PWM output from the IO board
|
force the safety switch off, enabling PWM output from the IO board
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user