HAL_ChibiOS: implement set_failsafe_pwm()

This commit is contained in:
Andrew Tridgell 2018-09-13 06:23:01 +10:00
parent 4314d0ea12
commit 8c33b4b97d
2 changed files with 17 additions and 0 deletions

View File

@ -1443,4 +1443,16 @@ void RCOutput::safety_update(void)
#endif
}
/*
set PWM to send to a set of channels if the FMU firmware dies
*/
void RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
{
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
iomcu.set_failsafe_pwm(chmask, period_us);
}
#endif
}
#endif // HAL_USE_PWM

View File

@ -131,6 +131,11 @@ public:
get safety switch state, used by Util.cpp
*/
AP_HAL::Util::safety_state _safety_switch_state(void);
/*
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;
private:
struct pwm_group {