If RSSI Channel is set to Disabled when using S.Bus then generate RSS… (#5090)
[betaflight.git] / src / main / config / config_unittest.h
bloba15d8876faa95cba5dcda63f9646946861f79c06
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 #pragma once
20 #ifdef SRC_MAIN_SCHEDULER_C_
21 #ifdef UNIT_TEST
23 cfTask_t *unittest_scheduler_selectedTask;
24 uint8_t unittest_scheduler_selectedTaskDynamicPriority;
25 uint16_t unittest_scheduler_waitingTasks;
26 bool unittest_outsideRealtimeGuardInterval;
28 #define GET_SCHEDULER_LOCALS() \
29 { \
30 unittest_scheduler_selectedTask = selectedTask; \
31 unittest_scheduler_selectedTaskDynamicPriority = selectedTaskDynamicPriority; \
32 unittest_scheduler_waitingTasks = waitingTasks; \
33 unittest_outsideRealtimeGuardInterval = outsideRealtimeGuardInterval; \
36 #else
38 #define GET_SCHEDULER_LOCALS() {}
40 #endif
41 #endif
44 #ifdef SRC_MAIN_FLIGHT_PID_C_
45 #ifdef UNIT_TEST
47 float unittest_pidLuxFloat_lastErrorForDelta[3];
48 float unittest_pidLuxFloat_delta1[3];
49 float unittest_pidLuxFloat_delta2[3];
50 float unittest_pidLuxFloat_PTerm[3];
51 float unittest_pidLuxFloat_ITerm[3];
52 float unittest_pidLuxFloat_DTerm[3];
54 #define SET_PID_LUX_FLOAT_LOCALS(axis) \
55 { \
56 lastErrorForDelta[axis] = unittest_pidLuxFloat_lastErrorForDelta[axis]; \
57 delta1[axis] = unittest_pidLuxFloat_delta1[axis]; \
58 delta2[axis] = unittest_pidLuxFloat_delta2[axis]; \
61 #define GET_PID_LUX_FLOAT_LOCALS(axis) \
62 { \
63 unittest_pidLuxFloat_lastErrorForDelta[axis] = lastErrorForDelta[axis]; \
64 unittest_pidLuxFloat_delta1[axis] = delta1[axis]; \
65 unittest_pidLuxFloat_delta2[axis] = delta2[axis]; \
66 unittest_pidLuxFloat_PTerm[axis] = PTerm; \
67 unittest_pidLuxFloat_ITerm[axis] = ITerm; \
68 unittest_pidLuxFloat_DTerm[axis] = DTerm; \
71 int32_t unittest_pidMultiWiiRewrite_lastErrorForDelta[3];
72 int32_t unittest_pidMultiWiiRewrite_PTerm[3];
73 int32_t unittest_pidMultiWiiRewrite_ITerm[3];
74 int32_t unittest_pidMultiWiiRewrite_DTerm[3];
76 #define SET_PID_MULTI_WII_REWRITE_LOCALS(axis) \
77 { \
78 lastErrorForDelta[axis] = unittest_pidMultiWiiRewrite_lastErrorForDelta[axis]; \
81 #define GET_PID_MULTI_WII_REWRITE_LOCALS(axis) \
82 { \
83 unittest_pidMultiWiiRewrite_lastErrorForDelta[axis] = lastErrorForDelta[axis]; \
84 unittest_pidMultiWiiRewrite_PTerm[axis] = PTerm; \
85 unittest_pidMultiWiiRewrite_ITerm[axis] = ITerm; \
86 unittest_pidMultiWiiRewrite_DTerm[axis] = DTerm; \
89 #else
91 #define SET_PID_LUX_FLOAT_LOCALS(axis) {}
92 #define GET_PID_LUX_FLOAT_LOCALS(axis) {}
93 #define SET_PID_MULTI_WII_REWRITE_LOCALS(axis) {}
94 #define GET_PID_MULTI_WII_REWRITE_LOCALS(axis) {}
96 #endif // UNIT_TEST
97 #endif // SRC_MAIN_FLIGHT_PID_C_