Copter: remove comments that number scheduler table

This commit is contained in:
Jonathan Challinger 2015-06-08 15:41:04 -07:00 committed by Randy Mackay
parent 5e40ad5c38
commit 5b14ce7694

View File

@ -94,46 +94,46 @@
*/ */
const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = { const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = {
{ SCHED_TASK(rc_loop), 4, 130 }, // 0 { SCHED_TASK(rc_loop), 4, 130 },
{ SCHED_TASK(throttle_loop), 8, 75 }, // 1 { SCHED_TASK(throttle_loop), 8, 75 },
{ SCHED_TASK(update_GPS), 8, 200 }, // 2 { SCHED_TASK(update_GPS), 8, 200 },
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
{ SCHED_TASK(update_optical_flow), 2, 160 }, // 3 { SCHED_TASK(update_optical_flow), 2, 160 },
#endif #endif
{ SCHED_TASK(update_batt_compass), 40, 120 }, // 4 { SCHED_TASK(update_batt_compass), 40, 120 },
{ SCHED_TASK(read_aux_switches), 40, 50 }, // 5 { SCHED_TASK(read_aux_switches), 40, 50 },
{ SCHED_TASK(arm_motors_check), 40, 50 }, // 6 { SCHED_TASK(arm_motors_check), 40, 50 },
{ SCHED_TASK(auto_trim), 40, 75 }, // 7 { SCHED_TASK(auto_trim), 40, 75 },
{ SCHED_TASK(update_altitude), 40, 140 }, // 8 { SCHED_TASK(update_altitude), 40, 140 },
{ SCHED_TASK(run_nav_updates), 8, 100 }, // 9 { SCHED_TASK(run_nav_updates), 8, 100 },
{ SCHED_TASK(update_thr_average), 4, 90 }, // 10 { SCHED_TASK(update_thr_average), 4, 90 },
{ SCHED_TASK(three_hz_loop), 133, 75 }, // 11 { SCHED_TASK(three_hz_loop), 133, 75 },
{ SCHED_TASK(compass_accumulate), 8, 100 }, // 12 { SCHED_TASK(compass_accumulate), 8, 100 },
{ SCHED_TASK(barometer_accumulate), 8, 90 }, // 13 { SCHED_TASK(barometer_accumulate), 8, 90 },
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
{ SCHED_TASK(check_dynamic_flight), 8, 75 }, { SCHED_TASK(check_dynamic_flight), 8, 75 },
#endif #endif
{ SCHED_TASK(update_notify), 8, 90 }, // 14 { SCHED_TASK(update_notify), 8, 90 },
{ SCHED_TASK(one_hz_loop), 400, 100 }, // 15 { SCHED_TASK(one_hz_loop), 400, 100 },
{ SCHED_TASK(ekf_check), 40, 75 }, // 16 { SCHED_TASK(ekf_check), 40, 75 },
{ SCHED_TASK(crash_check), 40, 75 }, // 17 { SCHED_TASK(crash_check), 40, 75 },
{ SCHED_TASK(landinggear_update), 40, 75 }, // 18 { SCHED_TASK(landinggear_update), 40, 75 },
{ SCHED_TASK(lost_vehicle_check), 40, 50 }, // 19 { SCHED_TASK(lost_vehicle_check), 40, 50 },
{ SCHED_TASK(gcs_check_input), 1, 180 }, // 20 { SCHED_TASK(gcs_check_input), 1, 180 },
{ SCHED_TASK(gcs_send_heartbeat), 400, 110 }, // 21 { SCHED_TASK(gcs_send_heartbeat), 400, 110 },
{ SCHED_TASK(gcs_send_deferred), 8, 550 }, // 22 { SCHED_TASK(gcs_send_deferred), 8, 550 },
{ SCHED_TASK(gcs_data_stream_send), 8, 550 }, // 23 { SCHED_TASK(gcs_data_stream_send), 8, 550 },
{ SCHED_TASK(update_mount), 8, 75 }, // 24 { SCHED_TASK(update_mount), 8, 75 },
{ SCHED_TASK(ten_hz_logging_loop), 40, 350 }, // 25 { SCHED_TASK(ten_hz_logging_loop), 40, 350 },
{ SCHED_TASK(fifty_hz_logging_loop), 8, 110 }, // 26 { SCHED_TASK(fifty_hz_logging_loop), 8, 110 },
{ SCHED_TASK(full_rate_logging_loop),1, 100 }, // 27 { SCHED_TASK(full_rate_logging_loop),1, 100 },
{ SCHED_TASK(perf_update), 4000, 75 }, // 28 { SCHED_TASK(perf_update), 4000, 75 },
{ SCHED_TASK(read_receiver_rssi), 40, 75 }, // 29 { SCHED_TASK(read_receiver_rssi), 40, 75 },
#if FRSKY_TELEM_ENABLED == ENABLED #if FRSKY_TELEM_ENABLED == ENABLED
{ SCHED_TASK(frsky_telemetry_send), 80, 75 }, // 30 { SCHED_TASK(frsky_telemetry_send), 80, 75 },
#endif #endif
#if EPM_ENABLED == ENABLED #if EPM_ENABLED == ENABLED
{ SCHED_TASK(epm_update), 40, 75 }, // 31 { SCHED_TASK(epm_update), 40, 75 },
#endif #endif
#ifdef USERHOOK_FASTLOOP #ifdef USERHOOK_FASTLOOP
{ SCHED_TASK(userhook_FastLoop), 4, 75 }, { SCHED_TASK(userhook_FastLoop), 4, 75 },