From c16e3a035f447ea12717505055478b2c5690edf2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 20 Jan 2014 19:40:11 +1100 Subject: [PATCH] Plane: fixed disarmed throttle in HIL --- ArduPlane/Attitude.pde | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index a99a24f60e..f5e5caedc4 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -855,16 +855,6 @@ static void set_servos(void) channel_rudder->radio_out = channel_rudder->radio_in; } -#if HIL_MODE != HIL_MODE_DISABLED - // get the servos to the GCS immediately for HIL - if (comm_get_txspace(MAVLINK_COMM_0) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN) { - send_radio_out(MAVLINK_COMM_0); - } - if (!g.hil_servos) { - return; - } -#endif - if (g.vtail_output != MIXING_DISABLED) { channel_output_mixer(g.vtail_output, channel_pitch->radio_out, channel_rudder->radio_out); } else if (g.elevon_output != MIXING_DISABLED) { @@ -889,6 +879,16 @@ static void set_servos(void) } } +#if HIL_MODE != HIL_MODE_DISABLED + // get the servos to the GCS immediately for HIL + if (comm_get_txspace(MAVLINK_COMM_0) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN) { + send_servo_out(MAVLINK_COMM_0); + } + if (!g.hil_servos) { + return; + } +#endif + // send values to the PWM timers for output // ---------------------------------------- channel_roll->output();