Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / fc / fc_tasks.c
blob6918b9a6dab5cd0553e701f05a7aa1d4969a371e
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdlib.h>
20 #include <stdint.h>
22 #include "platform.h"
24 #include "cms/cms.h"
26 #include "common/axis.h"
27 #include "common/color.h"
28 #include "common/utils.h"
29 #include "programming/programming_task.h"
31 #include "drivers/accgyro/accgyro.h"
32 #include "drivers/compass/compass.h"
33 #include "drivers/sensor.h"
34 #include "drivers/serial.h"
35 #include "drivers/stack_check.h"
36 #include "drivers/pwm_mapping.h"
37 #include "drivers/gimbal_common.h"
38 #include "drivers/headtracker_common.h"
40 #include "fc/cli.h"
41 #include "fc/config.h"
42 #include "fc/fc_core.h"
43 #include "fc/fc_msp.h"
44 #include "fc/fc_tasks.h"
45 #include "fc/rc_controls.h"
46 #include "fc/runtime_config.h"
48 #include "flight/dynamic_lpf.h"
49 #include "flight/imu.h"
50 #include "flight/mixer.h"
51 #include "flight/pid.h"
52 #include "flight/power_limits.h"
53 #include "flight/rpm_filter.h"
54 #include "flight/servos.h"
55 #include "flight/wind_estimator.h"
56 #include "flight/adaptive_filter.h"
58 #include "navigation/navigation.h"
60 #include "io/beeper.h"
61 #include "io/lights.h"
62 #include "io/dashboard.h"
63 #include "io/gps.h"
64 #include "io/ledstrip.h"
65 #include "io/osd.h"
66 #include "io/serial.h"
67 #include "io/rcdevice_cam.h"
68 #include "io/osd_joystick.h"
69 #include "io/smartport_master.h"
70 #include "io/vtx.h"
71 #include "io/vtx_msp.h"
72 #include "io/osd_dji_hd.h"
73 #include "io/displayport_msp_osd.h"
74 #include "io/servo_sbus.h"
75 #include "io/adsb.h"
77 #include "msp/msp_serial.h"
79 #include "rx/rx.h"
81 #include "scheduler/scheduler.h"
83 #include "sensors/sensors.h"
84 #include "sensors/acceleration.h"
85 #include "sensors/temperature.h"
86 #include "sensors/barometer.h"
87 #include "sensors/battery.h"
88 #include "sensors/compass.h"
89 #include "sensors/gyro.h"
90 #include "sensors/irlock.h"
91 #include "sensors/pitotmeter.h"
92 #include "sensors/rangefinder.h"
93 #include "sensors/opflow.h"
95 #include "telemetry/telemetry.h"
97 #include "config/feature.h"
99 #if defined(SITL_BUILD)
100 #include "target/SITL/serial_proxy.h"
101 #endif
103 void taskHandleSerial(timeUs_t currentTimeUs)
105 UNUSED(currentTimeUs);
106 // in cli mode, all serial stuff goes to here. enter cli mode by sending #
107 if (cliMode) {
108 cliProcess();
111 // Allow MSP processing even if in CLI mode
112 mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand);
114 #if defined(USE_DJI_HD_OSD)
115 // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task
116 djiOsdSerialProcess();
117 #endif
119 #ifdef USE_MSP_OSD
120 // Capture MSP Displayport messages to determine if VTX is connected
121 mspOsdSerialProcess(mspFcProcessCommand);
122 #ifdef USE_VTX_MSP
123 mspVtxSerialProcess(mspFcProcessCommand);
124 #endif
125 #endif
128 void taskUpdateBattery(timeUs_t currentTimeUs)
130 static timeUs_t batMonitoringLastServiced = 0;
131 timeDelta_t BatMonitoringTimeSinceLastServiced = cmpTimeUs(currentTimeUs, batMonitoringLastServiced);
133 if (isAmperageConfigured()) {
134 currentMeterUpdate(BatMonitoringTimeSinceLastServiced);
135 #ifdef USE_POWER_LIMITS
136 currentLimiterUpdate(BatMonitoringTimeSinceLastServiced);
137 #endif
140 #ifdef USE_ADC
141 if (feature(FEATURE_VBAT)) {
142 batteryUpdate(BatMonitoringTimeSinceLastServiced);
145 if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
146 powerMeterUpdate(BatMonitoringTimeSinceLastServiced);
147 sagCompensatedVBatUpdate(currentTimeUs, BatMonitoringTimeSinceLastServiced);
148 #if defined(USE_POWER_LIMITS) && defined(USE_ADC)
149 powerLimiterUpdate(BatMonitoringTimeSinceLastServiced);
150 #endif
152 #endif
154 batMonitoringLastServiced = currentTimeUs;
157 void taskUpdateTemperature(timeUs_t currentTimeUs)
159 UNUSED(currentTimeUs);
160 temperatureUpdate();
163 #ifdef USE_GPS
164 void taskProcessGPS(timeUs_t currentTimeUs)
166 // if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
167 // hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
168 // change this based on available hardware
169 if (feature(FEATURE_GPS)) {
170 if (gpsUpdate()) {
171 #ifdef USE_WIND_ESTIMATOR
172 updateWindEstimator(currentTimeUs);
173 #endif
177 if (sensors(SENSOR_GPS)) {
178 updateGpsIndicator(currentTimeUs);
181 #endif
183 #ifdef USE_MAG
184 void taskUpdateCompass(timeUs_t currentTimeUs)
186 if (sensors(SENSOR_MAG)) {
187 compassUpdate(currentTimeUs);
190 #endif
192 #ifdef USE_ADSB
193 void taskAdsb(timeUs_t currentTimeUs)
195 UNUSED(currentTimeUs);
196 adsbTtlClean(currentTimeUs);
198 #endif
200 #ifdef USE_BARO
201 void taskUpdateBaro(timeUs_t currentTimeUs)
203 if (!sensors(SENSOR_BARO)) {
204 return;
207 const uint32_t newDeadline = baroUpdate();
208 if (newDeadline != 0) {
209 rescheduleTask(TASK_SELF, newDeadline);
212 updatePositionEstimator_BaroTopic(currentTimeUs);
214 #endif
216 #ifdef USE_PITOT
217 void taskUpdatePitot(timeUs_t currentTimeUs)
219 if (!sensors(SENSOR_PITOT)) {
220 return;
223 pitotUpdate();
225 if ( pitotIsHealthy()) {
226 updatePositionEstimator_PitotTopic(currentTimeUs);
229 #endif
231 #ifdef USE_RANGEFINDER
232 void taskUpdateRangefinder(timeUs_t currentTimeUs)
234 UNUSED(currentTimeUs);
236 if (!sensors(SENSOR_RANGEFINDER))
237 return;
239 // Update and adjust task to update at required rate
240 const uint32_t newDeadline = rangefinderUpdate();
241 if (newDeadline != 0) {
242 rescheduleTask(TASK_SELF, newDeadline);
246 * Process raw rangefinder readout
248 if (rangefinderProcess(calculateCosTiltAngle())) {
249 updatePositionEstimator_SurfaceTopic(currentTimeUs, rangefinderGetLatestAltitude());
252 #endif
254 #if defined(USE_IRLOCK)
255 void taskUpdateIrlock(timeUs_t currentTimeUs)
257 UNUSED(currentTimeUs);
258 irlockUpdate();
260 #endif
262 #ifdef USE_OPFLOW
263 void taskUpdateOpticalFlow(timeUs_t currentTimeUs)
265 if (!sensors(SENSOR_OPFLOW))
266 return;
268 opflowUpdate(currentTimeUs);
269 updatePositionEstimator_OpticalFlowTopic(currentTimeUs);
271 #endif
273 #ifdef USE_DASHBOARD
274 void taskDashboardUpdate(timeUs_t currentTimeUs)
276 if (feature(FEATURE_DASHBOARD)) {
277 dashboardUpdate(currentTimeUs);
280 #endif
282 #ifdef USE_TELEMETRY
283 void taskTelemetry(timeUs_t currentTimeUs)
285 telemetryCheckState();
287 if (!cliMode && feature(FEATURE_TELEMETRY)) {
288 telemetryProcess(currentTimeUs);
291 #endif
293 #if defined(USE_SMARTPORT_MASTER)
294 void taskSmartportMaster(timeUs_t currentTimeUs)
296 smartportMasterHandle(currentTimeUs);
298 #endif
300 #ifdef USE_LED_STRIP
301 void taskLedStrip(timeUs_t currentTimeUs)
303 if (feature(FEATURE_LED_STRIP)) {
304 ledStripUpdate(currentTimeUs);
307 #endif
309 void taskSyncServoDriver(timeUs_t currentTimeUs)
311 UNUSED(currentTimeUs);
313 #if defined(USE_SERVO_SBUS)
314 sbusServoSendUpdate();
315 #endif
319 #ifdef USE_OSD
320 void taskUpdateOsd(timeUs_t currentTimeUs)
322 if (feature(FEATURE_OSD)) {
323 osdUpdate(currentTimeUs);
326 #endif
328 void taskUpdateAux(timeUs_t currentTimeUs)
330 updatePIDCoefficients();
331 dynamicLpfGyroTask();
332 #ifdef USE_SIMULATOR
333 if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) {
334 updateFixedWingLevelTrim(currentTimeUs);
336 #else
337 updateFixedWingLevelTrim(currentTimeUs);
338 #endif
341 void fcTasksInit(void)
343 schedulerInit();
345 rescheduleTask(TASK_PID, getLooptime());
346 setTaskEnabled(TASK_PID, true);
348 rescheduleTask(TASK_GYRO, getGyroLooptime());
349 setTaskEnabled(TASK_GYRO, true);
351 setTaskEnabled(TASK_AUX, true);
353 setTaskEnabled(TASK_SERIAL, true);
354 #if defined(BEEPER) || defined(USE_DSHOT)
355 setTaskEnabled(TASK_BEEPER, true);
356 #endif
357 #ifdef USE_LIGHTS
358 setTaskEnabled(TASK_LIGHTS, true);
359 #endif
360 setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || isAmperageConfigured());
361 setTaskEnabled(TASK_TEMPERATURE, true);
362 setTaskEnabled(TASK_RX, true);
363 #ifdef USE_GPS
364 setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
365 #endif
366 #ifdef USE_MAG
367 setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
368 #if defined(USE_MAG_MPU9250)
369 // fixme temporary solution for AK6983 via slave I2C on MPU9250
370 rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
371 #endif
372 #endif
373 #ifdef USE_BARO
374 setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
375 #endif
376 #ifdef USE_PITOT
377 setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT));
378 #endif
379 #ifdef USE_ADSB
380 setTaskEnabled(TASK_ADSB, true);
381 #endif
382 #ifdef USE_RANGEFINDER
383 setTaskEnabled(TASK_RANGEFINDER, sensors(SENSOR_RANGEFINDER));
384 #endif
385 #ifdef USE_DASHBOARD
386 setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD));
387 #endif
388 #ifdef USE_TELEMETRY
389 setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
390 #endif
391 #ifdef USE_LED_STRIP
392 setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
393 #endif
394 #ifdef STACK_CHECK
395 setTaskEnabled(TASK_STACK_CHECK, true);
396 #endif
397 #if defined(USE_SERVO_SBUS)
398 setTaskEnabled(TASK_PWMDRIVER, (servoConfig()->servo_protocol == SERVO_TYPE_SBUS) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM));
399 #endif
400 #ifdef USE_CMS
401 #ifdef USE_MSP_DISPLAYPORT
402 setTaskEnabled(TASK_CMS, true);
403 #else
404 setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DASHBOARD));
405 #endif
406 #endif
407 #ifdef USE_OPFLOW
408 setTaskEnabled(TASK_OPFLOW, sensors(SENSOR_OPFLOW));
409 #endif
410 #ifdef USE_VTX_CONTROL
411 #if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
412 setTaskEnabled(TASK_VTXCTRL, true);
413 #endif
414 #endif
415 #ifdef USE_RCDEVICE
416 #ifdef USE_LED_STRIP
417 setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled() || osdJoystickEnabled());
418 #else
419 setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
420 #endif
421 #endif
422 #ifdef USE_PROGRAMMING_FRAMEWORK
423 setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true);
424 #endif
425 #ifdef USE_IRLOCK
426 setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected());
427 #endif
428 #if defined(USE_SMARTPORT_MASTER)
429 setTaskEnabled(TASK_SMARTPORT_MASTER, true);
430 #endif
432 #ifdef USE_SERIAL_GIMBAL
433 setTaskEnabled(TASK_GIMBAL, true);
434 #endif
436 #ifdef USE_HEADTRACKER
437 setTaskEnabled(TASK_HEADTRACKER, true);
438 #endif
440 #ifdef USE_ADAPTIVE_FILTER
441 setTaskEnabled(TASK_ADAPTIVE_FILTER, (
442 gyroConfig()->gyroFilterMode == GYRO_FILTER_MODE_ADAPTIVE &&
443 gyroConfig()->adaptiveFilterMinHz > 0 &&
444 gyroConfig()->adaptiveFilterMaxHz > 0
446 #endif
448 #if defined(SITL_BUILD)
449 serialProxyStart();
450 #endif
453 cfTask_t cfTasks[TASK_COUNT] = {
454 [TASK_SYSTEM] = {
455 .taskName = "SYSTEM",
456 .taskFunc = taskSystem,
457 .desiredPeriod = TASK_PERIOD_HZ(10), // run every 100 ms, 10Hz
458 .staticPriority = TASK_PRIORITY_HIGH,
460 [TASK_PID] = {
461 .taskName = "PID",
462 .taskFunc = taskMainPidLoop,
463 .desiredPeriod = TASK_PERIOD_US(1000),
464 .staticPriority = TASK_PRIORITY_REALTIME,
466 [TASK_GYRO] = {
467 .taskName = "GYRO",
468 .taskFunc = taskGyro,
469 .desiredPeriod = TASK_PERIOD_US(TASK_GYRO_LOOPTIME),
470 .staticPriority = TASK_PRIORITY_REALTIME,
472 [TASK_SERIAL] = {
473 .taskName = "SERIAL",
474 .taskFunc = taskHandleSerial,
475 .desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
476 .staticPriority = TASK_PRIORITY_LOW,
479 #if defined(BEEPER) || defined(USE_DSHOT)
480 [TASK_BEEPER] = {
481 .taskName = "BEEPER",
482 .taskFunc = beeperUpdate,
483 .desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz
484 .staticPriority = TASK_PRIORITY_MEDIUM,
486 #endif
488 #ifdef USE_LIGHTS
489 [TASK_LIGHTS] = {
490 .taskName = "LIGHTS",
491 .taskFunc = lightsUpdate,
492 .desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz
493 .staticPriority = TASK_PRIORITY_LOW,
495 #endif
497 [TASK_BATTERY] = {
498 .taskName = "BATTERY",
499 .taskFunc = taskUpdateBattery,
500 .desiredPeriod = TASK_PERIOD_HZ(50), // 50 Hz
501 .staticPriority = TASK_PRIORITY_MEDIUM,
504 [TASK_TEMPERATURE] = {
505 .taskName = "TEMPERATURE",
506 .taskFunc = taskUpdateTemperature,
507 .desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz
508 .staticPriority = TASK_PRIORITY_LOW,
511 [TASK_RX] = {
512 .taskName = "RX",
513 .checkFunc = taskUpdateRxCheck,
514 .taskFunc = taskUpdateRxMain,
515 .desiredPeriod = TASK_PERIOD_HZ(10), // If event-based scheduling doesn't work, fallback to periodic scheduling
516 .staticPriority = TASK_PRIORITY_HIGH,
519 #ifdef USE_GPS
520 [TASK_GPS] = {
521 .taskName = "GPS",
522 .taskFunc = taskProcessGPS,
523 .desiredPeriod = TASK_PERIOD_HZ(50), // GPS usually don't go raster than 10Hz
524 .staticPriority = TASK_PRIORITY_MEDIUM,
526 #endif
528 #ifdef USE_MAG
529 [TASK_COMPASS] = {
530 .taskName = "COMPASS",
531 .taskFunc = taskUpdateCompass,
532 .desiredPeriod = TASK_PERIOD_HZ(10), // Compass is updated at 10 Hz
533 .staticPriority = TASK_PRIORITY_MEDIUM,
535 #endif
537 #ifdef USE_ADSB
538 [TASK_ADSB] = {
539 .taskName = "ADSB",
540 .taskFunc = taskAdsb,
541 .desiredPeriod = TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
542 .staticPriority = TASK_PRIORITY_IDLE,
544 #endif
546 #ifdef USE_BARO
547 [TASK_BARO] = {
548 .taskName = "BARO",
549 .taskFunc = taskUpdateBaro,
550 .desiredPeriod = TASK_PERIOD_HZ(20),
551 .staticPriority = TASK_PRIORITY_MEDIUM,
553 #endif
555 #ifdef USE_PITOT
556 [TASK_PITOT] = {
557 .taskName = "PITOT",
558 .taskFunc = taskUpdatePitot,
559 .desiredPeriod = TASK_PERIOD_MS(20),
560 .staticPriority = TASK_PRIORITY_MEDIUM,
562 #endif
564 #ifdef USE_RANGEFINDER
565 [TASK_RANGEFINDER] = {
566 .taskName = "RANGEFINDER",
567 .taskFunc = taskUpdateRangefinder,
568 .desiredPeriod = TASK_PERIOD_MS(70),
569 .staticPriority = TASK_PRIORITY_MEDIUM,
571 #endif
573 #ifdef USE_IRLOCK
574 [TASK_IRLOCK] = {
575 .taskName = "IRLOCK",
576 .taskFunc = taskUpdateIrlock,
577 .desiredPeriod = TASK_PERIOD_HZ(100),
578 .staticPriority = TASK_PRIORITY_MEDIUM,
580 #endif
582 #ifdef USE_DASHBOARD
583 [TASK_DASHBOARD] = {
584 .taskName = "DASHBOARD",
585 .taskFunc = taskDashboardUpdate,
586 .desiredPeriod = TASK_PERIOD_HZ(10),
587 .staticPriority = TASK_PRIORITY_LOW,
589 #endif
591 #ifdef USE_TELEMETRY
592 [TASK_TELEMETRY] = {
593 .taskName = "TELEMETRY",
594 .taskFunc = taskTelemetry,
595 .desiredPeriod = TASK_PERIOD_HZ(500), // 500 Hz
596 .staticPriority = TASK_PRIORITY_IDLE,
598 #endif
600 #if defined(USE_SMARTPORT_MASTER)
601 [TASK_SMARTPORT_MASTER] = {
602 .taskName = "SPORT MASTER",
603 .taskFunc = taskSmartportMaster,
604 .desiredPeriod = TASK_PERIOD_HZ(500), // 500 Hz
605 .staticPriority = TASK_PRIORITY_IDLE,
607 #endif
609 #ifdef USE_LED_STRIP
610 [TASK_LEDSTRIP] = {
611 .taskName = "LEDSTRIP",
612 .taskFunc = taskLedStrip,
613 .desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz
614 .staticPriority = TASK_PRIORITY_IDLE,
616 #endif
618 #if defined(USE_SERVO_SBUS)
619 [TASK_PWMDRIVER] = {
620 .taskName = "SERVOS",
621 .taskFunc = taskSyncServoDriver,
622 .desiredPeriod = TASK_PERIOD_HZ(200), // 200 Hz
623 .staticPriority = TASK_PRIORITY_HIGH,
625 #endif
627 #ifdef STACK_CHECK
628 [TASK_STACK_CHECK] = {
629 .taskName = "STACKCHECK",
630 .taskFunc = taskStackCheck,
631 .desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz
632 .staticPriority = TASK_PRIORITY_IDLE,
634 #endif
636 #ifdef USE_OSD
637 [TASK_OSD] = {
638 .taskName = "OSD",
639 .taskFunc = taskUpdateOsd,
640 .desiredPeriod = TASK_PERIOD_HZ(250),
641 .staticPriority = TASK_PRIORITY_LOW,
643 #endif
645 #ifdef USE_CMS
646 [TASK_CMS] = {
647 .taskName = "CMS",
648 .taskFunc = cmsHandler,
649 .desiredPeriod = TASK_PERIOD_HZ(50),
650 .staticPriority = TASK_PRIORITY_LOW,
652 #endif
654 #ifdef USE_OPFLOW
655 [TASK_OPFLOW] = {
656 .taskName = "OPFLOW",
657 .taskFunc = taskUpdateOpticalFlow,
658 .desiredPeriod = TASK_PERIOD_HZ(100), // I2C/SPI sensor will work at higher rate and accumulate, UART sensor will work at lower rate w/o accumulation
659 .staticPriority = TASK_PRIORITY_MEDIUM,
661 #endif
663 #ifdef USE_RCDEVICE
664 [TASK_RCDEVICE] = {
665 .taskName = "RCDEVICE",
666 .taskFunc = rcdeviceUpdate,
667 .desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz, 100ms
668 .staticPriority = TASK_PRIORITY_MEDIUM,
670 #endif
672 #if defined(USE_VTX_CONTROL)
673 [TASK_VTXCTRL] = {
674 .taskName = "VTXCTRL",
675 .taskFunc = vtxUpdate,
676 .desiredPeriod = TASK_PERIOD_HZ(5), // 5Hz @200msec
677 .staticPriority = TASK_PRIORITY_IDLE,
679 #endif
680 #ifdef USE_PROGRAMMING_FRAMEWORK
681 [TASK_PROGRAMMING_FRAMEWORK] = {
682 .taskName = "PROGRAMMING",
683 .taskFunc = programmingFrameworkUpdateTask,
684 .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec
685 .staticPriority = TASK_PRIORITY_IDLE,
687 #endif
688 #ifdef USE_RPM_FILTER
689 [TASK_RPM_FILTER] = {
690 .taskName = "RPM",
691 .taskFunc = rpmFilterUpdateTask,
692 .desiredPeriod = TASK_PERIOD_HZ(RPM_FILTER_UPDATE_RATE_HZ), // 300Hz @3,33ms
693 .staticPriority = TASK_PRIORITY_LOW,
695 #endif
696 [TASK_AUX] = {
697 .taskName = "AUX",
698 .taskFunc = taskUpdateAux,
699 .desiredPeriod = TASK_PERIOD_HZ(TASK_AUX_RATE_HZ), // 100Hz @10ms
700 .staticPriority = TASK_PRIORITY_HIGH,
702 #ifdef USE_ADAPTIVE_FILTER
703 [TASK_ADAPTIVE_FILTER] = {
704 .taskName = "ADAPTIVE_FILTER",
705 .taskFunc = adaptiveFilterTask,
706 .desiredPeriod = TASK_PERIOD_HZ(ADAPTIVE_FILTER_RATE_HZ), // 100Hz @10ms
707 .staticPriority = TASK_PRIORITY_LOW,
709 #endif
711 #ifdef USE_SERIAL_GIMBAL
712 [TASK_GIMBAL] = {
713 .taskName = "GIMBAL",
714 .taskFunc = taskUpdateGimbal,
715 .desiredPeriod = TASK_PERIOD_HZ(50),
716 .staticPriority = TASK_PRIORITY_MEDIUM,
718 #endif
720 #ifdef USE_HEADTRACKER
721 [TASK_HEADTRACKER] = {
722 .taskName = "HEADTRACKER",
723 .taskFunc = taskUpdateHeadTracker,
724 .desiredPeriod = TASK_PERIOD_HZ(50),
725 .staticPriority = TASK_PRIORITY_MEDIUM,
727 #endif