AP_Vechicle: add AP_Servo_Telem and call at 50Hz

This commit is contained in:
Iampete1 2024-11-16 11:14:34 +00:00 committed by Andrew Tridgell
parent e003cc511d
commit 38c3257151
2 changed files with 8 additions and 0 deletions

View File

@ -634,6 +634,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#if HAL_WITH_ESC_TELEM
SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 100, 50, 230),
#endif
#if AP_SERVO_TELEM_ENABLED
SCHED_TASK_CLASS(AP_Servo_Telem, &vehicle.servo_telem, update, 50, 50, 231),
#endif
#if HAL_GENERATOR_ENABLED
SCHED_TASK_CLASS(AP_Generator, &vehicle.generator, update, 10, 50, 235),
#endif

View File

@ -51,6 +51,7 @@
#include <AP_OpenDroneID/AP_OpenDroneID.h>
#include <AP_Hott_Telem/AP_Hott_Telem.h>
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include <AP_Servo_Telem/AP_Servo_Telem.h>
#include <AP_GyroFFT/AP_GyroFFT.h>
#include <AP_Networking/AP_Networking.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
@ -415,6 +416,10 @@ protected:
AP_ESC_Telem esc_telem;
#endif
#if AP_SERVO_TELEM_ENABLED
AP_Servo_Telem servo_telem;
#endif
#if AP_OPENDRONEID_ENABLED
AP_OpenDroneID opendroneid;
#endif