mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
Use the shorter macro call instead
This commit is contained in:
parent
5d0d1b6a6d
commit
e232a0936f
@ -377,9 +377,7 @@ static void set_servos(void)
|
|||||||
} else {
|
} else {
|
||||||
G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent;
|
G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent;
|
||||||
}
|
}
|
||||||
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) {
|
G_RC_AUX(k_flap_auto)->calc_pwm();
|
||||||
g_rc_function[RC_Channel_aux::k_flap_auto]->calc_pwm();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
||||||
|
Loading…
Reference in New Issue
Block a user