static void showBatteryPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE) { tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", getBatteryVoltage() / 10, getBatteryVoltage() % 10, getBatteryCellCount()); padLineBuffer(); i2c_OLED_set_line(bus, rowIndex++); i2c_OLED_send_string(bus, lineBuffer); uint8_t batteryPercentage = calculateBatteryPercentageRemaining(); i2c_OLED_set_line(bus, rowIndex++); drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, batteryPercentage); } if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) { int32_t amperage = getAmperage(); tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, getMAhDrawn()); padLineBuffer(); i2c_OLED_set_line(bus, rowIndex++); i2c_OLED_send_string(bus, lineBuffer); uint8_t capacityPercentage = calculateBatteryPercentageRemaining(); i2c_OLED_set_line(bus, rowIndex++); drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, capacityPercentage); } }
void showSensorsPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; static const char *format = "%c = %5d %5d %5d"; i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(" X Y Z"); if (sensors(SENSOR_ACC)) { tfp_sprintf(lineBuffer, format, 'A', accSmooth[X], accSmooth[Y], accSmooth[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } if (sensors(SENSOR_GYRO)) { tfp_sprintf(lineBuffer, format, 'G', gyroADC[X], gyroADC[Y], gyroADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #ifdef MAG if (sensors(SENSOR_MAG)) { tfp_sprintf(lineBuffer, format, 'M', magADC[X], magADC[Y], magADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #endif }
void showSensorsPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(" X Y Z"); if (sensors(SENSOR_ACC)) { tfp_sprintf(lineBuffer, "A = %5d %5d %5d", accSmooth[X], accSmooth[Y], accSmooth[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } if (sensors(SENSOR_GYRO)) { tfp_sprintf(lineBuffer, "G = %5d %5d %5d", gyroADC[X], gyroADC[Y], gyroADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #ifdef MAG if (sensors(SENSOR_MAG)) { tfp_sprintf(lineBuffer, "M = %5d %5d %5d", magADC[X], magADC[Y], magADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #endif }
void showProfilePage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfile()); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d", controlRateConfig->rcExpo8, controlRateConfig->rcRate8 ); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "RR:%d PR:%d YR:%d", controlRateConfig->rates[FD_ROLL], controlRateConfig->rates[FD_PITCH], controlRateConfig->rates[FD_YAW] ); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); }
void showBatteryPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; if (feature(FEATURE_VBAT)) { tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", vbat / 10, vbat % 10, batteryCellCount); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); uint8_t batteryPercentage = calculateBatteryPercentage(); i2c_OLED_set_line(rowIndex++); drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, batteryPercentage); } if (feature(FEATURE_CURRENT_METER)) { tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, mAhDrawn); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); uint8_t capacityPercentage = calculateBatteryCapacityRemainingPercentage(); i2c_OLED_set_line(rowIndex++); drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, capacityPercentage); } }
void showWelcomePage(void) { tfp_sprintf(lineBuffer, "Rev: %s", shortGitRevision); i2c_OLED_set_line(PAGE_TITLE_LINE_COUNT + 0); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "Target: %s", targetName); i2c_OLED_set_line(PAGE_TITLE_LINE_COUNT + 1); i2c_OLED_send_string(lineBuffer); }
void showWelcomePage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; tfp_sprintf(lineBuffer, "v%s (%s)", FC_VERSION_STRING, shortGitRevision); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "Target: %s", targetName); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); }
static bool saCmsDrawStatusString(char *buf, unsigned bufsize) { const char *defaultString = "- -- ---- ---"; // m bc ffff ppp // 0123456789012 if (bufsize < strlen(defaultString) + 1) { return false; } strcpy(buf, defaultString); if (!saCmsUpdateCopiedState()) { // VTX is not ready return true; } buf[0] = "-FR"[saCmsOpmodel]; if (saCmsFselMode == 0) { buf[2] = "ABEFR"[saDevice.channel / 8]; buf[3] = '1' + (saDevice.channel % 8); } else { buf[2] = 'U'; buf[3] = 'F'; } if ((saDevice.mode & SA_MODE_GET_PITMODE) && (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)) tfp_sprintf(&buf[5], "%4d", saDevice.orfreq); else if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) tfp_sprintf(&buf[5], "%4d", saDevice.freq); else tfp_sprintf(&buf[5], "%4d", vtx58frequencyTable[saDevice.channel / 8][saDevice.channel % 8]); buf[9] = ' '; if (saDevice.mode & SA_MODE_GET_PITMODE) { buf[10] = 'P'; if (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) { buf[11] = 'I'; } else { buf[11] = 'O'; } buf[12] = 'R'; buf[13] = 0; } else { tfp_sprintf(&buf[10], "%3d", (saDevice.version == 2) ? saPowerTable[saDevice.power].rfpower : saPowerTable[saDacToPowerIndex(saDevice.power)].rfpower); } return true; }
/* * Called periodically by the scheduler */ void osdSlaveUpdate(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); #ifdef MAX7456_DMA_CHANNEL_TX // don't touch buffers if DMA transaction is in progress if (displayIsTransferInProgress(osdDisplayPort)) { return; } #endif // MAX7456_DMA_CHANNEL_TX #ifdef OSD_SLAVE_DEBUG char buff[32]; for (int i = 0; i < 4; i ++) { tfp_sprintf(buff, "%5d", debug[i]); displayWrite(osdDisplayPort, i * 8, 0, buff); } #endif if (displayDrawScreenQueued) { displayDrawScreen(osdDisplayPort); displayDrawScreenQueued = false; receivingScreen = false; } }
void osdElementRender_voltage(const element_t *element, elementDataProviderFn dataFn) { voltageAndName_t *voltageAndName= (voltageAndName_t *) dataFn(); tfp_sprintf(elementAsciiBuffer, "%s:%2d.%dV", voltageAndName->name, voltageAndName->voltage / 10, voltageAndName->voltage % 10); osdPrintAt(element->x, element->y, elementAsciiBuffer); }
void generateLedConfig(ledConfig_t *ledConfig, char *ledConfigBuffer, size_t bufferSize) { char directions[LED_DIRECTION_COUNT + 1]; char baseFunctionOverlays[LED_OVERLAY_COUNT + 2]; memset(ledConfigBuffer, 0, bufferSize); char *dptr = directions; for (ledDirectionId_e dir = 0; dir < LED_DIRECTION_COUNT; dir++) { if (ledGetDirectionBit(ledConfig, dir)) { *dptr++ = directionCodes[dir]; } } *dptr = 0; char *fptr = baseFunctionOverlays; *fptr++ = baseFunctionCodes[ledGetFunction(ledConfig)]; for (ledOverlayId_e ol = 0; ol < LED_OVERLAY_COUNT; ol++) { if (ledGetOverlayBit(ledConfig, ol)) { *fptr++ = overlayCodes[ol]; } } *fptr = 0; // TODO - check buffer length tfp_sprintf(ledConfigBuffer, "%u,%u:%s:%s:%u", ledGetX(ledConfig), ledGetY(ledConfig), directions, baseFunctionOverlays, ledGetColor(ledConfig)); }
static void osdFormatAltitudeString(char * buff, int altitude) { const int alt = osdGetMetersToSelectedUnit(altitude) / 10; tfp_sprintf(buff, "%5d %c", alt, osdGetMetersToSelectedUnitSymbol()); buff[5] = buff[4]; buff[4] = '.'; }
static char *saCmsUserFreqGetString(void) { static char pbuf[5]; tfp_sprintf(pbuf, "%4d", saCmsUserFreq); return pbuf; }
void osdElementRender_voltageBattery(const element_t *element, elementDataProviderFn dataFn) { voltageAndName_t *voltageAndName= (voltageAndName_t *) dataFn(); tfp_sprintf(elementAsciiBuffer, "%2d.%dV", voltageAndName->voltage / 10, voltageAndName->voltage % 10); osdPrintAt(element->x +1, element->y, elementAsciiBuffer); osdSetRawCharacterAtPosition(element->x, element->y, voltageAndName->symbol); }
void showSensorsPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; static const char *format = "%s %5d %5d %5d"; i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(" X Y Z"); if (sensors(SENSOR_ACC)) { tfp_sprintf(lineBuffer, format, "ACC", accSmooth[X], accSmooth[Y], accSmooth[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } if (sensors(SENSOR_GYRO)) { tfp_sprintf(lineBuffer, format, "GYR", gyroADC[X], gyroADC[Y], gyroADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #ifdef MAG if (sensors(SENSOR_MAG)) { tfp_sprintf(lineBuffer, format, "MAG", magADC[X], magADC[Y], magADC[Z]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #endif tfp_sprintf(lineBuffer, format, "I&H", attitude.values.roll, attitude.values.pitch, DECIDEGREES_TO_DEGREES(attitude.values.yaw)); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); #ifdef SONAR if (sensors(SENSOR_SONAR)) { static const char *sonarFormat = "%s %5d"; tfp_sprintf(lineBuffer, sonarFormat, "SNR", sonarGetLatestAltitude()); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #endif }
void osdElementRender_amperage(const element_t *element, elementDataProviderFn dataFn) { int32_t amperage = (int32_t) dataFn(); tfp_sprintf(elementAsciiBuffer, "%2d.%02d", amperage / 100, amperage % 100); osdPrintAt(element->x, element->y, elementAsciiBuffer); osdSetRawCharacterAtPosition(element->x + 5, element->y, FONT_CHARACTER_AMP); }
void osdElementRender_mahDrawn(const element_t *element, elementDataProviderFn dataFn) { int32_t mAhDrawn = (int32_t) dataFn(); tfp_sprintf(elementAsciiBuffer, "%5d", mAhDrawn); osdPrintAt(element->x, element->y, elementAsciiBuffer); osdSetRawCharacterAtPosition(element->x + 5, element->y, FONT_CHARACTER_MAH); }
void osdElementRender_rssi(const element_t *element, elementDataProviderFn dataFn) { uint16_t rssi = (uint16_t) dataFn(); tfp_sprintf(elementAsciiBuffer, "%3d", (rssi / 1023) * 100); osdPrintAt(element->x, element->y, elementAsciiBuffer); osdSetRawCharacterAtPosition(element->x + 3, element->y, FONT_CHARACTER_RSSI); }
void showProfilePage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfile()); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); static const char* const axisTitles[3] = {"ROL", "PIT", "YAW"}; const pidProfile_t *pidProfile = ¤tProfile->pidProfile; for (int axis = 0; axis < 3; ++axis) { tfp_sprintf(lineBuffer, "%s P:%3d I:%3d D:%3d", axisTitles[axis], pidProfile->P8[axis], pidProfile->I8[axis], pidProfile->D8[axis] ); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } const uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); const controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d", controlRateConfig->rcExpo8, controlRateConfig->rcRate8 ); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "RR:%d PR:%d YR:%d", controlRateConfig->rates[FD_ROLL], controlRateConfig->rates[FD_PITCH], controlRateConfig->rates[FD_YAW] ); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); }
static void showDebugPage(void) { for (int rowIndex = 0; rowIndex < 4; rowIndex++) { tfp_sprintf(lineBuffer, "%d = %5d", rowIndex, debug[rowIndex]); padLineBuffer(); i2c_OLED_set_line(bus, rowIndex + PAGE_TITLE_LINE_COUNT); i2c_OLED_send_string(bus, lineBuffer); } }
STATIC_UNIT_TESTED void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time) { int seconds = time / 1000000; const int minutes = seconds / 60; seconds = seconds % 60; switch (precision) { case OSD_TIMER_PREC_SECOND: default: tfp_sprintf(buff, "%02d:%02d", minutes, seconds); break; case OSD_TIMER_PREC_HUNDREDTHS: { const int hundredths = (time / 10000) % 100; tfp_sprintf(buff, "%02d:%02d.%02d", minutes, seconds, hundredths); break; } } }
void showGpsPage() { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; i2c_OLED_set_xy(MAX(0, SATELLITE_GRAPH_LEFT_OFFSET), rowIndex++); uint32_t index; for (index = 0; index < SATELLITE_COUNT && index < SCREEN_CHARACTER_COLUMN_COUNT; index++) { uint8_t bargraphValue = ((uint16_t) GPS_svinfo_cno[index] * VERTICAL_BARGRAPH_CHARACTER_COUNT) / (GPS_DBHZ_MAX - 1); bargraphValue = MIN(bargraphValue, VERTICAL_BARGRAPH_CHARACTER_COUNT - 1); i2c_OLED_send_char(VERTICAL_BARGRAPH_ZERO_CHARACTER + bargraphValue); } char fixChar = STATE(GPS_FIX) ? 'Y' : 'N'; tfp_sprintf(lineBuffer, "Satellites: %d Fix: %c", GPS_numSat, fixChar); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "Lat: %d Lon: %d", GPS_coord[LAT] / GPS_DEGREES_DIVIDER, GPS_coord[LON] / GPS_DEGREES_DIVIDER); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "Spd: %d cm/s GC: %d", GPS_speed, GPS_ground_course); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "RX: %d Delta: %d", GPS_packetCount, gpsData.lastMessage - gpsData.lastLastMessage); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "ERRs: %d TOs: %d", gpsData.errors, gpsData.timeouts); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); strncpy(lineBuffer, gpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); #ifdef GPS_PH_DEBUG tfp_sprintf(lineBuffer, "Angles: P:%d R:%d", GPS_angle[PITCH], GPS_angle[ROLL]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); #endif #if 0 tfp_sprintf(lineBuffer, "%d %d %d %d", debug[0], debug[1], debug[2], debug[3]); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); #endif }
void formatTrimDegrees ( char *formattedTrim, int16_t trimValue ) { char trim[6]; tfp_sprintf(trim, "%d", trimValue); int x = strlen(trim)-1; strncpy(formattedTrim,trim,x); formattedTrim[x] = '\0'; if (trimValue !=0) { strcat(formattedTrim,"."); } strcat(formattedTrim,trim+x); }
static void ipconfig_get(uint8_t *cmd, uint8_t len) { uint8_t ip_config[30]; osel_memset(cmd, 0x00, len); osel_memset(ip_config, 0x00, 30); tfp_sprintf((char *)ip_config, "\"%d.%d.%d.%d\",%u", gprs_info.dip[0], gprs_info.dip[1], gprs_info.dip[2], gprs_info.dip[3], gprs_info.port); if (gprs_info.mode) { tfp_sprintf((char *)cmd, (char *)CIPSTART, (char *)tcp_mode, (char *)ip_config); } else if(gprs_info.mode) { tfp_sprintf((char *)cmd, (char *)CIPSTART, (char *)udp_mode, (char *)ip_config); } }
static void osdGetBlackboxStatusString(char * buff) { bool storageDeviceIsWorking = false; uint32_t storageUsed = 0; uint32_t storageTotal = 0; switch (blackboxConfig()->device) { #ifdef USE_SDCARD case BLACKBOX_DEVICE_SDCARD: storageDeviceIsWorking = sdcard_isInserted() && sdcard_isFunctional() && (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_READY); if (storageDeviceIsWorking) { storageTotal = sdcard_getMetadata()->numBlocks / 2000; storageUsed = storageTotal - (afatfs_getContiguousFreeSpace() / 1024000); } break; #endif #ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: storageDeviceIsWorking = flashfsIsReady(); if (storageDeviceIsWorking) { const flashGeometry_t *geometry = flashfsGetGeometry(); storageTotal = geometry->totalSize / 1024; storageUsed = flashfsGetOffset() / 1024; } break; #endif default: break; } if (storageDeviceIsWorking) { const uint16_t storageUsedPercent = (storageUsed * 100) / storageTotal; tfp_sprintf(buff, "%d%%", storageUsedPercent); } else { tfp_sprintf(buff, "FAULT"); } }
static void osdFormatCoordinate(char *buff, char sym, int32_t val) { // latitude maximum integer width is 3 (-90). // longitude maximum integer width is 4 (-180). // We show 7 decimals, so we need to use 12 characters: // eg: s-180.1234567z s=symbol, z=zero terminator, decimal separator between 0 and 1 static const int coordinateMaxLength = 13;//12 for the number (4 + dot + 7) + 1 for the symbol buff[0] = sym; const int32_t integerPart = val / GPS_DEGREES_DIVIDER; const int32_t decimalPart = labs(val % GPS_DEGREES_DIVIDER); const int written = tfp_sprintf(buff + 1, "%d.%07d", integerPart, decimalPart); // pad with blanks to coordinateMaxLength for (int pos = 1 + written; pos < coordinateMaxLength; ++pos) { buff[pos] = SYM_BLANK; } buff[coordinateMaxLength] = '\0'; }
void osdInit(displayPort_t *osdDisplayPortToUse) { if (!osdDisplayPortToUse) { return; } BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31)); osdDisplayPort = osdDisplayPortToUse; #ifdef USE_CMS cmsDisplayPortRegister(osdDisplayPort); #endif armState = ARMING_FLAG(ARMED); memset(blinkBits, 0, sizeof(blinkBits)); displayClearScreen(osdDisplayPort); osdDrawLogo(3, 1); char string_buffer[30]; tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING); displayWrite(osdDisplayPort, 20, 6, string_buffer); #ifdef USE_CMS displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1); displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2); displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3); #endif #ifdef USE_RTC_TIME char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE]; if (osdFormatRtcDateTime(&dateTimeBuffer[0])) { displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer); } #endif displayResync(osdDisplayPort); resumeRefreshAt = micros() + (4 * REFRESH_1S); }
void osdSlaveInit(displayPort_t *osdDisplayPortToUse) { if (!osdDisplayPortToUse) return; osdDisplayPort = osdDisplayPortToUse; delay(100); // need max7456 to be ready before using the displayPort API further. displayClearScreen(osdDisplayPort); displayResync(osdDisplayPort); delay(100); // wait a little for video to stabilise osdDrawLogo(3, 1); char string_buffer[30]; tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING); displayWrite(osdDisplayPort, 20, 6, string_buffer); displayWrite(osdDisplayPort, 13, 6, "OSD"); displayResync(osdDisplayPort); }
static bool_t gprs_write_fifo(const uint8_t *const payload, const uint16_t len) { DBG_ASSERT(payload != NULL __DBG_LINE); if (gprs_info.gprs_state == WORK_ON && len < SEND_SIZE) { if(gprs_info.data_mode) { wdt_clear(SOFT_WDT); led_set(LED_RED, TRUE); osel_memset(send.buf, 0x00, SEND_SIZE); osel_memcpy(send.buf, payload, len); send.len = len; write_fifo(send.buf, send.len); led_set(LED_RED, FALSE); return TRUE; } else { if(xSemaphoreTake(gprs_mutex, 600) == pdTRUE) { led_set(LED_RED, TRUE); //等待数据发送完成 xTimerReset(gprs_daemon_timer, 400); osel_memset(send_data, 0x00, SIZE); tfp_sprintf((char *)send_data, CIPSEND, len); osel_memset(send.buf, 0x00, SEND_SIZE); osel_memcpy(send.buf, payload, len); send.len = len; write_fifo(send_data, mystrlen((char *)send_data)); return TRUE; } } } return FALSE; }
void showTasksPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; static const char *format = "%2d%6d%5d%4d%4d"; i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string("Task max avg mx% av%"); cfTaskInfo_t taskInfo; for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; ++taskId) { getTaskInfo(taskId, &taskInfo); if (taskInfo.isEnabled && taskId != TASK_SERIAL) {// don't waste a line of the display showing serial taskInfo const int taskFrequency = (int)(1000000.0f / ((float)taskInfo.latestDeltaTime)); const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 10000; const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 10000; tfp_sprintf(lineBuffer, format, taskId, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, maxLoad, averageLoad); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); if (rowIndex > SCREEN_CHARACTER_ROW_COUNT) { break; } } } }