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); } }
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); } }
static void drawRxChannel(uint8_t channelIndex, uint8_t width) { LCDprint(rcChannelLetters[channelIndex]); const uint32_t percentage = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); drawHorizonalPercentageBar(width - 1, percentage); }
static void showStatusPage(void) { uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; if (feature(FEATURE_VBAT)) { i2c_OLED_set_line(rowIndex++); tfp_sprintf(lineBuffer, "V: %d.%1d ", vbat / 10, vbat % 10); padLineBufferToChar(12); i2c_OLED_send_string(lineBuffer); uint8_t batteryPercentage = calculateBatteryPercentage(); drawHorizonalPercentageBar(10, batteryPercentage); } if (feature(FEATURE_CURRENT_METER)) { i2c_OLED_set_line(rowIndex++); tfp_sprintf(lineBuffer, "mAh: %d", mAhDrawn); padLineBufferToChar(12); i2c_OLED_send_string(lineBuffer); uint8_t capacityPercentage = calculateBatteryCapacityRemainingPercentage(); drawHorizonalPercentageBar(10, capacityPercentage); } #ifdef GPS if (feature(FEATURE_GPS)) { tfp_sprintf(lineBuffer, "Sats: %d", gpsSol.numSat); padHalfLineBuffer(); i2c_OLED_set_line(rowIndex); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "Fix: %s", gpsFixTypeText[gpsSol.fixType]); padHalfLineBuffer(); i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "HDOP: %d.%1d", gpsSol.hdop / 100, gpsSol.hdop % 100); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); tfp_sprintf(lineBuffer, "La/Lo: %d/%d", gpsSol.llh.lat / GPS_DEGREES_DIVIDER, gpsSol.llh.lon / GPS_DEGREES_DIVIDER); padLineBuffer(); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); } #endif #ifdef MAG if (sensors(SENSOR_MAG)) { tfp_sprintf(lineBuffer, "HDG: %d", DECIDEGREES_TO_DEGREES(attitude.values.yaw)); padHalfLineBuffer(); i2c_OLED_set_line(rowIndex); i2c_OLED_send_string(lineBuffer); } #endif #ifdef BARO if (sensors(SENSOR_BARO)) { int32_t alt = baroCalculateAltitude(); tfp_sprintf(lineBuffer, "Alt: %d", alt / 100); padHalfLineBuffer(); i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex); i2c_OLED_send_string(lineBuffer); } #endif rowIndex++; char rollTrim[7], pitchTrim[7]; formatTrimDegrees(rollTrim, boardAlignment()->rollDeciDegrees); formatTrimDegrees(pitchTrim, boardAlignment()->pitchDeciDegrees); tfp_sprintf(lineBuffer, "Acc: %sR, %sP", rollTrim, pitchTrim ); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); }