mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_ChibiOS: implement set_failsafe_pwm()
This commit is contained in:
parent
4314d0ea12
commit
8c33b4b97d
@ -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
|
||||
|
@ -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 {
|
||||
|
Loading…
Reference in New Issue
Block a user