From 1e6511b0100e3a8027857e5d4d3807849ada5261 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Nov 2014 15:37:00 +1100 Subject: [PATCH] Plane: fixed number of channels we pass to PWM limits --- ArduPlane/px4_mixer.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/px4_mixer.pde b/ArduPlane/px4_mixer.pde index 6e8142a1cc..2c035eac20 100644 --- a/ArduPlane/px4_mixer.pde +++ b/ArduPlane/px4_mixer.pde @@ -193,7 +193,7 @@ static bool setup_failsafe_mixing(void) } enum AP_HAL::Util::safety_state old_state = hal.util->safety_switch_state(); - struct pwm_output_values pwm_values = {.values = {0}, .channel_count = PWM_OUTPUT_MAX_CHANNELS}; + struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 8}; int px4io_fd = open("/dev/px4io", 0); if (px4io_fd == -1) {