mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: periodically call stats update
This commit is contained in:
parent
be13de79a4
commit
1bb6350a67
@ -151,6 +151,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
|
||||
#endif
|
||||
SCHED_TASK(button_update, 5, 100),
|
||||
SCHED_TASK(stats_update, 1, 100),
|
||||
};
|
||||
|
||||
|
||||
@ -207,6 +208,14 @@ void Copter::perf_update(void)
|
||||
pmTest1 = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
update AP_Stats
|
||||
*/
|
||||
void Copter::stats_update(void)
|
||||
{
|
||||
g2.stats.update();
|
||||
}
|
||||
|
||||
void Copter::loop()
|
||||
{
|
||||
// wait for an INS sample
|
||||
|
@ -718,6 +718,7 @@ private:
|
||||
void button_update();
|
||||
void init_proximity();
|
||||
void update_proximity();
|
||||
void stats_update();
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void gcs_send_message(enum ap_message id);
|
||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||
|
Loading…
Reference in New Issue
Block a user