Plane: fixed number of channels we pass to PWM limits

This commit is contained in:
Andrew Tridgell 2014-11-08 15:37:00 +11:00
parent 0a318d3a68
commit 1e6511b010
1 changed files with 1 additions and 1 deletions

View File

@ -193,7 +193,7 @@ static bool setup_failsafe_mixing(void)
} }
enum AP_HAL::Util::safety_state old_state = hal.util->safety_switch_state(); 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); int px4io_fd = open("/dev/px4io", 0);
if (px4io_fd == -1) { if (px4io_fd == -1) {