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 batteryUpdateConsumptionState(void) { if (batteryConfig()->useConsumptionAlerts && batteryConfig()->batteryCapacity > 0 && batteryCellCount > 0) { uint8_t batteryPercentageRemaining = calculateBatteryPercentageRemaining(); if (batteryPercentageRemaining == 0) { consumptionState = BATTERY_CRITICAL; } else if (batteryPercentageRemaining <= batteryConfig()->consumptionWarningPercentage) { consumptionState = BATTERY_WARNING; } else { consumptionState = BATTERY_OK; } } }
void mavlinkSendSystemStatus(void) { uint16_t msgLength; uint32_t onboardControlAndSensors = 35843; /* onboard_control_sensors_present Bitmask fedcba9876543210 1000110000000011 For all = 35843 0001000000000100 With Mag = 4100 0010000000001000 With Baro = 8200 0100000000100000 With GPS = 16416 0000001111111111 */ if (sensors(SENSOR_MAG)) onboardControlAndSensors |= 4100; if (sensors(SENSOR_BARO)) onboardControlAndSensors |= 8200; if (sensors(SENSOR_GPS)) onboardControlAndSensors |= 16416; uint16_t batteryVoltage = 0; int16_t batteryAmperage = -1; int8_t batteryRemaining = 100; if (getBatteryState() < BATTERY_NOT_PRESENT) { batteryVoltage = isBatteryVoltageConfigured() ? getBatteryVoltage() * 100 : batteryVoltage; batteryAmperage = isAmperageConfigured() ? getAmperage() : batteryAmperage; batteryRemaining = isBatteryVoltageConfigured() ? calculateBatteryPercentageRemaining() : batteryRemaining; } mavlink_msg_sys_status_pack(0, 200, &mavMsg, // onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. //Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, // 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, // 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, // 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control onboardControlAndSensors, // onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled onboardControlAndSensors, // onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error. onboardControlAndSensors & 1023, // load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 0, // voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) batteryVoltage, // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current batteryAmperage, // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery batteryRemaining, // drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) 0, // errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) 0, // errors_count1 Autopilot-specific errors 0, // errors_count2 Autopilot-specific errors 0, // errors_count3 Autopilot-specific errors 0, // errors_count4 Autopilot-specific errors 0); msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg); mavlinkSerialWrite(mavBuffer, msgLength); }
static void applyLedFixedLayers(void) { for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) { const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex]; hsvColor_t color = *getSC(LED_SCOLOR_BACKGROUND); int fn = ledGetFunction(ledConfig); int hOffset = HSV_HUE_MAX + 1; switch (fn) { case LED_FUNCTION_COLOR: color = ledStripConfig()->colors[ledGetColor(ledConfig)]; hsvColor_t nextColor = ledStripConfig()->colors[(ledGetColor(ledConfig) + 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT]; hsvColor_t previousColor = ledStripConfig()->colors[(ledGetColor(ledConfig) - 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT]; if (ledGetOverlayBit(ledConfig, LED_OVERLAY_THROTTLE)) { //smooth fade with selected Aux channel of all HSV values from previousColor through color to nextColor int centerPWM = (PWM_RANGE_MIN + PWM_RANGE_MAX) / 2; if (auxInput < centerPWM) { color.h = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.h, color.h); color.s = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.s, color.s); color.v = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.v, color.v); } else { color.h = scaleRange(auxInput, centerPWM, PWM_RANGE_MAX, color.h, nextColor.h); color.s = scaleRange(auxInput, centerPWM, PWM_RANGE_MAX, color.s, nextColor.s); color.v = scaleRange(auxInput, centerPWM, PWM_RANGE_MAX, color.v, nextColor.v); } } break; case LED_FUNCTION_FLIGHT_MODE: for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++) if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) { const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]); if (directionalColor) { color = *directionalColor; } break; // stop on first match } break; case LED_FUNCTION_ARM_STATE: color = ARMING_FLAG(ARMED) ? *getSC(LED_SCOLOR_ARMED) : *getSC(LED_SCOLOR_DISARMED); break; case LED_FUNCTION_BATTERY: color = HSV(RED); hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120); break; case LED_FUNCTION_RSSI: color = HSV(RED); hOffset += scaleRange(getRssi() * 100, 0, 1023, -30, 120); break; default: break; } if ((fn != LED_FUNCTION_COLOR) && ledGetOverlayBit(ledConfig, LED_OVERLAY_THROTTLE)) { hOffset += scaleRange(auxInput, PWM_RANGE_MIN, PWM_RANGE_MAX, 0, HSV_HUE_MAX + 1); } color.h = (color.h + hOffset) % (HSV_HUE_MAX + 1); setLedHsv(ledIndex, &color); } }