AP_Vehicle: increase rate at which we can log ESC telem

Some ESCs can give us >10Hz logging; we already check the data has
changed before logging, so let's log at the higher rate if we can.
This commit is contained in:
Peter Barker 2022-05-06 10:15:39 +10:00 committed by Peter Barker
parent 5087eabbca
commit d23ddc4116

View File

@ -290,7 +290,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_VideoTX, &vehicle.vtx, update, 2, 100, 220),
SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20, 225),
#if HAL_WITH_ESC_TELEM
SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 10, 50, 230),
SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 100, 50, 230),
#endif
#if HAL_GENERATOR_ENABLED
SCHED_TASK_CLASS(AP_Generator, &vehicle.generator, update, 10, 50, 235),