Browse Source

HAL_ChibiOS: allow set of safety mask from IOMCU

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
81fe8b7138
  1. 7
      libraries/AP_HAL_ChibiOS/RCOutput.h

7
libraries/AP_HAL_ChibiOS/RCOutput.h

@ -140,7 +140,12 @@ public: @@ -140,7 +140,12 @@ public:
set PWM to send to a set of channels if the FMU firmware dies
*/
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override;
/*
set safety mask for IOMCU
*/
void set_safety_mask(uint16_t mask) { safety_mask = mask; }
private:
struct pwm_group {
// only advanced timers can do high clocks needed for more than 400Hz

Loading…
Cancel
Save