Add OSD_STATE_GROUP_ELEMENTS state to osdUpdate() and optimise DMA vs polled MAX7456...
[betaflight.git] / src / main / build / debug.h
blob8494550257ae3ea42cc615d39aee2c2ac8a37c39
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #pragma once
23 #define DEBUG16_VALUE_COUNT 4
24 extern int16_t debug[DEBUG16_VALUE_COUNT];
25 extern uint8_t debugMode;
27 #define DEBUG_SET(mode, index, value) do { if (debugMode == (mode)) { debug[(index)] = (value); } } while (0)
29 typedef enum {
30 DEBUG_NONE,
31 DEBUG_CYCLETIME,
32 DEBUG_BATTERY,
33 DEBUG_GYRO_FILTERED,
34 DEBUG_ACCELEROMETER,
35 DEBUG_PIDLOOP,
36 DEBUG_GYRO_SCALED,
37 DEBUG_RC_INTERPOLATION,
38 DEBUG_ANGLERATE,
39 DEBUG_ESC_SENSOR,
40 DEBUG_SCHEDULER,
41 DEBUG_STACK,
42 DEBUG_ESC_SENSOR_RPM,
43 DEBUG_ESC_SENSOR_TMP,
44 DEBUG_ALTITUDE,
45 DEBUG_FFT,
46 DEBUG_FFT_TIME,
47 DEBUG_FFT_FREQ,
48 DEBUG_RX_FRSKY_SPI,
49 DEBUG_RX_SFHSS_SPI,
50 DEBUG_GYRO_RAW,
51 DEBUG_DUAL_GYRO_RAW,
52 DEBUG_DUAL_GYRO_DIFF,
53 DEBUG_MAX7456_SIGNAL,
54 DEBUG_MAX7456_SPICLOCK,
55 DEBUG_SBUS,
56 DEBUG_FPORT,
57 DEBUG_RANGEFINDER,
58 DEBUG_RANGEFINDER_QUALITY,
59 DEBUG_LIDAR_TF,
60 DEBUG_ADC_INTERNAL,
61 DEBUG_RUNAWAY_TAKEOFF,
62 DEBUG_SDIO,
63 DEBUG_CURRENT_SENSOR,
64 DEBUG_USB,
65 DEBUG_SMARTAUDIO,
66 DEBUG_RTH,
67 DEBUG_ITERM_RELAX,
68 DEBUG_ACRO_TRAINER,
69 DEBUG_RC_SMOOTHING,
70 DEBUG_RX_SIGNAL_LOSS,
71 DEBUG_RC_SMOOTHING_RATE,
72 DEBUG_ANTI_GRAVITY,
73 DEBUG_DYN_LPF,
74 DEBUG_RX_SPEKTRUM_SPI,
75 DEBUG_DSHOT_RPM_TELEMETRY,
76 DEBUG_RPM_FILTER,
77 DEBUG_D_MIN,
78 DEBUG_AC_CORRECTION,
79 DEBUG_AC_ERROR,
80 DEBUG_DUAL_GYRO_SCALED,
81 DEBUG_DSHOT_RPM_ERRORS,
82 DEBUG_CRSF_LINK_STATISTICS_UPLINK,
83 DEBUG_CRSF_LINK_STATISTICS_PWR,
84 DEBUG_CRSF_LINK_STATISTICS_DOWN,
85 DEBUG_BARO,
86 DEBUG_GPS_RESCUE_THROTTLE_PID,
87 DEBUG_DYN_IDLE,
88 DEBUG_FEEDFORWARD_LIMIT,
89 DEBUG_FEEDFORWARD,
90 DEBUG_BLACKBOX_OUTPUT,
91 DEBUG_GYRO_SAMPLE,
92 DEBUG_RX_TIMING,
93 DEBUG_D_LPF,
94 DEBUG_VTX_TRAMP,
95 DEBUG_GHST,
96 DEBUG_SCHEDULER_DETERMINISM,
97 DEBUG_TIMING_ACCURACY,
98 DEBUG_RX_EXPRESSLRS_SPI,
99 DEBUG_RX_EXPRESSLRS_PHASELOCK,
100 DEBUG_RX_STATE_TIME,
101 DEBUG_COUNT
102 } debugType_e;
104 extern const char * const debugModeNames[DEBUG_COUNT];