From d0da7411b2ef1fd0aa63a47d1adf5f8dd82dfd8d Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sun, 4 Sep 2016 18:38:42 -0700 Subject: [PATCH] Plane: Fetch mixer status for assessing mixer success --- ArduPlane/px4_mixer.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index 333bb60f63..10377d5e64 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -239,6 +239,7 @@ bool Plane::setup_failsafe_mixing(void) int px4io_fd = -1; enum AP_HAL::Util::safety_state old_state = hal.util->safety_switch_state(); struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 8}; + unsigned mixer_status = 0; buf = (char *)malloc(buf_size); if (buf == NULL) { @@ -390,6 +391,12 @@ bool Plane::setup_failsafe_mixing(void) goto failed; } + if (ioctl(px4io_fd, PWM_IO_GET_STATUS, (unsigned long)&mixer_status) != 0 || + (mixer_status & PX4IO_P_STATUS_FLAGS_MIXER_OK) != 0) { + hal.console->printf("Mixer failed: 0x%04x\n", mixer_status); + goto failed; + } + ret = true; failed: