mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
AP_HAL: added set_safety_pwm() API
This commit is contained in:
parent
950bb09735
commit
5e39b6fb11
@ -45,6 +45,12 @@ public:
|
||||
* array of channels. */
|
||||
virtual uint16_t read(uint8_t ch) = 0;
|
||||
virtual void read(uint16_t* period_us, uint8_t len) = 0;
|
||||
|
||||
/*
|
||||
set PWM to send to a set of channels when the safety switch is
|
||||
in the safe state
|
||||
*/
|
||||
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_RC_OUTPUT_H__
|
||||
|
Loading…
Reference in New Issue
Block a user