From 2cb93f5a167912ba720b0b9fe8ef4468ad627757 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:00:26 +1100 Subject: [PATCH] fixed a crash in HIL The g_rc_function[RC_Channel_aux::k_flap_auto] ptr came out as NULL during one HIL run on a desktop CPU, which led to ArduPlane crashing. I am not yet sure if this can happen in real flight, but I think the NULL check is worthwhile to be sure. --- ArduPlane/Attitude.pde | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 13af736483..a951873a4c 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -377,8 +377,9 @@ static void set_servos(void) } else { G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent; } - g_rc_function[RC_Channel_aux::k_flap_auto]->calc_pwm(); - + if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) { + g_rc_function[RC_Channel_aux::k_flap_auto]->calc_pwm(); + } } #if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS