mirror of https://github.com/ArduPilot/ardupilot
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.
This commit is contained in:
parent
1195c4750e
commit
2cb93f5a16
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue