mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Added comments explaining when should the function be used
This commit is contained in:
parent
7e0bff9cbe
commit
d3280bdd16
@ -248,6 +248,8 @@ static void trim_radio()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// update the g_rc_function array from pointers to rc_x channels
|
// update the g_rc_function array from pointers to rc_x channels
|
||||||
|
// This should be done periodically because the user might change the configuration and
|
||||||
|
// expects the changes to take effect instantly
|
||||||
static void update_aux_servo_function()
|
static void update_aux_servo_function()
|
||||||
{
|
{
|
||||||
RC_Channel_aux::Aux_servo_function_t aux_servo_function[NUM_CHANNELS]; // the function of the aux. servos
|
RC_Channel_aux::Aux_servo_function_t aux_servo_function[NUM_CHANNELS]; // the function of the aux. servos
|
||||||
|
Loading…
Reference in New Issue
Block a user