Browse Source

Copter: rename frsky_telemetry_send function

mission-4.1.18
Randy Mackay 10 years ago committed by Andrew Tridgell
parent
commit
f91fb9a4e8
  1. 4
      ArduCopter/ArduCopter.pde
  2. 7
      ArduCopter/system.pde

4
ArduCopter/ArduCopter.pde

@ -777,7 +777,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { @@ -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 = { @@ -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 },

7
ArduCopter/system.pde

@ -411,10 +411,9 @@ static void check_usb_mux(void) @@ -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);

Loading…
Cancel
Save