bool srxlFrameRpm(sbuf_t *dst, timeUs_t currentTimeUs) { uint16_t period_us = SPEKTRUM_RPM_UNUSED; #ifdef USE_ESC_SENSOR_TELEMETRY escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED); if (escData != NULL) { period_us = 60000000 / escData->rpm; // revs/minute -> microSeconds } #endif int16_t coreTemp = SPEKTRUM_TEMP_UNUSED; #if defined(USE_ADC_INTERNAL) coreTemp = getCoreTemperatureCelsius(); coreTemp = coreTemp * 9 / 5 + 32; // C -> F #endif UNUSED(currentTimeUs); sbufWriteU8(dst, SRXL_FRAMETYPE_TELE_RPM); sbufWriteU8(dst, SRXL_FRAMETYPE_SID); sbufWriteU16BigEndian(dst, period_us); // pulse leading edges if (telemetryConfig()->report_cell_voltage) { sbufWriteU16BigEndian(dst, getBatteryAverageCellVoltage()); // Cell voltage is in units of 0.01V } else { sbufWriteU16BigEndian(dst, getBatteryVoltage()); // vbat is in units of 0.01V } sbufWriteU16BigEndian(dst, coreTemp); // temperature sbufFill(dst, STRU_TELE_RPM_EMPTY_FIELDS_VALUE, STRU_TELE_RPM_EMPTY_FIELDS_COUNT); // Mandatory frame, send it unconditionally. return true; }
void voltageMeterESCRefresh(void) { #ifdef USE_ESC_SENSOR escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED); if (escData) { voltageMeterESCState.voltageUnfiltered = escData->dataAge <= ESC_BATTERY_AGE_MAX ? escData->voltage / 10 : 0; voltageMeterESCState.voltageFiltered = biquadFilterApply(&voltageMeterESCState.filter, voltageMeterESCState.voltageUnfiltered); } #endif }
void voltageMeterESCReadMotor(uint8_t motorNumber, voltageMeter_t *voltageMeter) { #ifndef USE_ESC_SENSOR UNUSED(motorNumber); voltageMeterReset(voltageMeter); #else escSensorData_t *escData = getEscSensorData(motorNumber); if (escData) { voltageMeter->unfiltered = escData->dataAge <= ESC_BATTERY_AGE_MAX ? escData->voltage / 10 : 0; voltageMeter->filtered = voltageMeter->unfiltered; // no filtering for ESC motors currently. } else { voltageMeterReset(voltageMeter); } #endif }
static bool osdDrawSingleElement(uint8_t item) { if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) { return false; } uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]); uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]); char buff[OSD_ELEMENT_BUFFER_LENGTH] = ""; switch (item) { case OSD_RSSI_VALUE: { uint16_t osdRssi = getRssi() * 100 / 1024; // change range if (osdRssi >= 100) osdRssi = 99; tfp_sprintf(buff, "%c%2d", SYM_RSSI, osdRssi); break; } case OSD_MAIN_BATT_VOLTAGE: buff[0] = osdGetBatterySymbol(osdGetBatteryAverageCellVoltage()); tfp_sprintf(buff + 1, "%2d.%1d%c", getBatteryVoltage() / 10, getBatteryVoltage() % 10, SYM_VOLT); break; case OSD_CURRENT_DRAW: { const int32_t amperage = getAmperage(); tfp_sprintf(buff, "%3d.%02d%c", abs(amperage) / 100, abs(amperage) % 100, SYM_AMP); break; } case OSD_MAH_DRAWN: tfp_sprintf(buff, "%4d%c", getMAhDrawn(), SYM_MAH); break; #ifdef USE_GPS case OSD_GPS_SATS: tfp_sprintf(buff, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat); break; case OSD_GPS_SPEED: // FIXME ideally we want to use SYM_KMH symbol but it's not in the font any more, so we use K (M for MPH) switch (osdConfig()->units) { case OSD_UNIT_IMPERIAL: tfp_sprintf(buff, "%3dM", CM_S_TO_MPH(gpsSol.groundSpeed)); break; default: tfp_sprintf(buff, "%3dK", CM_S_TO_KM_H(gpsSol.groundSpeed)); break; } break; case OSD_GPS_LAT: // The SYM_LAT symbol in the actual font contains only blank, so we use the SYM_ARROW_NORTH osdFormatCoordinate(buff, SYM_ARROW_NORTH, gpsSol.llh.lat); break; case OSD_GPS_LON: // The SYM_LON symbol in the actual font contains only blank, so we use the SYM_ARROW_EAST osdFormatCoordinate(buff, SYM_ARROW_EAST, gpsSol.llh.lon); break; case OSD_HOME_DIR: if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { if (GPS_distanceToHome > 0) { const int h = GPS_directionToHome - DECIDEGREES_TO_DEGREES(attitude.values.yaw); buff[0] = osdGetDirectionSymbolFromHeading(h); } else { // We don't have a HOME symbol in the font, by now we use this buff[0] = SYM_THR1; } } else { // We use this symbol when we don't have a FIX buff[0] = SYM_COLON; } buff[1] = 0; break; case OSD_HOME_DIST: if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { const int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome); tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol()); } else { // We use this symbol when we don't have a FIX buff[0] = SYM_COLON; // overwrite any previous distance with blanks memset(buff + 1, SYM_BLANK, 6); buff[7] = '\0'; } break; #endif // GPS case OSD_COMPASS_BAR: memcpy(buff, compassBar + osdGetHeadingIntoDiscreteDirections(DECIDEGREES_TO_DEGREES(attitude.values.yaw), 16), 9); buff[9] = 0; break; case OSD_ALTITUDE: osdFormatAltitudeString(buff, getEstimatedAltitude()); break; case OSD_ITEM_TIMER_1: case OSD_ITEM_TIMER_2: osdFormatTimer(buff, true, true, item - OSD_ITEM_TIMER_1); break; case OSD_REMAINING_TIME_ESTIMATE: { const int mAhDrawn = getMAhDrawn(); const int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn); if (mAhDrawn < 0.1 * osdConfig()->cap_alarm) { tfp_sprintf(buff, "--:--"); } else if (mAhDrawn > osdConfig()->cap_alarm) { tfp_sprintf(buff, "00:00"); } else { osdFormatTime(buff, OSD_TIMER_PREC_SECOND, remaining_time); } break; } case OSD_FLYMODE: { if (FLIGHT_MODE(FAILSAFE_MODE)) { strcpy(buff, "!FS!"); } else if (FLIGHT_MODE(ANGLE_MODE)) { strcpy(buff, "STAB"); } else if (FLIGHT_MODE(HORIZON_MODE)) { strcpy(buff, "HOR "); } else if (FLIGHT_MODE(GPS_RESCUE_MODE)) { strcpy(buff, "RESC"); } else if (isAirmodeActive()) { strcpy(buff, "AIR "); } else { strcpy(buff, "ACRO"); } break; } case OSD_ANTI_GRAVITY: { if (pidItermAccelerator() > 1.0f) { strcpy(buff, "AG"); } break; } case OSD_CRAFT_NAME: // This does not strictly support iterative updating if the craft name changes at run time. But since the craft name is not supposed to be changing this should not matter, and blanking the entire length of the craft name string on update will make it impossible to configure elements to be displayed on the right hand side of the craft name. //TODO: When iterative updating is implemented, change this so the craft name is only printed once whenever the OSD 'flight' screen is entered. if (strlen(pilotConfig()->name) == 0) { strcpy(buff, "CRAFT_NAME"); } else { unsigned i; for (i = 0; i < MAX_NAME_LENGTH; i++) { if (pilotConfig()->name[i]) { buff[i] = toupper((unsigned char)pilotConfig()->name[i]); } else { break; } } buff[i] = '\0'; } break; case OSD_THROTTLE_POS: buff[0] = SYM_THR; buff[1] = SYM_THR1; tfp_sprintf(buff + 2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); break; #if defined(USE_VTX_COMMON) case OSD_VTX_CHANNEL: { const char vtxBandLetter = vtx58BandLetter[vtxSettingsConfig()->band]; const char *vtxChannelName = vtx58ChannelNames[vtxSettingsConfig()->channel]; uint8_t vtxPower = vtxSettingsConfig()->power; const vtxDevice_t *vtxDevice = vtxCommonDevice(); if (vtxDevice && vtxSettingsConfig()->lowPowerDisarm) { vtxCommonGetPowerIndex(vtxDevice, &vtxPower); } tfp_sprintf(buff, "%c:%s:%1d", vtxBandLetter, vtxChannelName, vtxPower); break; } #endif case OSD_CROSSHAIRS: buff[0] = SYM_AH_CENTER_LINE; buff[1] = SYM_AH_CENTER; buff[2] = SYM_AH_CENTER_LINE_RIGHT; buff[3] = 0; break; case OSD_ARTIFICIAL_HORIZON: { // Get pitch and roll limits in tenths of degrees const int maxPitch = osdConfig()->ahMaxPitch * 10; const int maxRoll = osdConfig()->ahMaxRoll * 10; const int rollAngle = constrain(attitude.values.roll, -maxRoll, maxRoll); int pitchAngle = constrain(attitude.values.pitch, -maxPitch, maxPitch); // Convert pitchAngle to y compensation value // (maxPitch / 25) divisor matches previous settings of fixed divisor of 8 and fixed max AHI pitch angle of 20.0 degrees pitchAngle = ((pitchAngle * 25) / maxPitch) - 41; // 41 = 4 * AH_SYMBOL_COUNT + 5 for (int x = -4; x <= 4; x++) { const int y = ((-rollAngle * x) / 64) - pitchAngle; if (y >= 0 && y <= 81) { displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + (y / AH_SYMBOL_COUNT), (SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT))); } } return true; } case OSD_HORIZON_SIDEBARS: { // Draw AH sides const int8_t hudwidth = AH_SIDEBAR_WIDTH_POS; const int8_t hudheight = AH_SIDEBAR_HEIGHT_POS; for (int y = -hudheight; y <= hudheight; y++) { displayWriteChar(osdDisplayPort, elemPosX - hudwidth, elemPosY + y, SYM_AH_DECORATION); displayWriteChar(osdDisplayPort, elemPosX + hudwidth, elemPosY + y, SYM_AH_DECORATION); } // AH level indicators displayWriteChar(osdDisplayPort, elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT); displayWriteChar(osdDisplayPort, elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT); return true; } case OSD_ROLL_PIDS: osdFormatPID(buff, "ROL", ¤tPidProfile->pid[PID_ROLL]); break; case OSD_PITCH_PIDS: osdFormatPID(buff, "PIT", ¤tPidProfile->pid[PID_PITCH]); break; case OSD_YAW_PIDS: osdFormatPID(buff, "YAW", ¤tPidProfile->pid[PID_YAW]); break; case OSD_POWER: tfp_sprintf(buff, "%4dW", getAmperage() * getBatteryVoltage() / 1000); break; case OSD_PIDRATE_PROFILE: tfp_sprintf(buff, "%d-%d", getCurrentPidProfileIndex() + 1, getCurrentControlRateProfileIndex() + 1); break; case OSD_WARNINGS: { #define OSD_WARNINGS_MAX_SIZE 11 #define OSD_FORMAT_MESSAGE_BUFFER_SIZE (OSD_WARNINGS_MAX_SIZE + 1) STATIC_ASSERT(OSD_FORMAT_MESSAGE_BUFFER_SIZE <= sizeof(buff), osd_warnings_size_exceeds_buffer_size); const batteryState_e batteryState = getBatteryState(); if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " LAND NOW"); break; } #ifdef USE_ADC_INTERNAL uint8_t coreTemperature = getCoreTemperatureCelsius(); if (osdWarnGetState(OSD_WARNING_CORE_TEMPERATURE) && coreTemperature >= osdConfig()->core_temp_alarm) { char coreTemperatureWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE]; tfp_sprintf(coreTemperatureWarningMsg, "CORE: %3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit()); osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, coreTemperatureWarningMsg); break; } #endif #ifdef USE_ESC_SENSOR // Show warning if we lose motor output, the ESC is overheating or excessive current draw if (feature(FEATURE_ESC_SENSOR) && osdWarnGetState(OSD_WARNING_ESC_FAIL)) { char escWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE]; unsigned pos = 0; const char *title = "ESC"; // center justify message while (pos < (OSD_WARNINGS_MAX_SIZE - (strlen(title) + getMotorCount())) / 2) { escWarningMsg[pos++] = ' '; } strcpy(escWarningMsg + pos, title); pos += strlen(title); unsigned i = 0; unsigned escWarningCount = 0; while (i < getMotorCount() && pos < OSD_FORMAT_MESSAGE_BUFFER_SIZE - 1) { escSensorData_t *escData = getEscSensorData(i); const char motorNumber = '1' + i; // if everything is OK just display motor number else R, T or C char warnFlag = motorNumber; if (ARMING_FLAG(ARMED) && osdConfig()->esc_rpm_alarm != ESC_RPM_ALARM_OFF && calcEscRpm(escData->rpm) <= osdConfig()->esc_rpm_alarm) { warnFlag = 'R'; } if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escData->temperature >= osdConfig()->esc_temp_alarm) { warnFlag = 'T'; } if (ARMING_FLAG(ARMED) && osdConfig()->esc_current_alarm != ESC_CURRENT_ALARM_OFF && escData->current >= osdConfig()->esc_current_alarm) { warnFlag = 'C'; } escWarningMsg[pos++] = warnFlag; if (warnFlag != motorNumber) { escWarningCount++; } i++; } escWarningMsg[pos] = '\0'; if (escWarningCount > 0) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, escWarningMsg); } break; } #endif // Warn when in flip over after crash mode if (osdWarnGetState(OSD_WARNING_CRASH_FLIP) && isFlipOverAfterCrashMode()) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "CRASH FLIP"); break; } // Show most severe reason for arming being disabled if (osdWarnGetState(OSD_WARNING_ARMING_DISABLE) && IS_RC_MODE_ACTIVE(BOXARM) && isArmingDisabled()) { const armingDisableFlags_e flags = getArmingDisableFlags(); for (int i = 0; i < ARMING_DISABLE_FLAGS_COUNT; i++) { if (flags & (1 << i)) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, armingDisableFlagNames[i]); break; } } break; } if (osdWarnGetState(OSD_WARNING_BATTERY_WARNING) && batteryState == BATTERY_WARNING) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "LOW BATTERY"); break; } // Show warning if battery is not fresh if (osdWarnGetState(OSD_WARNING_BATTERY_NOT_FULL) && !ARMING_FLAG(WAS_EVER_ARMED) && (getBatteryState() == BATTERY_OK) && getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "BATT < FULL"); break; } // Visual beeper if (osdWarnGetState(OSD_WARNING_VISUAL_BEEPER) && showVisualBeeper) { osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " * * * *"); break; } osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, NULL); break; } case OSD_AVG_CELL_VOLTAGE: { const int cellV = osdGetBatteryAverageCellVoltage(); buff[0] = osdGetBatterySymbol(cellV); tfp_sprintf(buff + 1, "%d.%02d%c", cellV / 100, cellV % 100, SYM_VOLT); break; } case OSD_DEBUG: tfp_sprintf(buff, "DBG %5d %5d %5d %5d", debug[0], debug[1], debug[2], debug[3]); break; case OSD_PITCH_ANGLE: case OSD_ROLL_ANGLE: { const int angle = (item == OSD_PITCH_ANGLE) ? attitude.values.pitch : attitude.values.roll; tfp_sprintf(buff, "%c%02d.%01d", angle < 0 ? '-' : ' ', abs(angle / 10), abs(angle % 10)); break; } case OSD_MAIN_BATT_USAGE: { // Set length of indicator bar #define MAIN_BATT_USAGE_STEPS 11 // Use an odd number so the bar can be centered. // Calculate constrained value const float value = constrain(batteryConfig()->batteryCapacity - getMAhDrawn(), 0, batteryConfig()->batteryCapacity); // Calculate mAh used progress const uint8_t mAhUsedProgress = ceilf((value / (batteryConfig()->batteryCapacity / MAIN_BATT_USAGE_STEPS))); // Create empty battery indicator bar buff[0] = SYM_PB_START; for (int i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) { buff[i] = i <= mAhUsedProgress ? SYM_PB_FULL : SYM_PB_EMPTY; } buff[MAIN_BATT_USAGE_STEPS + 1] = SYM_PB_CLOSE; if (mAhUsedProgress > 0 && mAhUsedProgress < MAIN_BATT_USAGE_STEPS) { buff[1 + mAhUsedProgress] = SYM_PB_END; } buff[MAIN_BATT_USAGE_STEPS+2] = '\0'; break; } case OSD_DISARMED: if (!ARMING_FLAG(ARMED)) { tfp_sprintf(buff, "DISARMED"); } else { if (!lastArmState) { // previously disarmed - blank out the message one time tfp_sprintf(buff, " "); } } break; case OSD_NUMERICAL_HEADING: { const int heading = DECIDEGREES_TO_DEGREES(attitude.values.yaw); tfp_sprintf(buff, "%c%03d", osdGetDirectionSymbolFromHeading(heading), heading); break; } case OSD_NUMERICAL_VARIO: { const int verticalSpeed = osdGetMetersToSelectedUnit(getEstimatedVario()); const char directionSymbol = verticalSpeed < 0 ? SYM_ARROW_SOUTH : SYM_ARROW_NORTH; tfp_sprintf(buff, "%c%01d.%01d", directionSymbol, abs(verticalSpeed / 100), abs((verticalSpeed % 100) / 10)); break; } #ifdef USE_ESC_SENSOR case OSD_ESC_TMP: if (feature(FEATURE_ESC_SENSOR)) { tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(escDataCombined->temperature * 10) / 10, osdGetTemperatureSymbolForSelectedUnit()); } break; case OSD_ESC_RPM: if (feature(FEATURE_ESC_SENSOR)) { tfp_sprintf(buff, "%5d", escDataCombined == NULL ? 0 : calcEscRpm(escDataCombined->rpm)); } break; #endif #ifdef USE_RTC_TIME case OSD_RTC_DATETIME: osdFormatRtcDateTime(&buff[0]); break; #endif #ifdef USE_OSD_ADJUSTMENTS case OSD_ADJUSTMENT_RANGE: tfp_sprintf(buff, "%s: %3d", adjustmentRangeName, adjustmentRangeValue); break; #endif #ifdef USE_ADC_INTERNAL case OSD_CORE_TEMPERATURE: tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit()); break; #endif default: return false; } displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); return true; }
STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs) { static timeUs_t lastTimeUs = 0; static bool osdStatsEnabled = false; static bool osdStatsVisible = false; static timeUs_t osdStatsRefreshTimeUs; static uint16_t endBatteryVoltage; // detect arm/disarm if (armState != ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) { osdStatsEnabled = false; osdStatsVisible = false; osdResetStats(); osdShowArmed(); resumeRefreshAt = currentTimeUs + (REFRESH_1S / 2); } else if (isSomeStatEnabled() && (!(getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF) || !VISIBLE(osdConfig()->item_pos[OSD_WARNINGS]))) { // suppress stats if runaway takeoff triggered disarm and WARNINGS element is visible osdStatsEnabled = true; resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S); endBatteryVoltage = getBatteryVoltage(); } armState = ARMING_FLAG(ARMED); } if (ARMING_FLAG(ARMED)) { osdUpdateStats(); timeUs_t deltaT = currentTimeUs - lastTimeUs; flyTime += deltaT; stats.armed_time += deltaT; } else if (osdStatsEnabled) { // handle showing/hiding stats based on OSD disable switch position if (displayIsGrabbed(osdDisplayPort)) { osdStatsEnabled = false; resumeRefreshAt = 0; stats.armed_time = 0; } else { if (IS_RC_MODE_ACTIVE(BOXOSD) && osdStatsVisible) { osdStatsVisible = false; displayClearScreen(osdDisplayPort); } else if (!IS_RC_MODE_ACTIVE(BOXOSD)) { if (!osdStatsVisible) { osdStatsVisible = true; osdStatsRefreshTimeUs = 0; } if (currentTimeUs >= osdStatsRefreshTimeUs) { osdStatsRefreshTimeUs = currentTimeUs + REFRESH_1S; osdShowStats(endBatteryVoltage); } } } } lastTimeUs = currentTimeUs; if (resumeRefreshAt) { if (cmp32(currentTimeUs, resumeRefreshAt) < 0) { // in timeout period, check sticks for activity to resume display. if (IS_HI(THROTTLE) || IS_HI(PITCH)) { resumeRefreshAt = currentTimeUs; } displayHeartbeat(osdDisplayPort); return; } else { displayClearScreen(osdDisplayPort); resumeRefreshAt = 0; osdStatsEnabled = false; stats.armed_time = 0; } } blinkState = (currentTimeUs / 200000) % 2; #ifdef USE_ESC_SENSOR if (feature(FEATURE_ESC_SENSOR)) { escDataCombined = getEscSensorData(ESC_SENSOR_COMBINED); } #endif #ifdef USE_CMS if (!displayIsGrabbed(osdDisplayPort)) { osdUpdateAlarms(); osdDrawElements(); displayHeartbeat(osdDisplayPort); #ifdef OSD_CALLS_CMS } else { cmsUpdate(currentTimeUs); #endif } #endif lastArmState = ARMING_FLAG(ARMED); }