From 0d2d63980dc88618f95546bc4c2e690700cd158a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Nov 2014 10:38:15 +1100 Subject: [PATCH] Plane: limit RC config to 8 channels this is a limitation of current px4io.c --- ArduPlane/px4_mixer.pde | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/ArduPlane/px4_mixer.pde b/ArduPlane/px4_mixer.pde index da8893095f..026a87adc6 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 = 8}; + struct pwm_output_values pwm_values = {.values = {0}, .channel_count = PWM_OUTPUT_MAX_CHANNELS}; int px4io_fd = open("/dev/px4io", 0); if (px4io_fd == -1) { @@ -223,8 +223,10 @@ static bool setup_failsafe_mixing(void) goto failed; } - // setup RC config for each channel based on user specified mix/max/trim - for (uint8_t i=0; i