mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_IOMCU: iofirmware: remove saftey PWM
This commit is contained in:
parent
c1a2379504
commit
cc03b2975c
@ -607,15 +607,6 @@ bool AP_IOMCU_FW::handle_code_write()
|
|||||||
break;
|
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((®_safety_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case PAGE_FAILSAFE_PWM: {
|
case PAGE_FAILSAFE_PWM: {
|
||||||
uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
|
uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
|
||||||
if (offset + num_values > sizeof(reg_failsafe_pwm.pwm)/2) {
|
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) {
|
if (reg_status.flag_safety_off) {
|
||||||
reg_direct_pwm.pwm[i] = reg_failsafe_pwm.pwm[i];
|
reg_direct_pwm.pwm[i] = reg_failsafe_pwm.pwm[i];
|
||||||
} else {
|
} else {
|
||||||
reg_direct_pwm.pwm[i] = reg_safety_pwm.pwm[i];
|
reg_direct_pwm.pwm[i] = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (mixing.enabled) {
|
if (mixing.enabled) {
|
||||||
|
@ -94,11 +94,6 @@ public:
|
|||||||
uint16_t pwm[IOMCU_MAX_CHANNELS];
|
uint16_t pwm[IOMCU_MAX_CHANNELS];
|
||||||
} reg_failsafe_pwm;
|
} reg_failsafe_pwm;
|
||||||
|
|
||||||
// PAGE_SAFETY_PWM
|
|
||||||
struct {
|
|
||||||
uint16_t pwm[IOMCU_MAX_CHANNELS];
|
|
||||||
} reg_safety_pwm;
|
|
||||||
|
|
||||||
// output rates
|
// output rates
|
||||||
struct {
|
struct {
|
||||||
uint16_t freq;
|
uint16_t freq;
|
||||||
|
@ -54,7 +54,6 @@ enum iopage {
|
|||||||
PAGE_SETUP = 50,
|
PAGE_SETUP = 50,
|
||||||
PAGE_DIRECT_PWM = 54,
|
PAGE_DIRECT_PWM = 54,
|
||||||
PAGE_FAILSAFE_PWM = 55,
|
PAGE_FAILSAFE_PWM = 55,
|
||||||
PAGE_SAFETY_PWM = 108,
|
|
||||||
PAGE_MIXING = 200,
|
PAGE_MIXING = 200,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user