AP_IOMCU: iofirmware: remove saftey PWM

This commit is contained in:
Iampete1 2021-08-29 13:17:40 +01:00 committed by Andrew Tridgell
parent c1a2379504
commit cc03b2975c
3 changed files with 1 additions and 16 deletions

View File

@ -607,15 +607,6 @@ bool AP_IOMCU_FW::handle_code_write()
break;
}
case PAGE_SAFETY_PWM: {
uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
if (offset + num_values > sizeof(reg_safety_pwm.pwm)/2) {
return false;
}
memcpy((&reg_safety_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2);
break;
}
case PAGE_FAILSAFE_PWM: {
uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
if (offset + num_values > sizeof(reg_failsafe_pwm.pwm)/2) {
@ -750,7 +741,7 @@ void AP_IOMCU_FW::fill_failsafe_pwm(void)
if (reg_status.flag_safety_off) {
reg_direct_pwm.pwm[i] = reg_failsafe_pwm.pwm[i];
} else {
reg_direct_pwm.pwm[i] = reg_safety_pwm.pwm[i];
reg_direct_pwm.pwm[i] = 0;
}
}
if (mixing.enabled) {

View File

@ -94,11 +94,6 @@ public:
uint16_t pwm[IOMCU_MAX_CHANNELS];
} reg_failsafe_pwm;
// PAGE_SAFETY_PWM
struct {
uint16_t pwm[IOMCU_MAX_CHANNELS];
} reg_safety_pwm;
// output rates
struct {
uint16_t freq;

View File

@ -54,7 +54,6 @@ enum iopage {
PAGE_SETUP = 50,
PAGE_DIRECT_PWM = 54,
PAGE_FAILSAFE_PWM = 55,
PAGE_SAFETY_PWM = 108,
PAGE_MIXING = 200,
};