adjusted sensors usage in simulator mode
[inav.git] / src / main / fc / runtime_config.h
blob800145bf54e28c11ebf9d6008bd73d48004d7402
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 // FIXME some of these are flight modes, some of these are general status indicators
21 typedef enum {
22 ARMED = (1 << 2),
23 WAS_EVER_ARMED = (1 << 3),
24 SIMULATOR_MODE = (1 << 4),
26 ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7),
27 ARMING_DISABLED_NOT_LEVEL = (1 << 8),
28 ARMING_DISABLED_SENSORS_CALIBRATING = (1 << 9),
29 ARMING_DISABLED_SYSTEM_OVERLOADED = (1 << 10),
30 ARMING_DISABLED_NAVIGATION_UNSAFE = (1 << 11),
31 ARMING_DISABLED_COMPASS_NOT_CALIBRATED = (1 << 12),
32 ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED = (1 << 13),
33 ARMING_DISABLED_ARM_SWITCH = (1 << 14),
34 ARMING_DISABLED_HARDWARE_FAILURE = (1 << 15),
35 ARMING_DISABLED_BOXFAILSAFE = (1 << 16),
36 ARMING_DISABLED_BOXKILLSWITCH = (1 << 17),
37 ARMING_DISABLED_RC_LINK = (1 << 18),
38 ARMING_DISABLED_THROTTLE = (1 << 19),
39 ARMING_DISABLED_CLI = (1 << 20),
40 ARMING_DISABLED_CMS_MENU = (1 << 21),
41 ARMING_DISABLED_OSD_MENU = (1 << 22),
42 ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
43 ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
44 ARMING_DISABLED_OOM = (1 << 25),
45 ARMING_DISABLED_INVALID_SETTING = (1 << 26),
46 ARMING_DISABLED_PWM_OUTPUT_ERROR = (1 << 27),
47 ARMING_DISABLED_NO_PREARM = (1 << 28),
48 ARMING_DISABLED_DSHOT_BEEPER = (1 << 29),
49 ARMING_DISABLED_LANDING_DETECTED = (1 << 30),
51 ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING |
52 ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE |
53 ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
54 ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE |
55 ARMING_DISABLED_BOXKILLSWITCH | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI |
56 ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED |
57 ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING |
58 ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER |
59 ARMING_DISABLED_LANDING_DETECTED),
60 } armingFlag_e;
62 // Arming blockers that can be overriden by emergency arming.
63 // Keep in mind that this feature is intended to allow arming in
64 // situations where we might just need the motors to spin so the
65 // aircraft can move (even unpredictably) and get unstuck (e.g.
66 // crashed into a high tree).
67 #define ARMING_DISABLED_EMERGENCY_OVERRIDE (ARMING_DISABLED_NOT_LEVEL \
68 | ARMING_DISABLED_NAVIGATION_UNSAFE \
69 | ARMING_DISABLED_COMPASS_NOT_CALIBRATED \
70 | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED \
71 | ARMING_DISABLED_ARM_SWITCH \
72 | ARMING_DISABLED_HARDWARE_FAILURE)
75 extern uint32_t armingFlags;
77 extern const char *armingDisableFlagNames[];
79 #define isArmingDisabled() (armingFlags & (ARMING_DISABLED_ALL_FLAGS))
80 #define DISABLE_ARMING_FLAG(mask) (armingFlags &= ~(mask))
81 #define ENABLE_ARMING_FLAG(mask) (armingFlags |= (mask))
82 #define ARMING_FLAG(mask) (armingFlags & (mask))
84 // Returns the 1st flag from ARMING_DISABLED_ALL_FLAGS which is
85 // preventing arming, or zero if arming is not disabled.
86 armingFlag_e isArmingDisabledReason(void);
88 typedef enum {
89 ANGLE_MODE = (1 << 0),
90 HORIZON_MODE = (1 << 1),
91 HEADING_MODE = (1 << 2),
92 NAV_ALTHOLD_MODE = (1 << 3),
93 NAV_RTH_MODE = (1 << 4),
94 NAV_POSHOLD_MODE = (1 << 5),
95 HEADFREE_MODE = (1 << 6),
96 NAV_LAUNCH_MODE = (1 << 7),
97 MANUAL_MODE = (1 << 8),
98 FAILSAFE_MODE = (1 << 9),
99 AUTO_TUNE = (1 << 10),
100 NAV_WP_MODE = (1 << 11),
101 NAV_COURSE_HOLD_MODE = (1 << 12),
102 FLAPERON = (1 << 13),
103 TURN_ASSISTANT = (1 << 14),
104 TURTLE_MODE = (1 << 15),
105 SOARING_MODE = (1 << 16),
106 } flightModeFlags_e;
108 extern uint32_t flightModeFlags;
110 #define DISABLE_FLIGHT_MODE(mask) disableFlightMode(mask)
111 #define ENABLE_FLIGHT_MODE(mask) enableFlightMode(mask)
112 #define FLIGHT_MODE(mask) (flightModeFlags & (mask))
114 typedef enum {
115 GPS_FIX_HOME = (1 << 0),
116 GPS_FIX = (1 << 1),
117 CALIBRATE_MAG = (1 << 2),
118 SMALL_ANGLE = (1 << 3),
119 FIXED_WING_LEGACY = (1 << 4), // No new code should use this state. Use AIRPLANE, MULTIROTOR, ROVER, BOAT, ALTITUDE_CONTROL and MOVE_FORWARD_ONLY states
120 ANTI_WINDUP = (1 << 5),
121 FLAPERON_AVAILABLE = (1 << 6),
122 NAV_MOTOR_STOP_OR_IDLE = (1 << 7), // navigation requests MOTOR_STOP or motor idle regardless of throttle stick, will only activate if MOTOR_STOP feature is available
123 COMPASS_CALIBRATED = (1 << 8),
124 ACCELEROMETER_CALIBRATED = (1 << 9),
125 NAV_CRUISE_BRAKING = (1 << 11),
126 NAV_CRUISE_BRAKING_BOOST = (1 << 12),
127 NAV_CRUISE_BRAKING_LOCKED = (1 << 13),
128 NAV_EXTRA_ARMING_SAFETY_BYPASSED = (1 << 14), // nav_extra_arming_safey was bypassed. Keep it until power cycle.
129 AIRMODE_ACTIVE = (1 << 15),
130 ESC_SENSOR_ENABLED = (1 << 16),
131 AIRPLANE = (1 << 17),
132 MULTIROTOR = (1 << 18),
133 ROVER = (1 << 19),
134 BOAT = (1 << 20),
135 ALTITUDE_CONTROL = (1 << 21), //It means it can fly
136 MOVE_FORWARD_ONLY = (1 << 22),
137 SET_REVERSIBLE_MOTORS_FORWARD = (1 << 23),
138 FW_HEADING_USE_YAW = (1 << 24),
139 ANTI_WINDUP_DEACTIVATED = (1 << 25),
140 LANDING_DETECTED = (1 << 26),
141 } stateFlags_t;
143 #define DISABLE_STATE(mask) (stateFlags &= ~(mask))
144 #define ENABLE_STATE(mask) (stateFlags |= (mask))
145 #define STATE(mask) (stateFlags & (mask))
147 extern uint32_t stateFlags;
149 typedef enum {
150 FLM_MANUAL,
151 FLM_ACRO,
152 FLM_ACRO_AIR,
153 FLM_ANGLE,
154 FLM_HORIZON,
155 FLM_ALTITUDE_HOLD,
156 FLM_POSITION_HOLD,
157 FLM_RTH,
158 FLM_MISSION,
159 FLM_COURSE_HOLD,
160 FLM_CRUISE,
161 FLM_LAUNCH,
162 FLM_FAILSAFE,
163 FLM_COUNT
164 } flightModeForTelemetry_e;
166 flightModeForTelemetry_e getFlightModeForTelemetry(void);
169 typedef enum {
170 SIMU_ENABLE = (1 << 0),
171 SIMU_SIMULATE_BATTERY = (1 << 1),
172 SIMU_MUTE_BEEPER = (1 << 2),
173 SIMU_USE_SENSORS = (1 << 3)
174 } simulatorFlags_t;
176 typedef struct {
177 simulatorFlags_t flags;
178 uint8_t debugIndex;
179 } simulatorData_t;
181 extern simulatorData_t simulatorData;
183 uint32_t enableFlightMode(flightModeFlags_e mask);
184 uint32_t disableFlightMode(flightModeFlags_e mask);
186 bool sensors(uint32_t mask);
187 void sensorsSet(uint32_t mask);
188 void sensorsClear(uint32_t mask);
189 uint32_t sensorsMask(void);