AP_Vehicle: generalise ESC telemetry to allow harmonic notch handling with other ESCs

log ESC telemetry data in frontend
This commit is contained in:
Andy Piper 2021-02-23 22:06:37 +00:00 committed by Andrew Tridgell
parent f513b1d1c2
commit 5d154b138a
2 changed files with 6 additions and 0 deletions

View File

@ -175,6 +175,7 @@ void AP_Vehicle::setup()
#if GENERATOR_ENABLED
generator.init();
#endif
}
void AP_Vehicle::loop()
@ -221,6 +222,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
SCHED_TASK(update_dynamic_notch, 200, 200),
SCHED_TASK_CLASS(AP_VideoTX, &vehicle.vtx, update, 2, 100),
SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20),
#if HAL_WITH_ESC_TELEM
SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 10, 50),
#endif
#if GENERATOR_ENABLED
SCHED_TASK_CLASS(AP_Generator, &vehicle.generator, update, 10, 50),
#endif

View File

@ -307,7 +307,9 @@ protected:
AP_VisualOdom visual_odom;
#endif
#if HAL_WITH_ESC_TELEM
AP_ESC_Telem esc_telem;
#endif
#if HAL_MSP_ENABLED
AP_MSP msp;