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)
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/>.
32 #include "config/config.h"
33 #include "config/feature.h"
35 #include "common/maths.h"
36 #include "common/printf.h"
38 #include "drivers/display.h"
39 #include "drivers/osd_symbols.h"
40 #include "drivers/time.h"
41 #include "drivers/dshot.h"
45 #include "fc/rc_modes.h"
46 #include "fc/runtime_config.h"
48 #include "flight/failsafe.h"
49 #include "flight/gps_rescue.h"
50 #include "flight/imu.h"
51 #include "flight/mixer.h"
52 #include "flight/pid.h"
53 #include "flight/pos_hold.h"
55 #include "io/beeper.h"
58 #include "osd/osd_elements.h"
59 #include "osd/osd_warnings.h"
63 #include "sensors/acceleration.h"
64 #include "sensors/adcinternal.h"
65 #include "sensors/battery.h"
66 #include "sensors/sensors.h"
68 const char CRASHFLIP_WARNING
[] = ">CRASH FLIP<";
70 void renderOsdWarning(char *warningText
, bool *blinking
, uint8_t *displayAttr
)
72 const batteryState_e batteryState
= getBatteryState();
73 const timeUs_t currentTimeUs
= micros();
75 static timeUs_t armingDisabledUpdateTimeUs
;
76 static armingDisableFlags_e armingDisabledDisplayFlag
= 0;
78 warningText
[0] = '\0';
79 *displayAttr
= DISPLAYPORT_SEVERITY_NORMAL
;
82 // Cycle through the arming disabled reasons
83 if (osdWarnGetState(OSD_WARNING_ARMING_DISABLE
)) {
84 if (IS_RC_MODE_ACTIVE(BOXARM
) && isArmingDisabled()) {
85 armingDisableFlags_e flags
= getArmingDisableFlags();
87 // Remove the ARMSWITCH flag unless it's the only one
88 if (flags
!= ARMING_DISABLED_ARM_SWITCH
) {
89 flags
&= ~ARMING_DISABLED_ARM_SWITCH
;
92 // Rotate to the next arming disabled reason after a 0.5 second time delay
93 // or if the current flag is no longer set or if just starting
94 if (cmpTimeUs(currentTimeUs
, armingDisabledUpdateTimeUs
) > 500000
95 || (flags
& armingDisabledDisplayFlag
) == 0) {
96 armingDisabledUpdateTimeUs
= currentTimeUs
;
98 armingDisableFlags_e flag
= armingDisabledDisplayFlag
<< 1; // next bit to try or 0
99 armingDisableFlags_e flagsRemaining
= flags
& ~(flag
- 1); // clear all bits <= flag; clear all bits when flag == 0
100 flag
= flagsRemaining
& -flagsRemaining
; // LSB in remaining bits
102 // no bit is set above flag (or flag was 0), try again with all bits
103 flag
= flags
& -flags
;
105 armingDisabledDisplayFlag
= flag
; // store for next iteration
108 tfp_sprintf(warningText
, "%s", getArmingDisableFlagName(armingDisabledDisplayFlag
));
109 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
112 armingDisabledDisplayFlag
= 0; // start from LSB next time
117 if (isTryingToArm() && !ARMING_FLAG(ARMED
)) {
118 int armingDelayTime
= (getLastDshotBeaconCommandTimeUs() + DSHOT_BEACON_GUARD_DELAY_US
- currentTimeUs
) / 1e5
;
119 if (armingDelayTime
< 0) {
122 if (armingDelayTime
>= (DSHOT_BEACON_GUARD_DELAY_US
/ 1e5
- 5)) {
123 tfp_sprintf(warningText
, " BEACON ON"); // Display this message for the first 0.5 seconds
125 tfp_sprintf(warningText
, "ARM IN %d.%d", armingDelayTime
/ 10, armingDelayTime
% 10);
127 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
131 if (osdWarnGetState(OSD_WARNING_FAIL_SAFE
) && failsafeIsActive()) {
132 tfp_sprintf(warningText
, "FAIL SAFE");
133 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
138 // Warn when in flip over after crash mode
139 if (osdWarnGetState(OSD_WARNING_CRASHFLIP
) && IS_RC_MODE_ACTIVE(BOXCRASHFLIP
)) {
140 if (isCrashFlipModeActive()) { // if was armed in crashflip mode
141 tfp_sprintf(warningText
, CRASHFLIP_WARNING
);
142 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
144 } else if (!ARMING_FLAG(ARMED
)) { // if disarmed, but crashflip mode is activated (not allowed / can't happen)
145 tfp_sprintf(warningText
, "CRASHFLIP SW");
146 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
151 #ifdef USE_LAUNCH_CONTROL
152 // Warn when in launch control mode
153 if (osdWarnGetState(OSD_WARNING_LAUNCH_CONTROL
) && isLaunchControlActive()) {
155 if (sensors(SENSOR_ACC
)) {
156 const int pitchAngle
= constrain((attitude
.raw
[FD_PITCH
] - accelerometerConfig()->accelerometerTrims
.raw
[FD_PITCH
]) / 10, -90, 90);
157 tfp_sprintf(warningText
, "LAUNCH %d", pitchAngle
);
161 tfp_sprintf(warningText
, "LAUNCH");
164 // Blink the message if the throttle is within 10% of the launch setting
165 if ( calculateThrottlePercent() >= MAX(currentPidProfile
->launchControlThrottlePercent
- 10, 0)) {
169 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
172 #endif // USE_LAUNCH_CONTROL
175 if (osdWarnGetState(OSD_WARNING_RSSI
) && (getRssiPercent() < osdConfig()->rssi_alarm
)) {
176 tfp_sprintf(warningText
, "RSSI LOW");
177 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
181 #ifdef USE_RX_RSSI_DBM
183 if (osdWarnGetState(OSD_WARNING_RSSI_DBM
) && (getRssiDbm() < osdConfig()->rssi_dbm_alarm
)) {
184 tfp_sprintf(warningText
, "RSSI DBM");
185 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
189 #endif // USE_RX_RSSI_DBM
192 if (osdWarnGetState(OSD_WARNING_RSNR
) && (getRsnr() < osdConfig()->rsnr_alarm
)) {
193 tfp_sprintf(warningText
, "RSNR LOW");
194 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
198 #endif // USE_RX_RSNR
200 #ifdef USE_RX_LINK_QUALITY_INFO
202 if (osdWarnGetState(OSD_WARNING_LINK_QUALITY
) && (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm
)) {
203 tfp_sprintf(warningText
, "LINK QUALITY");
204 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
208 #endif // USE_RX_LINK_QUALITY_INFO
210 if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL
) && batteryState
== BATTERY_CRITICAL
) {
211 tfp_sprintf(warningText
, " LAND NOW");
212 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
217 if (osdWarnGetState(OSD_WARNING_LOAD
) && (getArmingDisableFlags() & ARMING_DISABLED_LOAD
)) {
218 tfp_sprintf(warningText
, "CPU OVERLOAD");
219 *displayAttr
= DISPLAYPORT_SEVERITY_CRITICAL
;
224 #ifdef USE_GPS_RESCUE
225 if (osdWarnGetState(OSD_WARNING_GPS_RESCUE_UNAVAILABLE
) &&
226 ARMING_FLAG(ARMED
) &&
227 gpsRescueIsConfigured() &&
228 !gpsRescueIsDisabled() &&
229 !gpsRescueIsAvailable()) {
230 tfp_sprintf(warningText
, "RESCUE N/A");
231 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
236 if (osdWarnGetState(OSD_WARNING_GPS_RESCUE_DISABLED
) &&
237 ARMING_FLAG(ARMED
) &&
238 gpsRescueIsConfigured() &&
239 gpsRescueIsDisabled()) {
241 statistic_t
*stats
= osdGetStats();
242 if (cmpTimeUs(stats
->armed_time
, OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US
) < 0) {
243 tfp_sprintf(warningText
, "RESCUE OFF");
244 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
250 #endif // USE_GPS_RESCUE
252 #ifdef USE_POSITION_HOLD
253 if (osdWarnGetState(OSD_WARNING_POSHOLD_FAILED
) && posHoldFailure()) {
254 tfp_sprintf(warningText
, "POSHOLD FAIL");
255 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
261 // Show warning if in HEADFREE flight mode
262 if (FLIGHT_MODE(HEADFREE_MODE
)) {
263 tfp_sprintf(warningText
, "HEADFREE");
264 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
269 #ifdef USE_ADC_INTERNAL
270 const int16_t coreTemperature
= getCoreTemperatureCelsius();
271 if (osdWarnGetState(OSD_WARNING_CORE_TEMPERATURE
) && coreTemperature
>= osdConfig()->core_temp_alarm
) {
272 tfp_sprintf(warningText
, "CORE %c: %3d%c", SYM_TEMPERATURE
, osdConvertTemperatureToSelectedUnit(coreTemperature
), osdGetTemperatureSymbolForSelectedUnit());
273 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
277 #endif // USE_ADC_INTERNAL
279 #ifdef USE_ESC_SENSOR
280 // Show warning if we lose motor output, the ESC is overheating or excessive current draw
281 if (featureIsEnabled(FEATURE_ESC_SENSOR
) && osdWarnGetState(OSD_WARNING_ESC_FAIL
) && ARMING_FLAG(ARMED
)) {
282 char* p
= warningText
;
286 bool escWarning
= false;
287 for (unsigned i
= 0; i
< getMotorCount() && p
< warningText
+ OSD_WARNINGS_MAX_SIZE
- 1; i
++) {
288 escSensorData_t
*escData
= getEscSensorData(i
);
289 // if everything is OK just display motor number else R, T or C
290 if (osdConfig()->esc_current_alarm
!= ESC_CURRENT_ALARM_OFF
291 && escData
->current
>= osdConfig()->esc_current_alarm
) {
294 } else if (osdConfig()->esc_temp_alarm
!= ESC_TEMP_ALARM_OFF
295 && escData
->temperature
>= osdConfig()->esc_temp_alarm
) {
298 } else if (osdConfig()->esc_rpm_alarm
!= ESC_RPM_ALARM_OFF
299 && erpmToRpm(escData
->rpm
) <= osdConfig()->esc_rpm_alarm
) {
302 } else { // no error, display motor number
303 *p
++ = '0' + (i
+ 1) % 10; // 123..9012..
307 *p
++ = 0; // terminate string
309 const int msgLen
= strlen(warningText
);
310 const int minMsgLen
= OSD_WARNINGS_PREFFERED_SIZE
; // intended minimum width
311 if (msgLen
< minMsgLen
- 1) {
312 // message is short, center it within minMsgLen
313 const int offset
= (minMsgLen
- msgLen
) / 2;
314 memmove(warningText
+ offset
, warningText
, msgLen
+ 1); // copy including '\0'
315 memset(warningText
, ' ', offset
); // left padding with spaces
317 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
321 // no warning, erase generated message and continue
322 warningText
[0] = '\0';
325 #endif // USE_ESC_SENSOR
327 #if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
329 if (motorConfig()->dev
.useDshotTelemetry
&& osdWarnGetState(OSD_WARNING_ESC_FAIL
) && ARMING_FLAG(ARMED
)) {
330 uint32_t dshotEscErrorLengthMotorBegin
;
331 uint32_t dshotEscErrorLength
= 0;
334 warningText
[dshotEscErrorLength
++] = 'E';
335 warningText
[dshotEscErrorLength
++] = 'S';
336 warningText
[dshotEscErrorLength
++] = 'C';
338 for (uint8_t k
= 0; k
< getMotorCount(); k
++) {
339 // Skip if no extended telemetry at all
340 if ((dshotTelemetryState
.motorState
[k
].telemetryTypes
& DSHOT_EXTENDED_TELEMETRY_MASK
) == 0) {
344 // Remember text index before writing warnings
345 dshotEscErrorLengthMotorBegin
= dshotEscErrorLength
;
348 warningText
[dshotEscErrorLength
++] = ' ';
349 warningText
[dshotEscErrorLength
++] = '0' + k
+ 1;
352 if (osdConfig()->esc_rpm_alarm
!= ESC_RPM_ALARM_OFF
353 && isDshotMotorTelemetryActive(k
)
354 && (dshotTelemetryState
.motorState
[k
].telemetryData
[DSHOT_TELEMETRY_TYPE_eRPM
] * 100 * 2 / motorConfig()->motorPoleCount
) <= osdConfig()->esc_rpm_alarm
) {
355 warningText
[dshotEscErrorLength
++] = 'R';
357 if (osdConfig()->esc_temp_alarm
!= ESC_TEMP_ALARM_OFF
358 && (dshotTelemetryState
.motorState
[k
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_TEMPERATURE
)) != 0
359 && dshotTelemetryState
.motorState
[k
].telemetryData
[DSHOT_TELEMETRY_TYPE_TEMPERATURE
] >= osdConfig()->esc_temp_alarm
) {
360 warningText
[dshotEscErrorLength
++] = 'T';
362 if (osdConfig()->esc_current_alarm
!= ESC_CURRENT_ALARM_OFF
363 && (dshotTelemetryState
.motorState
[k
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_CURRENT
)) != 0
364 && dshotTelemetryState
.motorState
[k
].telemetryData
[DSHOT_TELEMETRY_TYPE_CURRENT
] >= osdConfig()->esc_current_alarm
) {
365 warningText
[dshotEscErrorLength
++] = 'C';
368 // If no esc warning data undo esc nr (esc telemetry data types depends on the esc hw/sw)
369 if (dshotEscErrorLengthMotorBegin
+ 2 == dshotEscErrorLength
)
370 dshotEscErrorLength
= dshotEscErrorLengthMotorBegin
;
373 // If warning exists then notify, otherwise clear warning message
374 if (dshotEscErrorLength
> 3) {
375 warningText
[dshotEscErrorLength
] = 0; // End string
376 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
385 if (osdWarnGetState(OSD_WARNING_BATTERY_WARNING
) && batteryState
== BATTERY_WARNING
) {
386 tfp_sprintf(warningText
, "LOW BATTERY");
387 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
392 #ifdef USE_RC_SMOOTHING_FILTER
393 // Show warning if rc smoothing hasn't initialized the filters
394 if (osdWarnGetState(OSD_WARNING_RC_SMOOTHING
) && ARMING_FLAG(ARMED
) && !rcSmoothingInitializationComplete() && rxConfig()->rc_smoothing_mode
) {
395 tfp_sprintf(warningText
, "RCSMOOTHING");
396 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
400 #endif // USE_RC_SMOOTHING_FILTER
402 // Show warning if mah consumed is over the configured limit
403 if (osdWarnGetState(OSD_WARNING_OVER_CAP
) && ARMING_FLAG(ARMED
) && osdConfig()->cap_alarm
> 0 && getMAhDrawn() >= osdConfig()->cap_alarm
) {
404 tfp_sprintf(warningText
, "OVER CAP");
405 *displayAttr
= DISPLAYPORT_SEVERITY_WARNING
;
410 #ifdef USE_BATTERY_CONTINUE
411 // Show warning if battery is not fresh and battery continue is active
413 tfp_sprintf(warningText
, "BATTERY CONT");
414 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
417 #endif // USE_BATTERY_CONTINUE
419 // Show warning if battery is not fresh
420 if (osdWarnGetState(OSD_WARNING_BATTERY_NOT_FULL
) && !(ARMING_FLAG(ARMED
) || ARMING_FLAG(WAS_EVER_ARMED
)) && (getBatteryState() == BATTERY_OK
)
421 && getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage
) {
422 tfp_sprintf(warningText
, "BATT < FULL");
423 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
428 if (osdWarnGetState(OSD_WARNING_VISUAL_BEEPER
) && osdGetVisualBeeperState()) {
429 tfp_sprintf(warningText
, " * * * *");
430 *displayAttr
= DISPLAYPORT_SEVERITY_INFO
;
431 osdSetVisualBeeperState(false);