|
|
|
@ -37,6 +37,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
@@ -37,6 +37,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
|
|
|
|
SCHED_TASK(update_tracking, 50, 1000), |
|
|
|
|
SCHED_TASK(update_GPS, 10, 4000), |
|
|
|
|
SCHED_TASK(update_compass, 10, 1500), |
|
|
|
|
SCHED_TASK(compass_save, 0.02, 200), |
|
|
|
|
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500), |
|
|
|
|
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500), |
|
|
|
|
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700), |
|
|
|
@ -95,13 +96,6 @@ void Tracker::one_second_loop()
@@ -95,13 +96,6 @@ void Tracker::one_second_loop()
|
|
|
|
|
// updated armed/disarmed status LEDs
|
|
|
|
|
update_armed_disarmed(); |
|
|
|
|
|
|
|
|
|
one_second_counter++; |
|
|
|
|
|
|
|
|
|
if (one_second_counter >= 60) { |
|
|
|
|
compass_save(); |
|
|
|
|
one_second_counter = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// init compass location for declination
|
|
|
|
|
init_compass_location(); |
|
|
|
|
|
|
|
|
|