AP_HAL_ChibiOS: remove safe PWM

This commit is contained in:
Iampete1 2021-08-29 13:15:52 +01:00 committed by Andrew Tridgell
parent ed80d91d55
commit 53ee7d861d
2 changed files with 3 additions and 28 deletions

View File

@ -508,7 +508,7 @@ void RCOutput::write(uint8_t chan, uint16_t period_us)
if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) { if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) {
// implement safety pwm value // implement safety pwm value
period_us = safe_pwm[chan]; period_us = 0;
} }
chan -= chan_offset; chan -= chan_offset;
@ -555,7 +555,7 @@ void RCOutput::push_local(void)
if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) { if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
// safety is on, overwride pwm // safety is on, overwride pwm
period_us = safe_pwm[chan+chan_offset]; period_us = 0;
} }
if (group.current_mode == MODE_PWM_BRUSHED) { if (group.current_mode == MODE_PWM_BRUSHED) {
@ -1372,7 +1372,7 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us)
if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) { if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
// safety is on, overwride pwm // safety is on, overwride pwm
pwm = safe_pwm[chan+chan_offset]; pwm = 0;
} }
const uint16_t chan_mask = (1U<<chan); const uint16_t chan_mask = (1U<<chan);
@ -1956,24 +1956,6 @@ void RCOutput::force_safety_off(void)
#endif #endif
} }
/*
set PWM to send to a set of channels when the safety switch is
in the safe state
*/
void RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
{
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
iomcu.set_safety_pwm(chmask, period_us);
}
#endif
for (uint8_t i=0; i<16; i++) {
if (chmask & (1U<<i)) {
safe_pwm[i] = period_us;
}
}
}
/* /*
update safety state update safety state
*/ */

View File

@ -87,12 +87,6 @@ public:
*/ */
void force_safety_off(void) override; void force_safety_off(void) override;
/*
set PWM to send to a set of channels when the safety switch is
in the safe state
*/
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
bool enable_px4io_sbus_out(uint16_t rate_hz) override; bool enable_px4io_sbus_out(uint16_t rate_hz) override;
/* /*
@ -514,7 +508,6 @@ private:
&& _dshot_current_command.cycle > 0; && _dshot_current_command.cycle > 0;
} }
#endif #endif
uint16_t safe_pwm[max_channels]; // pwm to use when safety is on
bool corked; bool corked;
// mask of channels that are running in high speed // mask of channels that are running in high speed
uint16_t fast_channel_mask; uint16_t fast_channel_mask;