diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index fe9a3e00bb..30f25b4439 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -777,7 +777,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { perf_update, 4000, 20 }, { read_receiver_rssi, 40, 5 }, #if FRSKY_TELEM_ENABLED == ENABLED - { telemetry_send, 80, 10 }, + { frsky_telemetry_send, 80, 10 }, #endif #if EPM_ENABLED == ENABLED { epm_update, 40, 10 }, @@ -849,7 +849,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { perf_update, 1000, 200 }, { read_receiver_rssi, 10, 50 }, #if FRSKY_TELEM_ENABLED == ENABLED - { telemetry_send, 20, 100 }, + { frsky_telemetry_send, 20, 100 }, #endif #if EPM_ENABLED == ENABLED { epm_update, 10, 20 }, diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index cf70bc985b..51c3b326dd 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -411,10 +411,9 @@ static void check_usb_mux(void) #endif } -/* - send FrSky telemetry. Should be called at 5Hz by scheduler - */ -static void telemetry_send(void) +// frsky_telemetry_send - sends telemetry data using frsky telemetry +// should be called at 5Hz by scheduler +static void frsky_telemetry_send(void) { #if FRSKY_TELEM_ENABLED == ENABLED frsky_telemetry.send_frames((uint8_t)control_mode);