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/>.
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"
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"
64 #include "io/ledstrip.h"
66 #include "io/serial.h"
67 #include "io/rcdevice_cam.h"
68 #include "io/osd_joystick.h"
69 #include "io/smartport_master.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"
77 #include "msp/msp_serial.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"
96 #include "telemetry/sbus2.h"
98 #include "config/feature.h"
100 #if defined(SITL_BUILD)
101 #include "target/SITL/serial_proxy.h"
104 void taskHandleSerial(timeUs_t currentTimeUs
)
106 UNUSED(currentTimeUs
);
107 // in cli mode, all serial stuff goes to here. enter cli mode by sending #
112 // Allow MSP processing even if in CLI mode
113 mspSerialProcess(ARMING_FLAG(ARMED
) ? MSP_SKIP_NON_MSP_DATA
: MSP_EVALUATE_NON_MSP_DATA
, mspFcProcessCommand
);
115 #if defined(USE_DJI_HD_OSD)
116 // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task
117 djiOsdSerialProcess();
121 // Capture MSP Displayport messages to determine if VTX is connected
122 mspOsdSerialProcess(mspFcProcessCommand
);
124 mspVtxSerialProcess(mspFcProcessCommand
);
129 void taskUpdateBattery(timeUs_t currentTimeUs
)
131 static timeUs_t batMonitoringLastServiced
= 0;
132 timeDelta_t BatMonitoringTimeSinceLastServiced
= cmpTimeUs(currentTimeUs
, batMonitoringLastServiced
);
134 if (isAmperageConfigured()) {
135 currentMeterUpdate(BatMonitoringTimeSinceLastServiced
);
136 #ifdef USE_POWER_LIMITS
137 currentLimiterUpdate(BatMonitoringTimeSinceLastServiced
);
142 if (feature(FEATURE_VBAT
)) {
143 batteryUpdate(BatMonitoringTimeSinceLastServiced
);
146 if (feature(FEATURE_VBAT
) && isAmperageConfigured()) {
147 powerMeterUpdate(BatMonitoringTimeSinceLastServiced
);
148 sagCompensatedVBatUpdate(currentTimeUs
, BatMonitoringTimeSinceLastServiced
);
149 #if defined(USE_POWER_LIMITS) && defined(USE_ADC)
150 powerLimiterUpdate(BatMonitoringTimeSinceLastServiced
);
155 batMonitoringLastServiced
= currentTimeUs
;
158 void taskUpdateTemperature(timeUs_t currentTimeUs
)
160 UNUSED(currentTimeUs
);
165 void taskProcessGPS(timeUs_t currentTimeUs
)
167 // if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
168 // hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
169 // change this based on available hardware
170 if (feature(FEATURE_GPS
)) {
172 #ifdef USE_WIND_ESTIMATOR
173 updateWindEstimator(currentTimeUs
);
178 if (sensors(SENSOR_GPS
)) {
179 updateGpsIndicator(currentTimeUs
);
185 void taskUpdateCompass(timeUs_t currentTimeUs
)
187 if (sensors(SENSOR_MAG
)) {
188 compassUpdate(currentTimeUs
);
194 void taskAdsb(timeUs_t currentTimeUs
)
196 UNUSED(currentTimeUs
);
197 adsbTtlClean(currentTimeUs
);
202 void taskUpdateBaro(timeUs_t currentTimeUs
)
204 if (!sensors(SENSOR_BARO
)) {
208 const uint32_t newDeadline
= baroUpdate();
209 if (newDeadline
!= 0) {
210 rescheduleTask(TASK_SELF
, newDeadline
);
213 updatePositionEstimator_BaroTopic(currentTimeUs
);
218 void taskUpdatePitot(timeUs_t currentTimeUs
)
220 if (!sensors(SENSOR_PITOT
)) {
226 if ( pitotIsHealthy()) {
227 updatePositionEstimator_PitotTopic(currentTimeUs
);
232 #ifdef USE_RANGEFINDER
233 void taskUpdateRangefinder(timeUs_t currentTimeUs
)
235 UNUSED(currentTimeUs
);
237 if (!sensors(SENSOR_RANGEFINDER
))
240 // Update and adjust task to update at required rate
241 const uint32_t newDeadline
= rangefinderUpdate();
242 if (newDeadline
!= 0) {
243 rescheduleTask(TASK_SELF
, newDeadline
);
247 * Process raw rangefinder readout
249 if (rangefinderProcess(calculateCosTiltAngle())) {
250 updatePositionEstimator_SurfaceTopic(currentTimeUs
, rangefinderGetLatestAltitude());
255 #if defined(USE_IRLOCK)
256 void taskUpdateIrlock(timeUs_t currentTimeUs
)
258 UNUSED(currentTimeUs
);
264 void taskUpdateOpticalFlow(timeUs_t currentTimeUs
)
266 if (!sensors(SENSOR_OPFLOW
))
269 opflowUpdate(currentTimeUs
);
270 updatePositionEstimator_OpticalFlowTopic(currentTimeUs
);
275 void taskDashboardUpdate(timeUs_t currentTimeUs
)
277 if (feature(FEATURE_DASHBOARD
)) {
278 dashboardUpdate(currentTimeUs
);
284 void taskTelemetry(timeUs_t currentTimeUs
)
286 telemetryCheckState();
288 if (!cliMode
&& feature(FEATURE_TELEMETRY
)) {
289 telemetryProcess(currentTimeUs
);
294 #if defined(USE_SMARTPORT_MASTER)
295 void taskSmartportMaster(timeUs_t currentTimeUs
)
297 smartportMasterHandle(currentTimeUs
);
302 void taskLedStrip(timeUs_t currentTimeUs
)
304 if (feature(FEATURE_LED_STRIP
)) {
305 ledStripUpdate(currentTimeUs
);
310 void taskSyncServoDriver(timeUs_t currentTimeUs
)
312 UNUSED(currentTimeUs
);
314 #if defined(USE_SERVO_SBUS)
315 sbusServoSendUpdate();
321 void taskUpdateOsd(timeUs_t currentTimeUs
)
323 if (feature(FEATURE_OSD
)) {
324 osdUpdate(currentTimeUs
);
329 void taskUpdateAux(timeUs_t currentTimeUs
)
331 updatePIDCoefficients();
332 dynamicLpfGyroTask();
334 if (!ARMING_FLAG(SIMULATOR_MODE_HITL
)) {
335 updateFixedWingLevelTrim(currentTimeUs
);
338 updateFixedWingLevelTrim(currentTimeUs
);
342 void fcTasksInit(void)
346 rescheduleTask(TASK_PID
, getLooptime());
347 setTaskEnabled(TASK_PID
, true);
349 rescheduleTask(TASK_GYRO
, getGyroLooptime());
350 setTaskEnabled(TASK_GYRO
, true);
352 setTaskEnabled(TASK_AUX
, true);
354 setTaskEnabled(TASK_SERIAL
, true);
355 #if defined(BEEPER) || defined(USE_DSHOT)
356 setTaskEnabled(TASK_BEEPER
, true);
359 setTaskEnabled(TASK_LIGHTS
, true);
361 setTaskEnabled(TASK_BATTERY
, feature(FEATURE_VBAT
) || isAmperageConfigured());
362 setTaskEnabled(TASK_TEMPERATURE
, true);
363 setTaskEnabled(TASK_RX
, true);
365 setTaskEnabled(TASK_GPS
, feature(FEATURE_GPS
));
368 setTaskEnabled(TASK_COMPASS
, sensors(SENSOR_MAG
));
369 #if defined(USE_MAG_MPU9250)
370 // fixme temporary solution for AK6983 via slave I2C on MPU9250
371 rescheduleTask(TASK_COMPASS
, TASK_PERIOD_HZ(40));
375 setTaskEnabled(TASK_BARO
, sensors(SENSOR_BARO
));
378 setTaskEnabled(TASK_PITOT
, sensors(SENSOR_PITOT
));
381 setTaskEnabled(TASK_ADSB
, true);
383 #ifdef USE_RANGEFINDER
384 setTaskEnabled(TASK_RANGEFINDER
, sensors(SENSOR_RANGEFINDER
));
387 setTaskEnabled(TASK_DASHBOARD
, feature(FEATURE_DASHBOARD
));
390 setTaskEnabled(TASK_TELEMETRY
, feature(FEATURE_TELEMETRY
));
393 setTaskEnabled(TASK_LEDSTRIP
, feature(FEATURE_LED_STRIP
));
396 setTaskEnabled(TASK_STACK_CHECK
, true);
398 #if defined(USE_SERVO_SBUS)
399 setTaskEnabled(TASK_PWMDRIVER
, (servoConfig()->servo_protocol
== SERVO_TYPE_SBUS
) || (servoConfig()->servo_protocol
== SERVO_TYPE_SBUS_PWM
));
402 #ifdef USE_MSP_DISPLAYPORT
403 setTaskEnabled(TASK_CMS
, true);
405 setTaskEnabled(TASK_CMS
, feature(FEATURE_OSD
) || feature(FEATURE_DASHBOARD
));
409 setTaskEnabled(TASK_OPFLOW
, sensors(SENSOR_OPFLOW
));
411 #ifdef USE_VTX_CONTROL
412 #if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
413 setTaskEnabled(TASK_VTXCTRL
, true);
418 setTaskEnabled(TASK_RCDEVICE
, rcdeviceIsEnabled() || osdJoystickEnabled());
420 setTaskEnabled(TASK_RCDEVICE
, rcdeviceIsEnabled());
423 #ifdef USE_PROGRAMMING_FRAMEWORK
424 setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK
, true);
427 setTaskEnabled(TASK_IRLOCK
, irlockHasBeenDetected());
429 #if defined(USE_SMARTPORT_MASTER)
430 setTaskEnabled(TASK_SMARTPORT_MASTER
, true);
433 #ifdef USE_SERIAL_GIMBAL
434 setTaskEnabled(TASK_GIMBAL
, true);
437 #ifdef USE_HEADTRACKER
438 setTaskEnabled(TASK_HEADTRACKER
, true);
441 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2)
442 setTaskEnabled(TASK_TELEMETRY_SBUS2
,feature(FEATURE_TELEMETRY
) && rxConfig()->receiverType
== RX_TYPE_SERIAL
&& rxConfig()->serialrx_provider
== SERIALRX_SBUS2
);
445 #ifdef USE_ADAPTIVE_FILTER
446 setTaskEnabled(TASK_ADAPTIVE_FILTER
, (
447 gyroConfig()->gyroFilterMode
== GYRO_FILTER_MODE_ADAPTIVE
&&
448 gyroConfig()->adaptiveFilterMinHz
> 0 &&
449 gyroConfig()->adaptiveFilterMaxHz
> 0
453 #if defined(SITL_BUILD)
458 cfTask_t cfTasks
[TASK_COUNT
] = {
460 .taskName
= "SYSTEM",
461 .taskFunc
= taskSystem
,
462 .desiredPeriod
= TASK_PERIOD_HZ(10), // run every 100 ms, 10Hz
463 .staticPriority
= TASK_PRIORITY_HIGH
,
467 .taskFunc
= taskMainPidLoop
,
468 .desiredPeriod
= TASK_PERIOD_US(1000),
469 .staticPriority
= TASK_PRIORITY_REALTIME
,
473 .taskFunc
= taskGyro
,
474 .desiredPeriod
= TASK_PERIOD_US(TASK_GYRO_LOOPTIME
),
475 .staticPriority
= TASK_PRIORITY_REALTIME
,
478 .taskName
= "SERIAL",
479 .taskFunc
= taskHandleSerial
,
480 .desiredPeriod
= TASK_PERIOD_HZ(100), // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
481 .staticPriority
= TASK_PRIORITY_LOW
,
484 #if defined(BEEPER) || defined(USE_DSHOT)
486 .taskName
= "BEEPER",
487 .taskFunc
= beeperUpdate
,
488 .desiredPeriod
= TASK_PERIOD_HZ(100), // 100 Hz
489 .staticPriority
= TASK_PRIORITY_MEDIUM
,
495 .taskName
= "LIGHTS",
496 .taskFunc
= lightsUpdate
,
497 .desiredPeriod
= TASK_PERIOD_HZ(100), // 100 Hz
498 .staticPriority
= TASK_PRIORITY_LOW
,
503 .taskName
= "BATTERY",
504 .taskFunc
= taskUpdateBattery
,
505 .desiredPeriod
= TASK_PERIOD_HZ(50), // 50 Hz
506 .staticPriority
= TASK_PRIORITY_MEDIUM
,
509 [TASK_TEMPERATURE
] = {
510 .taskName
= "TEMPERATURE",
511 .taskFunc
= taskUpdateTemperature
,
512 .desiredPeriod
= TASK_PERIOD_HZ(100), // 100 Hz
513 .staticPriority
= TASK_PRIORITY_LOW
,
518 .checkFunc
= taskUpdateRxCheck
,
519 .taskFunc
= taskUpdateRxMain
,
520 .desiredPeriod
= TASK_PERIOD_HZ(10), // If event-based scheduling doesn't work, fallback to periodic scheduling
521 .staticPriority
= TASK_PRIORITY_HIGH
,
527 .taskFunc
= taskProcessGPS
,
528 .desiredPeriod
= TASK_PERIOD_HZ(50), // GPS usually don't go raster than 10Hz
529 .staticPriority
= TASK_PRIORITY_MEDIUM
,
535 .taskName
= "COMPASS",
536 .taskFunc
= taskUpdateCompass
,
537 .desiredPeriod
= TASK_PERIOD_HZ(10), // Compass is updated at 10 Hz
538 .staticPriority
= TASK_PRIORITY_MEDIUM
,
545 .taskFunc
= taskAdsb
,
546 .desiredPeriod
= TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
547 .staticPriority
= TASK_PRIORITY_IDLE
,
554 .taskFunc
= taskUpdateBaro
,
555 .desiredPeriod
= TASK_PERIOD_HZ(20),
556 .staticPriority
= TASK_PRIORITY_MEDIUM
,
563 .taskFunc
= taskUpdatePitot
,
564 .desiredPeriod
= TASK_PERIOD_MS(20),
565 .staticPriority
= TASK_PRIORITY_MEDIUM
,
569 #ifdef USE_RANGEFINDER
570 [TASK_RANGEFINDER
] = {
571 .taskName
= "RANGEFINDER",
572 .taskFunc
= taskUpdateRangefinder
,
573 .desiredPeriod
= TASK_PERIOD_MS(70),
574 .staticPriority
= TASK_PRIORITY_MEDIUM
,
580 .taskName
= "IRLOCK",
581 .taskFunc
= taskUpdateIrlock
,
582 .desiredPeriod
= TASK_PERIOD_HZ(100),
583 .staticPriority
= TASK_PRIORITY_MEDIUM
,
589 .taskName
= "DASHBOARD",
590 .taskFunc
= taskDashboardUpdate
,
591 .desiredPeriod
= TASK_PERIOD_HZ(10),
592 .staticPriority
= TASK_PRIORITY_LOW
,
598 .taskName
= "TELEMETRY",
599 .taskFunc
= taskTelemetry
,
600 .desiredPeriod
= TASK_PERIOD_HZ(500), // 500 Hz
601 .staticPriority
= TASK_PRIORITY_IDLE
,
605 #if defined(USE_SMARTPORT_MASTER)
606 [TASK_SMARTPORT_MASTER
] = {
607 .taskName
= "SPORT MASTER",
608 .taskFunc
= taskSmartportMaster
,
609 .desiredPeriod
= TASK_PERIOD_HZ(500), // 500 Hz
610 .staticPriority
= TASK_PRIORITY_IDLE
,
616 .taskName
= "LEDSTRIP",
617 .taskFunc
= taskLedStrip
,
618 .desiredPeriod
= TASK_PERIOD_HZ(100), // 100 Hz
619 .staticPriority
= TASK_PRIORITY_IDLE
,
623 #if defined(USE_SERVO_SBUS)
625 .taskName
= "SERVOS",
626 .taskFunc
= taskSyncServoDriver
,
627 .desiredPeriod
= TASK_PERIOD_HZ(200), // 200 Hz
628 .staticPriority
= TASK_PRIORITY_HIGH
,
633 [TASK_STACK_CHECK
] = {
634 .taskName
= "STACKCHECK",
635 .taskFunc
= taskStackCheck
,
636 .desiredPeriod
= TASK_PERIOD_HZ(10), // 10 Hz
637 .staticPriority
= TASK_PRIORITY_IDLE
,
644 .taskFunc
= taskUpdateOsd
,
645 .desiredPeriod
= TASK_PERIOD_HZ(250),
646 .staticPriority
= TASK_PRIORITY_LOW
,
653 .taskFunc
= cmsHandler
,
654 .desiredPeriod
= TASK_PERIOD_HZ(50),
655 .staticPriority
= TASK_PRIORITY_LOW
,
661 .taskName
= "OPFLOW",
662 .taskFunc
= taskUpdateOpticalFlow
,
663 .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
664 .staticPriority
= TASK_PRIORITY_MEDIUM
,
670 .taskName
= "RCDEVICE",
671 .taskFunc
= rcdeviceUpdate
,
672 .desiredPeriod
= TASK_PERIOD_HZ(10), // 10 Hz, 100ms
673 .staticPriority
= TASK_PRIORITY_MEDIUM
,
677 #if defined(USE_VTX_CONTROL)
679 .taskName
= "VTXCTRL",
680 .taskFunc
= vtxUpdate
,
681 .desiredPeriod
= TASK_PERIOD_HZ(5), // 5Hz @200msec
682 .staticPriority
= TASK_PRIORITY_IDLE
,
685 #ifdef USE_PROGRAMMING_FRAMEWORK
686 [TASK_PROGRAMMING_FRAMEWORK
] = {
687 .taskName
= "PROGRAMMING",
688 .taskFunc
= programmingFrameworkUpdateTask
,
689 .desiredPeriod
= TASK_PERIOD_HZ(10), // 10Hz @100msec
690 .staticPriority
= TASK_PRIORITY_IDLE
,
693 #ifdef USE_RPM_FILTER
694 [TASK_RPM_FILTER
] = {
696 .taskFunc
= rpmFilterUpdateTask
,
697 .desiredPeriod
= TASK_PERIOD_HZ(RPM_FILTER_UPDATE_RATE_HZ
), // 300Hz @3,33ms
698 .staticPriority
= TASK_PRIORITY_LOW
,
703 .taskFunc
= taskUpdateAux
,
704 .desiredPeriod
= TASK_PERIOD_HZ(TASK_AUX_RATE_HZ
), // 100Hz @10ms
705 .staticPriority
= TASK_PRIORITY_HIGH
,
707 #ifdef USE_ADAPTIVE_FILTER
708 [TASK_ADAPTIVE_FILTER
] = {
709 .taskName
= "ADAPTIVE_FILTER",
710 .taskFunc
= adaptiveFilterTask
,
711 .desiredPeriod
= TASK_PERIOD_HZ(ADAPTIVE_FILTER_RATE_HZ
), // 100Hz @10ms
712 .staticPriority
= TASK_PRIORITY_LOW
,
716 #ifdef USE_SERIAL_GIMBAL
718 .taskName
= "GIMBAL",
719 .taskFunc
= taskUpdateGimbal
,
720 .desiredPeriod
= TASK_PERIOD_HZ(50),
721 .staticPriority
= TASK_PRIORITY_MEDIUM
,
725 #ifdef USE_HEADTRACKER
726 [TASK_HEADTRACKER
] = {
727 .taskName
= "HEADTRACKER",
728 .taskFunc
= taskUpdateHeadTracker
,
729 .desiredPeriod
= TASK_PERIOD_HZ(50),
730 .staticPriority
= TASK_PRIORITY_MEDIUM
,
734 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2)
735 [TASK_TELEMETRY_SBUS2
] = {
736 .taskName
= "SBUS2 TLM",
737 .taskFunc
= taskSendSbus2Telemetry
,
738 .desiredPeriod
= TASK_PERIOD_US(125), // 8kHz 2ms dead time + 650us window / sensor.
739 .staticPriority
= TASK_PRIORITY_LOW
, // timing is critical. Ideally, should be a timer interrupt triggered by sbus packet