Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix iofirmware pwm structure sizes to support SBUS_OUT #26825

Merged
merged 2 commits into from
Apr 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified Tools/IO_Firmware/iofirmware_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_lowpolh.bin
Binary file not shown.
4 changes: 2 additions & 2 deletions libraries/AP_IOMCU/AP_IOMCU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ void AP_IOMCU::thread_main(void)
// update failsafe pwm
if (pwm_out.failsafe_pwm_set != pwm_out.failsafe_pwm_sent) {
uint8_t set = pwm_out.failsafe_pwm_set;
if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.failsafe_pwm)) {
if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_RC_CHANNELS, pwm_out.failsafe_pwm)) {
pwm_out.failsafe_pwm_sent = set;
}
}
Expand All @@ -372,7 +372,7 @@ void AP_IOMCU::send_servo_out()
if (rate.sbus_rate_hz == 0) {
n = MIN(n, 8);
} else {
n = MIN(n, IOMCU_MAX_CHANNELS);
n = MIN(n, IOMCU_MAX_RC_CHANNELS);
}
uint32_t now = AP_HAL::micros();
if (now - last_servo_out_us >= 2000 || AP_BoardConfig::io_dshot()) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_IOMCU/iofirmware/iofirmware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -966,7 +966,7 @@ bool AP_IOMCU_FW::handle_code_write()
}
/* copy channel data */
uint16_t i = 0, num_values = rx_io_packet.count;
while ((i < IOMCU_MAX_CHANNELS) && (num_values > 0)) {
while ((i < IOMCU_MAX_RC_CHANNELS) && (num_values > 0)) {
/* XXX range-check value? */
if (rx_io_packet.regs[i] != PWM_IGNORE_THIS_CHANNEL) {
reg_direct_pwm.pwm[i] = rx_io_packet.regs[i];
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_IOMCU/iofirmware/iofirmware.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,17 +93,17 @@ class AP_IOMCU_FW {

// PAGE_SERVO values
struct {
uint16_t pwm[IOMCU_MAX_CHANNELS];
uint16_t pwm[IOMCU_MAX_RC_CHANNELS]; // size has to account for virtual channels via SBUS_OUT
} reg_servo;

// PAGE_DIRECT_PWM values
struct {
uint16_t pwm[IOMCU_MAX_CHANNELS];
uint16_t pwm[IOMCU_MAX_RC_CHANNELS];
} reg_direct_pwm;

// PAGE_FAILSAFE_PWM
struct {
uint16_t pwm[IOMCU_MAX_CHANNELS];
uint16_t pwm[IOMCU_MAX_RC_CHANNELS];
} reg_failsafe_pwm;

// output rates
Expand Down
Loading