Added throttle flight statistics (#12978)
[betaflight.git] / src / main / build / debug.h
blob7b71d583e94305896c2f4f4910eaaa11869ad6ff
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 #include <stdint.h>
25 #define DEBUG16_VALUE_COUNT 8
26 extern int16_t debug[DEBUG16_VALUE_COUNT];
27 extern uint8_t debugMode;
29 #define DEBUG_SET(mode, index, value) do { if (debugMode == (mode)) { debug[(index)] = (value); } } while (0)
31 typedef enum {
32 DEBUG_NONE,
33 DEBUG_CYCLETIME,
34 DEBUG_BATTERY,
35 DEBUG_GYRO_FILTERED,
36 DEBUG_ACCELEROMETER,
37 DEBUG_PIDLOOP,
38 DEBUG_GYRO_SCALED,
39 DEBUG_RC_INTERPOLATION,
40 DEBUG_ANGLERATE,
41 DEBUG_ESC_SENSOR,
42 DEBUG_SCHEDULER,
43 DEBUG_STACK,
44 DEBUG_ESC_SENSOR_RPM,
45 DEBUG_ESC_SENSOR_TMP,
46 DEBUG_ALTITUDE,
47 DEBUG_FFT,
48 DEBUG_FFT_TIME,
49 DEBUG_FFT_FREQ,
50 DEBUG_RX_FRSKY_SPI,
51 DEBUG_RX_SFHSS_SPI,
52 DEBUG_GYRO_RAW,
53 DEBUG_DUAL_GYRO_RAW,
54 DEBUG_DUAL_GYRO_DIFF,
55 DEBUG_MAX7456_SIGNAL,
56 DEBUG_MAX7456_SPICLOCK,
57 DEBUG_SBUS,
58 DEBUG_FPORT,
59 DEBUG_RANGEFINDER,
60 DEBUG_RANGEFINDER_QUALITY,
61 DEBUG_LIDAR_TF,
62 DEBUG_ADC_INTERNAL,
63 DEBUG_RUNAWAY_TAKEOFF,
64 DEBUG_SDIO,
65 DEBUG_CURRENT_SENSOR,
66 DEBUG_USB,
67 DEBUG_SMARTAUDIO,
68 DEBUG_RTH,
69 DEBUG_ITERM_RELAX,
70 DEBUG_ACRO_TRAINER,
71 DEBUG_RC_SMOOTHING,
72 DEBUG_RX_SIGNAL_LOSS,
73 DEBUG_RC_SMOOTHING_RATE,
74 DEBUG_ANTI_GRAVITY,
75 DEBUG_DYN_LPF,
76 DEBUG_RX_SPEKTRUM_SPI,
77 DEBUG_DSHOT_RPM_TELEMETRY,
78 DEBUG_RPM_FILTER,
79 DEBUG_D_MIN,
80 DEBUG_AC_CORRECTION,
81 DEBUG_AC_ERROR,
82 DEBUG_DUAL_GYRO_SCALED,
83 DEBUG_DSHOT_RPM_ERRORS,
84 DEBUG_CRSF_LINK_STATISTICS_UPLINK,
85 DEBUG_CRSF_LINK_STATISTICS_PWR,
86 DEBUG_CRSF_LINK_STATISTICS_DOWN,
87 DEBUG_BARO,
88 DEBUG_GPS_RESCUE_THROTTLE_PID,
89 DEBUG_DYN_IDLE,
90 DEBUG_FEEDFORWARD_LIMIT,
91 DEBUG_FEEDFORWARD,
92 DEBUG_BLACKBOX_OUTPUT,
93 DEBUG_GYRO_SAMPLE,
94 DEBUG_RX_TIMING,
95 DEBUG_D_LPF,
96 DEBUG_VTX_TRAMP,
97 DEBUG_GHST,
98 DEBUG_GHST_MSP,
99 DEBUG_SCHEDULER_DETERMINISM,
100 DEBUG_TIMING_ACCURACY,
101 DEBUG_RX_EXPRESSLRS_SPI,
102 DEBUG_RX_EXPRESSLRS_PHASELOCK,
103 DEBUG_RX_STATE_TIME,
104 DEBUG_GPS_RESCUE_VELOCITY,
105 DEBUG_GPS_RESCUE_HEADING,
106 DEBUG_GPS_RESCUE_TRACKING,
107 DEBUG_ATTITUDE,
108 DEBUG_VTX_MSP,
109 DEBUG_GPS_DOP,
110 DEBUG_FAILSAFE,
111 DEBUG_GYRO_CALIBRATION,
112 DEBUG_ANGLE_MODE,
113 DEBUG_ANGLE_TARGET,
114 DEBUG_CURRENT_ANGLE,
115 DEBUG_DSHOT_TELEMETRY_COUNTS,
116 DEBUG_RPM_LIMIT,
117 DEBUG_RC_STATS,
118 DEBUG_COUNT
119 } debugType_e;
121 extern const char * const debugModeNames[DEBUG_COUNT];
123 void debugInit(void);