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/>.
20 // FIXME some of these are flight modes, some of these are general status indicators
23 WAS_EVER_ARMED
= (1 << 3),
24 SIMULATOR_MODE_HITL
= (1 << 4),
25 SIMULATOR_MODE_SITL
= (1 << 5),
27 ARMING_DISABLED_FAILSAFE_SYSTEM
= (1 << 7),
28 ARMING_DISABLED_NOT_LEVEL
= (1 << 8),
29 ARMING_DISABLED_SENSORS_CALIBRATING
= (1 << 9),
30 ARMING_DISABLED_SYSTEM_OVERLOADED
= (1 << 10),
31 ARMING_DISABLED_NAVIGATION_UNSAFE
= (1 << 11),
32 ARMING_DISABLED_COMPASS_NOT_CALIBRATED
= (1 << 12),
33 ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED
= (1 << 13),
34 ARMING_DISABLED_ARM_SWITCH
= (1 << 14),
35 ARMING_DISABLED_HARDWARE_FAILURE
= (1 << 15),
36 ARMING_DISABLED_BOXFAILSAFE
= (1 << 16),
37 ARMING_DISABLED_BOXKILLSWITCH
= (1 << 17),
38 ARMING_DISABLED_RC_LINK
= (1 << 18),
39 ARMING_DISABLED_THROTTLE
= (1 << 19),
40 ARMING_DISABLED_CLI
= (1 << 20),
41 ARMING_DISABLED_CMS_MENU
= (1 << 21),
42 ARMING_DISABLED_OSD_MENU
= (1 << 22),
43 ARMING_DISABLED_ROLLPITCH_NOT_CENTERED
= (1 << 23),
44 ARMING_DISABLED_SERVO_AUTOTRIM
= (1 << 24),
45 ARMING_DISABLED_OOM
= (1 << 25),
46 ARMING_DISABLED_INVALID_SETTING
= (1 << 26),
47 ARMING_DISABLED_PWM_OUTPUT_ERROR
= (1 << 27),
48 ARMING_DISABLED_NO_PREARM
= (1 << 28),
49 ARMING_DISABLED_DSHOT_BEEPER
= (1 << 29),
50 ARMING_DISABLED_LANDING_DETECTED
= (1 << 30),
52 ARMING_DISABLED_ALL_FLAGS
= (ARMING_DISABLED_FAILSAFE_SYSTEM
| ARMING_DISABLED_NOT_LEVEL
| ARMING_DISABLED_SENSORS_CALIBRATING
|
53 ARMING_DISABLED_SYSTEM_OVERLOADED
| ARMING_DISABLED_NAVIGATION_UNSAFE
|
54 ARMING_DISABLED_COMPASS_NOT_CALIBRATED
| ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED
|
55 ARMING_DISABLED_ARM_SWITCH
| ARMING_DISABLED_HARDWARE_FAILURE
| ARMING_DISABLED_BOXFAILSAFE
|
56 ARMING_DISABLED_BOXKILLSWITCH
| ARMING_DISABLED_RC_LINK
| ARMING_DISABLED_THROTTLE
| ARMING_DISABLED_CLI
|
57 ARMING_DISABLED_CMS_MENU
| ARMING_DISABLED_OSD_MENU
| ARMING_DISABLED_ROLLPITCH_NOT_CENTERED
|
58 ARMING_DISABLED_SERVO_AUTOTRIM
| ARMING_DISABLED_OOM
| ARMING_DISABLED_INVALID_SETTING
|
59 ARMING_DISABLED_PWM_OUTPUT_ERROR
| ARMING_DISABLED_NO_PREARM
| ARMING_DISABLED_DSHOT_BEEPER
|
60 ARMING_DISABLED_LANDING_DETECTED
),
63 // Arming blockers that can be overriden by emergency arming.
64 // Keep in mind that this feature is intended to allow arming in
65 // situations where we might just need the motors to spin so the
66 // aircraft can move (even unpredictably) and get unstuck (e.g.
67 // crashed into a high tree).
68 #define ARMING_DISABLED_EMERGENCY_OVERRIDE (ARMING_DISABLED_NOT_LEVEL \
69 | ARMING_DISABLED_NAVIGATION_UNSAFE \
70 | ARMING_DISABLED_COMPASS_NOT_CALIBRATED \
71 | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED \
72 | ARMING_DISABLED_ARM_SWITCH \
73 | ARMING_DISABLED_HARDWARE_FAILURE)
76 extern uint32_t armingFlags
;
78 extern const char *armingDisableFlagNames
[];
80 #define isArmingDisabled() (armingFlags & (ARMING_DISABLED_ALL_FLAGS))
81 #define DISABLE_ARMING_FLAG(mask) (armingFlags &= ~(mask))
82 #define ENABLE_ARMING_FLAG(mask) (armingFlags |= (mask))
83 #define ARMING_FLAG(mask) (armingFlags & (mask))
85 // Returns the 1st flag from ARMING_DISABLED_ALL_FLAGS which is
86 // preventing arming, or zero if arming is not disabled.
87 armingFlag_e
isArmingDisabledReason(void);
90 ANGLE_MODE
= (1 << 0),
91 HORIZON_MODE
= (1 << 1),
92 HEADING_MODE
= (1 << 2),
93 NAV_ALTHOLD_MODE
= (1 << 3),
94 NAV_RTH_MODE
= (1 << 4),
95 NAV_POSHOLD_MODE
= (1 << 5),
96 HEADFREE_MODE
= (1 << 6),
97 NAV_LAUNCH_MODE
= (1 << 7),
98 MANUAL_MODE
= (1 << 8),
99 FAILSAFE_MODE
= (1 << 9),
100 AUTO_TUNE
= (1 << 10),
101 NAV_WP_MODE
= (1 << 11),
102 NAV_COURSE_HOLD_MODE
= (1 << 12),
103 FLAPERON
= (1 << 13),
104 TURN_ASSISTANT
= (1 << 14),
105 TURTLE_MODE
= (1 << 15),
106 SOARING_MODE
= (1 << 16),
107 ATTIHOLD_MODE
= (1 << 17),
110 extern uint32_t flightModeFlags
;
112 #define DISABLE_FLIGHT_MODE(mask) (flightModeFlags &= ~(mask))
113 #define ENABLE_FLIGHT_MODE(mask) (flightModeFlags |= (mask))
114 #define FLIGHT_MODE(mask) (flightModeFlags & (mask))
117 GPS_FIX_HOME
= (1 << 0),
119 CALIBRATE_MAG
= (1 << 2),
120 SMALL_ANGLE
= (1 << 3),
121 FIXED_WING_LEGACY
= (1 << 4), // No new code should use this state. Use AIRPLANE, MULTIROTOR, ROVER, BOAT, ALTITUDE_CONTROL and MOVE_FORWARD_ONLY states
122 ANTI_WINDUP
= (1 << 5),
123 FLAPERON_AVAILABLE
= (1 << 6),
124 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
125 COMPASS_CALIBRATED
= (1 << 8),
126 ACCELEROMETER_CALIBRATED
= (1 << 9),
127 NAV_CRUISE_BRAKING
= (1 << 11),
128 NAV_CRUISE_BRAKING_BOOST
= (1 << 12),
129 NAV_CRUISE_BRAKING_LOCKED
= (1 << 13),
130 NAV_EXTRA_ARMING_SAFETY_BYPASSED
= (1 << 14), // nav_extra_arming_safey was bypassed. Keep it until power cycle.
131 AIRMODE_ACTIVE
= (1 << 15),
132 ESC_SENSOR_ENABLED
= (1 << 16),
133 AIRPLANE
= (1 << 17),
134 MULTIROTOR
= (1 << 18),
137 ALTITUDE_CONTROL
= (1 << 21), //It means it can fly
138 MOVE_FORWARD_ONLY
= (1 << 22),
139 SET_REVERSIBLE_MOTORS_FORWARD
= (1 << 23),
140 FW_HEADING_USE_YAW
= (1 << 24),
141 ANTI_WINDUP_DEACTIVATED
= (1 << 25),
142 LANDING_DETECTED
= (1 << 26),
143 IN_FLIGHT_EMERG_REARM
= (1 << 27),
146 #define DISABLE_STATE(mask) (stateFlags &= ~(mask))
147 #define ENABLE_STATE(mask) (stateFlags |= (mask))
148 #define STATE(mask) (stateFlags & (mask))
150 extern uint32_t stateFlags
;
168 } flightModeForTelemetry_e
;
170 flightModeForTelemetry_e
getFlightModeForTelemetry(void);
174 #define SIMULATOR_MSP_VERSION 2 // Simulator MSP version
175 #define SIMULATOR_BARO_TEMP 25 // °C
176 #define SIMULATOR_FULL_BATTERY 12.6f // Volts
177 #define SIMULATOR_HAS_OPTION(flag) ((simulatorData.flags & flag) != 0)
180 HITL_RESET_FLAGS
= (0 << 0),
181 HITL_ENABLE
= (1 << 0),
182 HITL_SIMULATE_BATTERY
= (1 << 1),
183 HITL_MUTE_BEEPER
= (1 << 2),
184 HITL_USE_IMU
= (1 << 3), // Use the Acc and Gyro data provided by XPlane to calculate Attitude (i.e. 100% of the calculations made by AHRS from INAV)
185 HITL_HAS_NEW_GPS_DATA
= (1 << 4),
186 HITL_EXT_BATTERY_VOLTAGE
= (1 << 5), // Extend MSP_SIMULATOR format 2
187 HITL_AIRSPEED
= (1 << 6),
188 HITL_EXTENDED_FLAGS
= (1 << 7), // Extend MSP_SIMULATOR format 2
189 HITL_GPS_TIMEOUT
= (1 << 8),
190 HITL_PITOT_FAILURE
= (1 << 9)
194 simulatorFlags_t flags
;
196 uint8_t vbat
; // 126 -> 12.6V
197 uint16_t airSpeed
; // cm/s
201 extern simulatorData_t simulatorData
;
205 void updateFlightModeChangeBeeper(void);
207 bool sensors(uint32_t mask
);
208 void sensorsSet(uint32_t mask
);
209 void sensorsClear(uint32_t mask
);
210 uint32_t sensorsMask(void);