mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Add battery profiles feature
This commit is contained in:
parent
99f7b1daf2
commit
ce8621ee8f
26 changed files with 578 additions and 176 deletions
|
@ -123,6 +123,7 @@ COMMON_SRC = \
|
||||||
blackbox/blackbox_encoding.c \
|
blackbox/blackbox_encoding.c \
|
||||||
blackbox/blackbox_io.c \
|
blackbox/blackbox_io.c \
|
||||||
cms/cms.c \
|
cms/cms.c \
|
||||||
|
cms/cms_menu_battery.c \
|
||||||
cms/cms_menu_blackbox.c \
|
cms/cms_menu_blackbox.c \
|
||||||
cms/cms_menu_builtin.c \
|
cms/cms_menu_builtin.c \
|
||||||
cms/cms_menu_imu.c \
|
cms/cms_menu_imu.c \
|
||||||
|
|
|
@ -506,7 +506,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
return feature(FEATURE_VBAT);
|
return feature(FEATURE_VBAT);
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
|
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
|
||||||
return feature(FEATURE_CURRENT_METER) && batteryConfig()->current.type == CURRENT_SENSOR_ADC;
|
return feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC;
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_SURFACE:
|
case FLIGHT_LOG_FIELD_CONDITION_SURFACE:
|
||||||
#ifdef USE_RANGEFINDER
|
#ifdef USE_RANGEFINDER
|
||||||
|
@ -1355,21 +1355,21 @@ static bool blackboxWriteSysinfo(void)
|
||||||
|
|
||||||
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
||||||
blackboxPrintfHeaderLine("vbat_scale", "%u", batteryConfig()->voltage.scale / 10);
|
blackboxPrintfHeaderLine("vbat_scale", "%u", batteryMetersConfig()->voltage_scale / 10);
|
||||||
} else {
|
} else {
|
||||||
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", batteryConfig()->voltage.cellMin / 10,
|
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", currentBatteryProfile->voltage.cellMin / 10,
|
||||||
batteryConfig()->voltage.cellWarning / 10,
|
currentBatteryProfile->voltage.cellWarning / 10,
|
||||||
batteryConfig()->voltage.cellMax / 10);
|
currentBatteryProfile->voltage.cellMax / 10);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
|
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
|
||||||
|
|
||||||
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
||||||
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
||||||
if (feature(FEATURE_CURRENT_METER)) {
|
if (feature(FEATURE_CURRENT_METER)) {
|
||||||
blackboxPrintfHeaderLine("currentMeter", "%d,%d", batteryConfig()->current.offset,
|
blackboxPrintfHeaderLine("currentMeter", "%d,%d", batteryMetersConfig()->current.offset,
|
||||||
batteryConfig()->current.scale);
|
batteryMetersConfig()->current.scale);
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
|
|
||||||
|
|
141
src/main/cms/cms_menu_battery.c
Normal file
141
src/main/cms/cms_menu_battery.c
Normal file
|
@ -0,0 +1,141 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_CMS
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_misc.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
// Battery menu
|
||||||
|
|
||||||
|
static uint8_t battDispProfileIndex;
|
||||||
|
static uint8_t battProfileIndex;
|
||||||
|
static char battProfileIndexString[] = " p";
|
||||||
|
|
||||||
|
|
||||||
|
static long cmsx_menuBattery_onEnter(const OSD_Entry *from)
|
||||||
|
{
|
||||||
|
UNUSED(from);
|
||||||
|
|
||||||
|
battProfileIndex = getConfigBatteryProfile();
|
||||||
|
battDispProfileIndex = battProfileIndex + 1;
|
||||||
|
battProfileIndexString[1] = '0' + battDispProfileIndex;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_menuBattery_onExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
setConfigBatteryProfile(battProfileIndex);
|
||||||
|
activateBatteryProfile();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_onBatteryProfileIndexChange(displayPort_t *displayPort, const void *ptr)
|
||||||
|
{
|
||||||
|
UNUSED(displayPort);
|
||||||
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
battProfileIndex = battDispProfileIndex - 1;
|
||||||
|
battProfileIndexString[1] = '0' + battDispProfileIndex;
|
||||||
|
batteryDisableProfileAutoswitch();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_menuBattSettings_onEnter(const OSD_Entry *from)
|
||||||
|
{
|
||||||
|
UNUSED(from);
|
||||||
|
|
||||||
|
setConfigBatteryProfile(battProfileIndex);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const OSD_Entry menuBattSettingsEntries[]=
|
||||||
|
{
|
||||||
|
OSD_LABEL_DATA_ENTRY("-- BATT SETTINGS --", battProfileIndexString),
|
||||||
|
|
||||||
|
#ifdef USE_ADC
|
||||||
|
OSD_SETTING_ENTRY("CELLS", SETTING_BAT_CELLS),
|
||||||
|
OSD_SETTING_ENTRY("CELL DET.", SETTING_VBAT_CELL_DETECT_VOLTAGE),
|
||||||
|
OSD_SETTING_ENTRY("CELL MAX", SETTING_VBAT_MAX_CELL_VOLTAGE),
|
||||||
|
OSD_SETTING_ENTRY("CELL WARN", SETTING_VBAT_WARNING_CELL_VOLTAGE),
|
||||||
|
OSD_SETTING_ENTRY("CELL MIN", SETTING_VBAT_MIN_CELL_VOLTAGE),
|
||||||
|
#endif /* USE_ADC */
|
||||||
|
OSD_SETTING_ENTRY("CAP UNIT", SETTING_BATTERY_CAPACITY_UNIT),
|
||||||
|
OSD_SETTING_ENTRY("CAPACITY", SETTING_BATTERY_CAPACITY),
|
||||||
|
OSD_SETTING_ENTRY("CAP WARN", SETTING_BATTERY_CAPACITY_WARNING),
|
||||||
|
OSD_SETTING_ENTRY("CAP CRIT", SETTING_BATTERY_CAPACITY_CRITICAL),
|
||||||
|
|
||||||
|
OSD_BACK_ENTRY,
|
||||||
|
OSD_END_ENTRY
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuBattSettings = {
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
.GUARD_text = "XBATT",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
#endif
|
||||||
|
.onEnter = cmsx_menuBattSettings_onEnter,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuBattSettingsEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
static OSD_Entry menuBatteryEntries[]=
|
||||||
|
{
|
||||||
|
OSD_LABEL_ENTRY("-- BATTERY --"),
|
||||||
|
|
||||||
|
#ifdef USE_ADC
|
||||||
|
OSD_SETTING_ENTRY("PROF AUTOSWITCH", SETTING_BAT_PROFILE_AUTOSWITCH),
|
||||||
|
#endif
|
||||||
|
OSD_UINT8_CALLBACK_ENTRY("PROF", cmsx_onBatteryProfileIndexChange, (&(const OSD_UINT8_t){ &battDispProfileIndex, 1, MAX_BATTERY_PROFILE_COUNT, 1})),
|
||||||
|
OSD_SUBMENU_ENTRY("SETTINGS", &cmsx_menuBattSettings),
|
||||||
|
|
||||||
|
OSD_BACK_ENTRY,
|
||||||
|
OSD_END_ENTRY
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuBattery = {
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
.GUARD_text = "XBATT",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
#endif
|
||||||
|
.onEnter = cmsx_menuBattery_onEnter,
|
||||||
|
.onExit = cmsx_menuBattery_onExit,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuBatteryEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // CMS
|
20
src/main/cms/cms_menu_battery.h
Normal file
20
src/main/cms/cms_menu_battery.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuBattery;
|
|
@ -46,6 +46,7 @@
|
||||||
#include "cms/cms_menu_vtx.h"
|
#include "cms/cms_menu_vtx.h"
|
||||||
#include "cms/cms_menu_osd.h"
|
#include "cms/cms_menu_osd.h"
|
||||||
#include "cms/cms_menu_ledstrip.h"
|
#include "cms/cms_menu_ledstrip.h"
|
||||||
|
#include "cms/cms_menu_battery.h"
|
||||||
#include "cms/cms_menu_misc.h"
|
#include "cms/cms_menu_misc.h"
|
||||||
|
|
||||||
// VTX supplied menus
|
// VTX supplied menus
|
||||||
|
@ -150,6 +151,7 @@ static const OSD_Entry menuMainEntries[] =
|
||||||
OSD_SUBMENU_ENTRY("OSD LAYOUTS", &cmsx_menuOsdLayout),
|
OSD_SUBMENU_ENTRY("OSD LAYOUTS", &cmsx_menuOsdLayout),
|
||||||
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
||||||
#endif
|
#endif
|
||||||
|
OSD_SUBMENU_ENTRY("BATTERY", &cmsx_menuBattery),
|
||||||
OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo),
|
OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo),
|
||||||
OSD_SUBMENU_ENTRY("MISC", &cmsx_menuMisc),
|
OSD_SUBMENU_ENTRY("MISC", &cmsx_menuMisc),
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav
|
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav
|
||||||
//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav
|
//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav
|
||||||
#define PG_GYRO_CONFIG 10
|
#define PG_GYRO_CONFIG 10
|
||||||
#define PG_BATTERY_CONFIG 11
|
#define PG_BATTERY_PROFILES 11
|
||||||
#define PG_CONTROL_RATE_PROFILES 12
|
#define PG_CONTROL_RATE_PROFILES 12
|
||||||
#define PG_SERIAL_CONFIG 13
|
#define PG_SERIAL_CONFIG 13
|
||||||
#define PG_PID_PROFILE 14
|
#define PG_PID_PROFILE 14
|
||||||
|
@ -63,6 +63,7 @@
|
||||||
#define PG_SERVO_PARAMS 42
|
#define PG_SERVO_PARAMS 42
|
||||||
//#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
|
//#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
|
||||||
#define PG_RX_CHANNEL_RANGE_CONFIG 44
|
#define PG_RX_CHANNEL_RANGE_CONFIG 44
|
||||||
|
#define PG_BATTERY_METERS_CONFIG 45
|
||||||
//#define PG_MODE_COLOR_CONFIG 45
|
//#define PG_MODE_COLOR_CONFIG 45
|
||||||
//#define PG_SPECIAL_COLOR_CONFIG 46
|
//#define PG_SPECIAL_COLOR_CONFIG 46
|
||||||
//#define PG_PILOT_CONFIG 47
|
//#define PG_PILOT_CONFIG 47
|
||||||
|
|
|
@ -229,11 +229,12 @@ static void cliPutp(void *p, char ch)
|
||||||
typedef enum {
|
typedef enum {
|
||||||
DUMP_MASTER = (1 << 0),
|
DUMP_MASTER = (1 << 0),
|
||||||
DUMP_PROFILE = (1 << 1),
|
DUMP_PROFILE = (1 << 1),
|
||||||
DUMP_RATES = (1 << 2),
|
DUMP_BATTERY_PROFILE = (1 << 2),
|
||||||
DUMP_ALL = (1 << 3),
|
DUMP_RATES = (1 << 3),
|
||||||
DO_DIFF = (1 << 4),
|
DUMP_ALL = (1 << 4),
|
||||||
SHOW_DEFAULTS = (1 << 5),
|
DO_DIFF = (1 << 5),
|
||||||
HIDE_UNUSED = (1 << 6)
|
SHOW_DEFAULTS = (1 << 6),
|
||||||
|
HIDE_UNUSED = (1 << 7)
|
||||||
} dumpFlags_e;
|
} dumpFlags_e;
|
||||||
|
|
||||||
static void cliPrintfva(const char *format, va_list va)
|
static void cliPrintfva(const char *format, va_list va)
|
||||||
|
@ -2203,6 +2204,33 @@ static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask)
|
||||||
dumpAllValues(CONTROL_RATE_VALUE, dumpMask);
|
dumpAllValues(CONTROL_RATE_VALUE, dumpMask);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void cliBatteryProfile(char *cmdline)
|
||||||
|
{
|
||||||
|
// CLI profile index is 1-based
|
||||||
|
if (isEmpty(cmdline)) {
|
||||||
|
cliPrintLinef("battery_profile %d", getConfigBatteryProfile() + 1);
|
||||||
|
return;
|
||||||
|
} else {
|
||||||
|
const int i = fastA2I(cmdline) - 1;
|
||||||
|
if (i >= 0 && i < MAX_PROFILE_COUNT) {
|
||||||
|
setConfigBatteryProfileAndWriteEEPROM(i);
|
||||||
|
cliBatteryProfile("");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cliDumpBatteryProfile(uint8_t profileIndex, uint8_t dumpMask)
|
||||||
|
{
|
||||||
|
if (profileIndex >= MAX_BATTERY_PROFILE_COUNT) {
|
||||||
|
// Faulty values
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
setConfigBatteryProfile(profileIndex);
|
||||||
|
cliPrintHashLine("battery_profile");
|
||||||
|
cliPrintLinef("battery_profile %d\r\n", getConfigBatteryProfile() + 1);
|
||||||
|
dumpAllValues(BATTERY_CONFIG_VALUE, dumpMask);
|
||||||
|
}
|
||||||
|
|
||||||
static void cliSave(char *cmdline)
|
static void cliSave(char *cmdline)
|
||||||
{
|
{
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
@ -2583,6 +2611,8 @@ static void printConfig(const char *cmdline, bool doDiff)
|
||||||
dumpMask = DUMP_MASTER; // only
|
dumpMask = DUMP_MASTER; // only
|
||||||
} else if ((options = checkCommand(cmdline, "profile"))) {
|
} else if ((options = checkCommand(cmdline, "profile"))) {
|
||||||
dumpMask = DUMP_PROFILE; // only
|
dumpMask = DUMP_PROFILE; // only
|
||||||
|
} else if ((options = checkCommand(cmdline, "battery_profile"))) {
|
||||||
|
dumpMask = DUMP_BATTERY_PROFILE; // only
|
||||||
} else if ((options = checkCommand(cmdline, "all"))) {
|
} else if ((options = checkCommand(cmdline, "all"))) {
|
||||||
dumpMask = DUMP_ALL; // all profiles and rates
|
dumpMask = DUMP_ALL; // all profiles and rates
|
||||||
} else {
|
} else {
|
||||||
|
@ -2594,11 +2624,13 @@ static void printConfig(const char *cmdline, bool doDiff)
|
||||||
}
|
}
|
||||||
|
|
||||||
const int currentProfileIndexSave = getConfigProfile();
|
const int currentProfileIndexSave = getConfigProfile();
|
||||||
|
const int currentBatteryProfileIndexSave = getConfigBatteryProfile();
|
||||||
backupConfigs();
|
backupConfigs();
|
||||||
// reset all configs to defaults to do differencing
|
// reset all configs to defaults to do differencing
|
||||||
resetConfigs();
|
resetConfigs();
|
||||||
// restore the profile indices, since they should not be reset for proper comparison
|
// restore the profile indices, since they should not be reset for proper comparison
|
||||||
setConfigProfile(currentProfileIndexSave);
|
setConfigProfile(currentProfileIndexSave);
|
||||||
|
setConfigBatteryProfile(currentBatteryProfileIndexSave);
|
||||||
|
|
||||||
if (checkCommand(options, "showdefaults")) {
|
if (checkCommand(options, "showdefaults")) {
|
||||||
dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
|
dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
|
||||||
|
@ -2681,23 +2713,35 @@ static void printConfig(const char *cmdline, bool doDiff)
|
||||||
if (dumpMask & DUMP_ALL) {
|
if (dumpMask & DUMP_ALL) {
|
||||||
// dump all profiles
|
// dump all profiles
|
||||||
const int currentProfileIndexSave = getConfigProfile();
|
const int currentProfileIndexSave = getConfigProfile();
|
||||||
|
const int currentBatteryProfileIndexSave = getConfigBatteryProfile();
|
||||||
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
|
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
|
||||||
cliDumpProfile(ii, dumpMask);
|
cliDumpProfile(ii, dumpMask);
|
||||||
}
|
}
|
||||||
|
for (int ii = 0; ii < MAX_BATTERY_PROFILE_COUNT; ++ii) {
|
||||||
|
cliDumpBatteryProfile(ii, dumpMask);
|
||||||
|
}
|
||||||
setConfigProfile(currentProfileIndexSave);
|
setConfigProfile(currentProfileIndexSave);
|
||||||
|
setConfigBatteryProfile(currentBatteryProfileIndexSave);
|
||||||
|
|
||||||
cliPrintHashLine("restore original profile selection");
|
cliPrintHashLine("restore original profile selection");
|
||||||
cliPrintLinef("profile %d", currentProfileIndexSave + 1);
|
cliPrintLinef("profile %d", currentProfileIndexSave + 1);
|
||||||
|
cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1);
|
||||||
|
|
||||||
cliPrintHashLine("save configuration\r\nsave");
|
cliPrintHashLine("save configuration\r\nsave");
|
||||||
} else {
|
} else {
|
||||||
// dump just the current profile
|
// dump just the current profiles
|
||||||
cliDumpProfile(getConfigProfile(), dumpMask);
|
cliDumpProfile(getConfigProfile(), dumpMask);
|
||||||
|
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dumpMask & DUMP_PROFILE) {
|
if (dumpMask & DUMP_PROFILE) {
|
||||||
cliDumpProfile(getConfigProfile(), dumpMask);
|
cliDumpProfile(getConfigProfile(), dumpMask);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (dumpMask & DUMP_BATTERY_PROFILE) {
|
||||||
|
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
|
||||||
|
}
|
||||||
// restore configs from copies
|
// restore configs from copies
|
||||||
restoreConfigs();
|
restoreConfigs();
|
||||||
}
|
}
|
||||||
|
@ -2760,9 +2804,9 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
|
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
|
||||||
CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
|
CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
|
||||||
CLI_COMMAND_DEF("diff", "list configuration changes from default",
|
CLI_COMMAND_DEF("diff", "list configuration changes from default",
|
||||||
"[master|profile|rates|all] {showdefaults}", cliDiff),
|
"[master|battery_profile|profile|rates|all] {showdefaults}", cliDiff),
|
||||||
CLI_COMMAND_DEF("dump", "dump configuration",
|
CLI_COMMAND_DEF("dump", "dump configuration",
|
||||||
"[master|profile|rates|all] {showdefaults}", cliDump),
|
"[master|battery_profile|profile|rates|all] {showdefaults}", cliDump),
|
||||||
#ifdef USE_RX_ELERES
|
#ifdef USE_RX_ELERES
|
||||||
CLI_COMMAND_DEF("eleres_bind", NULL, NULL, cliEleresBind),
|
CLI_COMMAND_DEF("eleres_bind", NULL, NULL, cliEleresBind),
|
||||||
#endif // USE_RX_ELERES
|
#endif // USE_RX_ELERES
|
||||||
|
@ -2796,6 +2840,8 @@ const clicmd_t cmdTable[] = {
|
||||||
#endif
|
#endif
|
||||||
CLI_COMMAND_DEF("profile", "change profile",
|
CLI_COMMAND_DEF("profile", "change profile",
|
||||||
"[<index>]", cliProfile),
|
"[<index>]", cliProfile),
|
||||||
|
CLI_COMMAND_DEF("battery_profile", "change battery profile",
|
||||||
|
"[<index>]", cliBatteryProfile),
|
||||||
#if !defined(SKIP_TASK_STATISTICS) && !defined(SKIP_CLI_RESOURCES)
|
#if !defined(SKIP_TASK_STATISTICS) && !defined(SKIP_CLI_RESOURCES)
|
||||||
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
|
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -109,6 +109,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG,
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
.current_profile_index = 0,
|
.current_profile_index = 0,
|
||||||
|
.current_battery_profile_index = 0,
|
||||||
.debug_mode = DEBUG_NONE,
|
.debug_mode = DEBUG_NONE,
|
||||||
.i2c_speed = I2C_SPEED_400KHZ,
|
.i2c_speed = I2C_SPEED_400KHZ,
|
||||||
.cpuUnderclock = 0,
|
.cpuUnderclock = 0,
|
||||||
|
@ -367,6 +368,7 @@ void resetConfigs(void)
|
||||||
static void activateConfig(void)
|
static void activateConfig(void)
|
||||||
{
|
{
|
||||||
activateControlRateConfig();
|
activateControlRateConfig();
|
||||||
|
activateBatteryProfile();
|
||||||
|
|
||||||
resetAdjustmentStates();
|
resetAdjustmentStates();
|
||||||
|
|
||||||
|
@ -396,6 +398,7 @@ void readEEPROM(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
setConfigProfile(getConfigProfile());
|
setConfigProfile(getConfigProfile());
|
||||||
|
setConfigBatteryProfile(getConfigBatteryProfile());
|
||||||
|
|
||||||
validateAndFixConfig();
|
validateAndFixConfig();
|
||||||
activateConfig();
|
activateConfig();
|
||||||
|
@ -464,6 +467,35 @@ void setConfigProfileAndWriteEEPROM(uint8_t profileIndex)
|
||||||
beeperConfirmationBeeps(profileIndex + 1);
|
beeperConfirmationBeeps(profileIndex + 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t getConfigBatteryProfile(void)
|
||||||
|
{
|
||||||
|
return systemConfig()->current_battery_profile_index;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setConfigBatteryProfile(uint8_t profileIndex)
|
||||||
|
{
|
||||||
|
bool ret = true; // return true if current_battery_profile_index has changed
|
||||||
|
if (systemConfig()->current_battery_profile_index == profileIndex) {
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
if (profileIndex >= MAX_BATTERY_PROFILE_COUNT) {// sanity check
|
||||||
|
profileIndex = 0;
|
||||||
|
}
|
||||||
|
systemConfigMutable()->current_battery_profile_index = profileIndex;
|
||||||
|
setBatteryProfile(profileIndex);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex)
|
||||||
|
{
|
||||||
|
if (setConfigBatteryProfile(profileIndex)) {
|
||||||
|
// profile has changed, so ensure current values saved before new profile is loaded
|
||||||
|
writeEEPROM();
|
||||||
|
readEEPROM();
|
||||||
|
}
|
||||||
|
beeperConfirmationBeeps(profileIndex + 1);
|
||||||
|
}
|
||||||
|
|
||||||
void beeperOffSet(uint32_t mask)
|
void beeperOffSet(uint32_t mask)
|
||||||
{
|
{
|
||||||
beeperConfigMutable()->beeper_off_flags |= mask;
|
beeperConfigMutable()->beeper_off_flags |= mask;
|
||||||
|
|
|
@ -81,6 +81,7 @@ typedef struct systemConfig_s {
|
||||||
uint16_t accTaskFrequency;
|
uint16_t accTaskFrequency;
|
||||||
uint16_t attitudeTaskFrequency;
|
uint16_t attitudeTaskFrequency;
|
||||||
uint8_t current_profile_index;
|
uint8_t current_profile_index;
|
||||||
|
uint8_t current_battery_profile_index;
|
||||||
uint8_t asyncMode;
|
uint8_t asyncMode;
|
||||||
uint8_t debug_mode;
|
uint8_t debug_mode;
|
||||||
uint8_t i2c_speed;
|
uint8_t i2c_speed;
|
||||||
|
@ -134,6 +135,10 @@ uint8_t getConfigProfile(void);
|
||||||
bool setConfigProfile(uint8_t profileIndex);
|
bool setConfigProfile(uint8_t profileIndex);
|
||||||
void setConfigProfileAndWriteEEPROM(uint8_t profileIndex);
|
void setConfigProfileAndWriteEEPROM(uint8_t profileIndex);
|
||||||
|
|
||||||
|
uint8_t getConfigBatteryProfile(void);
|
||||||
|
bool setConfigBatteryProfile(uint8_t profileIndex);
|
||||||
|
void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex);
|
||||||
|
|
||||||
bool canSoftwareSerialBeUsed(void);
|
bool canSoftwareSerialBeUsed(void);
|
||||||
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch);
|
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch);
|
||||||
|
|
||||||
|
|
|
@ -302,7 +302,7 @@ void init(void)
|
||||||
pwm_params.useParallelPWM = (rxConfig()->receiverType == RX_TYPE_PWM);
|
pwm_params.useParallelPWM = (rxConfig()->receiverType == RX_TYPE_PWM);
|
||||||
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
|
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
|
||||||
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
|
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
|
||||||
&& batteryConfig()->current.type == CURRENT_SENSOR_ADC;
|
&& batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC;
|
||||||
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
|
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
|
||||||
pwm_params.usePPM = (rxConfig()->receiverType == RX_TYPE_PPM);
|
pwm_params.usePPM = (rxConfig()->receiverType == RX_TYPE_PPM);
|
||||||
pwm_params.useSerialRx = (rxConfig()->receiverType == RX_TYPE_SERIAL);
|
pwm_params.useSerialRx = (rxConfig()->receiverType == RX_TYPE_SERIAL);
|
||||||
|
@ -473,7 +473,7 @@ void init(void)
|
||||||
adc_params.adcFunctionChannel[ADC_RSSI] = adcChannelConfig()->adcFunctionChannel[ADC_RSSI];
|
adc_params.adcFunctionChannel[ADC_RSSI] = adcChannelConfig()->adcFunctionChannel[ADC_RSSI];
|
||||||
}
|
}
|
||||||
|
|
||||||
if (feature(FEATURE_CURRENT_METER) && batteryConfig()->current.type == CURRENT_SENSOR_ADC) {
|
if (feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC) {
|
||||||
adc_params.adcFunctionChannel[ADC_CURRENT] = adcChannelConfig()->adcFunctionChannel[ADC_CURRENT];
|
adc_params.adcFunctionChannel[ADC_CURRENT] = adcChannelConfig()->adcFunctionChannel[ADC_CURRENT];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -419,7 +419,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
#endif
|
#endif
|
||||||
sbufWriteU16(dst, packSensorStatus());
|
sbufWriteU16(dst, packSensorStatus());
|
||||||
sbufWriteU16(dst, averageSystemLoadPercent);
|
sbufWriteU16(dst, averageSystemLoadPercent);
|
||||||
sbufWriteU8(dst, getConfigProfile());
|
sbufWriteU8(dst, (getConfigBatteryProfile() << 4) || getConfigProfile());
|
||||||
sbufWriteU32(dst, armingFlags);
|
sbufWriteU32(dst, armingFlags);
|
||||||
sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags));
|
sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags));
|
||||||
}
|
}
|
||||||
|
@ -670,10 +670,10 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
|
|
||||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||||
|
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.scale / 10);
|
sbufWriteU8(dst, batteryMetersConfig()->voltage_scale / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMin / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMax / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellWarning / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP2_INAV_MISC:
|
case MSP2_INAV_MISC:
|
||||||
|
@ -698,32 +698,32 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
|
|
||||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||||
|
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.scale);
|
sbufWriteU16(dst, batteryMetersConfig()->voltage_scale);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellDetect);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellDetect);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMin);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMax);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellWarning);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
|
||||||
|
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.value);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.value);
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.warning);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.warning);
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.critical);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.critical);
|
||||||
sbufWriteU8(dst, batteryConfig()->capacity.unit);
|
sbufWriteU8(dst, currentBatteryProfile->capacity.unit);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP2_INAV_BATTERY_CONFIG:
|
case MSP2_INAV_BATTERY_CONFIG:
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.scale);
|
sbufWriteU16(dst, batteryMetersConfig()->voltage_scale);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellDetect);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellDetect);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMin);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMax);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
|
||||||
sbufWriteU16(dst, batteryConfig()->voltage.cellWarning);
|
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
|
||||||
|
|
||||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
|
||||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
|
||||||
|
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.value);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.value);
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.warning);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.warning);
|
||||||
sbufWriteU32(dst, batteryConfig()->capacity.critical);
|
sbufWriteU32(dst, currentBatteryProfile->capacity.critical);
|
||||||
sbufWriteU8(dst, batteryConfig()->capacity.unit);
|
sbufWriteU8(dst, currentBatteryProfile->capacity.unit);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_MOTOR_PINS:
|
case MSP_MOTOR_PINS:
|
||||||
|
@ -809,17 +809,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_VOLTAGE_METER_CONFIG:
|
case MSP_VOLTAGE_METER_CONFIG:
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.scale / 10);
|
sbufWriteU8(dst, batteryMetersConfig()->voltage_scale / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMin / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMax / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltage.cellWarning / 10);
|
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_CURRENT_METER_CONFIG:
|
case MSP_CURRENT_METER_CONFIG:
|
||||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
|
||||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
|
||||||
sbufWriteU8(dst, batteryConfig()->current.type);
|
sbufWriteU8(dst, batteryMetersConfig()->current.type);
|
||||||
sbufWriteU16(dst, constrain(batteryConfig()->capacity.value, 0, 0xFFFF));
|
sbufWriteU16(dst, constrain(currentBatteryProfile->capacity.value, 0, 0xFFFF));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_MIXER:
|
case MSP_MIXER:
|
||||||
|
@ -879,8 +879,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
sbufWriteU16(dst, boardAlignment()->pitchDeciDegrees);
|
sbufWriteU16(dst, boardAlignment()->pitchDeciDegrees);
|
||||||
sbufWriteU16(dst, boardAlignment()->yawDeciDegrees);
|
sbufWriteU16(dst, boardAlignment()->yawDeciDegrees);
|
||||||
|
|
||||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
|
||||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_CF_SERIAL_CONFIG:
|
case MSP_CF_SERIAL_CONFIG:
|
||||||
|
@ -964,7 +964,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
||||||
#endif
|
#endif
|
||||||
sbufWriteU8(dst, osdConfig()->units);
|
sbufWriteU8(dst, osdConfig()->units);
|
||||||
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
||||||
sbufWriteU16(dst, batteryConfig()->capacity.warning);
|
sbufWriteU16(dst, currentBatteryProfile->capacity.warning);
|
||||||
sbufWriteU16(dst, osdConfig()->time_alarm);
|
sbufWriteU16(dst, osdConfig()->time_alarm);
|
||||||
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
||||||
sbufWriteU16(dst, osdConfig()->dist_alarm);
|
sbufWriteU16(dst, osdConfig()->dist_alarm);
|
||||||
|
@ -1415,6 +1415,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
{
|
{
|
||||||
uint8_t tmp_u8;
|
uint8_t tmp_u8;
|
||||||
uint16_t tmp_u16;
|
uint16_t tmp_u16;
|
||||||
|
batteryProfile_t *currentBatteryProfileMutable = (batteryProfile_t*)currentBatteryProfile;
|
||||||
|
|
||||||
const unsigned int dataSize = sbufBytesRemaining(src);
|
const unsigned int dataSize = sbufBytesRemaining(src);
|
||||||
|
|
||||||
|
@ -1625,10 +1626,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
sbufReadU16(src);
|
sbufReadU16(src);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
batteryConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
|
batteryMetersConfigMutable()->voltage_scale = sbufReadU8(src) * 10;
|
||||||
batteryConfigMutable()->voltage.cellMin = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
|
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
|
||||||
batteryConfigMutable()->voltage.cellMax = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
|
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
|
||||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
|
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
|
||||||
} else
|
} else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
break;
|
break;
|
||||||
|
@ -1663,18 +1664,18 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
sbufReadU16(src);
|
sbufReadU16(src);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
batteryConfigMutable()->voltage.scale = sbufReadU16(src);
|
batteryMetersConfigMutable()->voltage_scale = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellDetect = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellDetect = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellMin = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellMax = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
|
||||||
|
|
||||||
batteryConfigMutable()->capacity.value = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.value = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.warning = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.warning = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.critical = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.critical = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.unit = sbufReadU8(src);
|
currentBatteryProfileMutable->capacity.unit = sbufReadU8(src);
|
||||||
if ((batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
if ((currentBatteryProfile->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (currentBatteryProfile->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
||||||
batteryConfigMutable()->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
currentBatteryProfileMutable->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
}
|
}
|
||||||
} else
|
} else
|
||||||
|
@ -1683,21 +1684,21 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
|
|
||||||
case MSP2_INAV_SET_BATTERY_CONFIG:
|
case MSP2_INAV_SET_BATTERY_CONFIG:
|
||||||
if (dataSize == 27) {
|
if (dataSize == 27) {
|
||||||
batteryConfigMutable()->voltage.scale = sbufReadU16(src);
|
batteryMetersConfigMutable()->voltage_scale = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellDetect = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellDetect = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellMin = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellMax = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU16(src);
|
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
|
||||||
|
|
||||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
|
||||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
|
||||||
|
|
||||||
batteryConfigMutable()->capacity.value = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.value = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.warning = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.warning = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.critical = sbufReadU32(src);
|
currentBatteryProfileMutable->capacity.critical = sbufReadU32(src);
|
||||||
batteryConfigMutable()->capacity.unit = sbufReadU8(src);
|
currentBatteryProfileMutable->capacity.unit = sbufReadU8(src);
|
||||||
if ((batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
if ((currentBatteryProfile->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (currentBatteryProfile->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
||||||
batteryConfigMutable()->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
currentBatteryProfileMutable->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
}
|
}
|
||||||
} else
|
} else
|
||||||
|
@ -2089,7 +2090,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
#endif
|
#endif
|
||||||
osdConfigMutable()->units = sbufReadU8(src);
|
osdConfigMutable()->units = sbufReadU8(src);
|
||||||
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
||||||
batteryConfigMutable()->capacity.warning = sbufReadU16(src);
|
currentBatteryProfileMutable->capacity.warning = sbufReadU16(src);
|
||||||
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
||||||
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
||||||
// Won't be read if they weren't provided
|
// Won't be read if they weren't provided
|
||||||
|
@ -2234,20 +2235,20 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
|
|
||||||
case MSP_SET_VOLTAGE_METER_CONFIG:
|
case MSP_SET_VOLTAGE_METER_CONFIG:
|
||||||
if (dataSize >= 4) {
|
if (dataSize >= 4) {
|
||||||
batteryConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
|
batteryMetersConfigMutable()->voltage_scale = sbufReadU8(src) * 10;
|
||||||
batteryConfigMutable()->voltage.cellMin = sbufReadU8(src) * 10;
|
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10;
|
||||||
batteryConfigMutable()->voltage.cellMax = sbufReadU8(src) * 10;
|
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10;
|
||||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU8(src) * 10;
|
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10;
|
||||||
} else
|
} else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_CURRENT_METER_CONFIG:
|
case MSP_SET_CURRENT_METER_CONFIG:
|
||||||
if (dataSize >= 7) {
|
if (dataSize >= 7) {
|
||||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
|
||||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
|
||||||
batteryConfigMutable()->current.type = sbufReadU8(src);
|
batteryMetersConfigMutable()->current.type = sbufReadU8(src);
|
||||||
batteryConfigMutable()->capacity.value = sbufReadU16(src);
|
currentBatteryProfileMutable->capacity.value = sbufReadU16(src);
|
||||||
} else
|
} else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
break;
|
break;
|
||||||
|
@ -2331,8 +2332,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
boardAlignmentMutable()->pitchDeciDegrees = sbufReadU16(src); // board_align_pitch
|
boardAlignmentMutable()->pitchDeciDegrees = sbufReadU16(src); // board_align_pitch
|
||||||
boardAlignmentMutable()->yawDeciDegrees = sbufReadU16(src); // board_align_yaw
|
boardAlignmentMutable()->yawDeciDegrees = sbufReadU16(src); // board_align_yaw
|
||||||
|
|
||||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
|
||||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
|
||||||
} else
|
} else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
break;
|
break;
|
||||||
|
@ -2517,6 +2518,13 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case MSP2_INAV_SELECT_BATTERY_PROFILE:
|
||||||
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
|
if (sbufReadU8Safe(&tmp_u8, src))
|
||||||
|
setConfigBatteryProfileAndWriteEEPROM(tmp_u8);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
}
|
}
|
||||||
|
|
|
@ -232,7 +232,6 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
}
|
}
|
||||||
|
|
||||||
// actions during not armed
|
// actions during not armed
|
||||||
int i = 0;
|
|
||||||
|
|
||||||
// GYRO calibration
|
// GYRO calibration
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
|
@ -257,16 +256,38 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
|
|
||||||
// Multiple configuration profiles
|
// Multiple configuration profiles
|
||||||
if (feature(FEATURE_TX_PROF_SEL)) {
|
if (feature(FEATURE_TX_PROF_SEL)) {
|
||||||
|
|
||||||
|
uint8_t i = 0;
|
||||||
|
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
||||||
i = 1;
|
i = 1;
|
||||||
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_CE) // PITCH up -> Profile 2
|
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_CE) // PITCH up -> Profile 2
|
||||||
i = 2;
|
i = 2;
|
||||||
else if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_HI) // ROLL right -> Profile 3
|
else if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_HI) // ROLL right -> Profile 3
|
||||||
i = 3;
|
i = 3;
|
||||||
|
|
||||||
if (i) {
|
if (i) {
|
||||||
setConfigProfileAndWriteEEPROM(i - 1);
|
setConfigProfileAndWriteEEPROM(i - 1);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
i = 0;
|
||||||
|
|
||||||
|
// Multiple battery configuration profiles
|
||||||
|
if (rcSticks == THR_HI + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
||||||
|
i = 1;
|
||||||
|
else if (rcSticks == THR_HI + YAW_LO + PIT_HI + ROL_CE) // PITCH up -> Profile 2
|
||||||
|
i = 2;
|
||||||
|
else if (rcSticks == THR_HI + YAW_LO + PIT_CE + ROL_HI) // ROLL right -> Profile 3
|
||||||
|
i = 3;
|
||||||
|
|
||||||
|
if (i) {
|
||||||
|
setConfigBatteryProfileAndWriteEEPROM(i - 1);
|
||||||
|
batteryDisableProfileAutoswitch();
|
||||||
|
activateBatteryProfile();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save config
|
// Save config
|
||||||
|
|
|
@ -118,6 +118,8 @@ static uint16_t getValueOffset(const setting_t *value)
|
||||||
return value->offset + sizeof(pidProfile_t) * getConfigProfile();
|
return value->offset + sizeof(pidProfile_t) * getConfigProfile();
|
||||||
case CONTROL_RATE_VALUE:
|
case CONTROL_RATE_VALUE:
|
||||||
return value->offset + sizeof(controlRateConfig_t) * getConfigProfile();
|
return value->offset + sizeof(controlRateConfig_t) * getConfigProfile();
|
||||||
|
case BATTERY_CONFIG_VALUE:
|
||||||
|
return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile();
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,6 +34,7 @@ typedef enum {
|
||||||
MASTER_VALUE = (0 << SETTING_SECTION_OFFSET),
|
MASTER_VALUE = (0 << SETTING_SECTION_OFFSET),
|
||||||
PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET),
|
PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET),
|
||||||
CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20
|
CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20
|
||||||
|
BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET),
|
||||||
} setting_section_e;
|
} setting_section_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -97,4 +98,4 @@ setting_min_t setting_get_min(const setting_t *val);
|
||||||
// Returns the maximum valid value for the given setting_t. setting_max_t
|
// Returns the maximum valid value for the given setting_t. setting_max_t
|
||||||
// depends on the target and build options, but will always be an unsigned
|
// depends on the target and build options, but will always be an unsigned
|
||||||
// integer (e.g. uintxx_t,)
|
// integer (e.g. uintxx_t,)
|
||||||
setting_max_t setting_get_max(const setting_t *val);
|
setting_max_t setting_get_max(const setting_t *val);
|
||||||
|
|
|
@ -500,16 +500,43 @@ groups:
|
||||||
field: yawDeciDegrees
|
field: yawDeciDegrees
|
||||||
min: -1800
|
min: -1800
|
||||||
max: 3600
|
max: 3600
|
||||||
|
|
||||||
- name: PG_BATTERY_CONFIG
|
- name: PG_BATTERY_METERS_CONFIG
|
||||||
type: batteryConfig_t
|
type: batteryMetersConfig_t
|
||||||
headers: ["sensors/battery.h"]
|
headers: ["sensors/battery.h"]
|
||||||
members:
|
members:
|
||||||
|
- name: bat_profile_autoswitch
|
||||||
|
field: profile_autoswitch
|
||||||
|
condition: USE_ADC
|
||||||
|
type: bool
|
||||||
- name: vbat_scale
|
- name: vbat_scale
|
||||||
field: voltage.scale
|
field: voltage_scale
|
||||||
condition: USE_ADC
|
condition: USE_ADC
|
||||||
min: VBAT_SCALE_MIN
|
min: VBAT_SCALE_MIN
|
||||||
max: VBAT_SCALE_MAX
|
max: VBAT_SCALE_MAX
|
||||||
|
- name: current_meter_scale
|
||||||
|
field: current.scale
|
||||||
|
min: -10000
|
||||||
|
max: 10000
|
||||||
|
- name: current_meter_offset
|
||||||
|
field: current.offset
|
||||||
|
min: -3300
|
||||||
|
max: 3300
|
||||||
|
- name: current_meter_type
|
||||||
|
field: current.type
|
||||||
|
table: current_sensor
|
||||||
|
type: uint8_t
|
||||||
|
|
||||||
|
- name: PG_BATTERY_PROFILES
|
||||||
|
type: batteryProfile_t
|
||||||
|
headers: ["sensors/battery.h"]
|
||||||
|
value_type: BATTERY_CONFIG_VALUE
|
||||||
|
members:
|
||||||
|
- name: bat_cells
|
||||||
|
field: cells
|
||||||
|
condition: USE_ADC
|
||||||
|
min: 0
|
||||||
|
max: 8
|
||||||
- name: vbat_cell_detect_voltage
|
- name: vbat_cell_detect_voltage
|
||||||
field: voltage.cellDetect
|
field: voltage.cellDetect
|
||||||
condition: USE_ADC
|
condition: USE_ADC
|
||||||
|
@ -546,18 +573,6 @@ groups:
|
||||||
field: capacity.unit
|
field: capacity.unit
|
||||||
table: bat_capacity_unit
|
table: bat_capacity_unit
|
||||||
type: uint8_t
|
type: uint8_t
|
||||||
- name: current_meter_scale
|
|
||||||
field: current.scale
|
|
||||||
min: -10000
|
|
||||||
max: 10000
|
|
||||||
- name: current_meter_offset
|
|
||||||
field: current.offset
|
|
||||||
min: -3300
|
|
||||||
max: 3300
|
|
||||||
- name: current_meter_type
|
|
||||||
field: current.type
|
|
||||||
table: current_sensor
|
|
||||||
type: uint8_t
|
|
||||||
|
|
||||||
- name: PG_MIXER_CONFIG
|
- name: PG_MIXER_CONFIG
|
||||||
type: mixerConfig_t
|
type: mixerConfig_t
|
||||||
|
|
|
@ -722,7 +722,7 @@ static void osdFormatBatteryChargeSymbol(char *buff)
|
||||||
|
|
||||||
static void osdUpdateBatteryCapacityOrVoltageTextAttributes(textAttributes_t *attr)
|
static void osdUpdateBatteryCapacityOrVoltageTextAttributes(textAttributes_t *attr)
|
||||||
{
|
{
|
||||||
if ((getBatteryState() != BATTERY_NOT_PRESENT) && ((batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= batteryConfig()->capacity.warning - batteryConfig()->capacity.critical)) || ((!batteryUsesCapacityThresholds()) && (getBatteryVoltage() <= getBatteryWarningVoltage()))))
|
if ((getBatteryState() != BATTERY_NOT_PRESENT) && ((batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical)) || ((!batteryUsesCapacityThresholds()) && (getBatteryVoltage() <= getBatteryWarningVoltage()))))
|
||||||
TEXT_ATTRIBUTES_ADD_BLINK(*attr);
|
TEXT_ATTRIBUTES_ADD_BLINK(*attr);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1083,18 +1083,18 @@ static bool osdDrawSingleElement(uint8_t item)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_BATTERY_REMAINING_CAPACITY:
|
case OSD_BATTERY_REMAINING_CAPACITY:
|
||||||
buff[0] = (batteryConfig()->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH);
|
buff[0] = (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH);
|
||||||
|
|
||||||
if (batteryConfig()->capacity.value == 0)
|
if (currentBatteryProfile->capacity.value == 0)
|
||||||
tfp_sprintf(buff + 1, "NA");
|
tfp_sprintf(buff + 1, "NA");
|
||||||
else if (!batteryWasFullWhenPluggedIn())
|
else if (!batteryWasFullWhenPluggedIn())
|
||||||
tfp_sprintf(buff + 1, "NF");
|
tfp_sprintf(buff + 1, "NF");
|
||||||
else if (batteryConfig()->capacity.unit == BAT_CAPACITY_UNIT_MAH)
|
else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH)
|
||||||
tfp_sprintf(buff + 1, "%-4lu", getBatteryRemainingCapacity());
|
tfp_sprintf(buff + 1, "%-4lu", getBatteryRemainingCapacity());
|
||||||
else // batteryConfig()->capacity.unit == BAT_CAPACITY_UNIT_MWH
|
else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH
|
||||||
osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3);
|
osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3);
|
||||||
|
|
||||||
if ((getBatteryState() != BATTERY_NOT_PRESENT) && batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= batteryConfig()->capacity.warning - batteryConfig()->capacity.critical))
|
if ((getBatteryState() != BATTERY_NOT_PRESENT) && batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical))
|
||||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -39,3 +39,5 @@
|
||||||
#define MSP2_INAV_OSD_SET_ALARMS 0x2015
|
#define MSP2_INAV_OSD_SET_ALARMS 0x2015
|
||||||
#define MSP2_INAV_OSD_PREFERENCES 0x2016
|
#define MSP2_INAV_OSD_PREFERENCES 0x2016
|
||||||
#define MSP2_INAV_OSD_SET_PREFERENCES 0x2017
|
#define MSP2_INAV_OSD_SET_PREFERENCES 0x2017
|
||||||
|
|
||||||
|
#define MSP2_INAV_SELECT_BATTERY_PROFILE 0x2018
|
||||||
|
|
|
@ -17,12 +17,14 @@
|
||||||
|
|
||||||
#include "stdbool.h"
|
#include "stdbool.h"
|
||||||
#include "stdint.h"
|
#include "stdint.h"
|
||||||
|
#include "stdlib.h"
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
|
#include "config/config_reset.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
#include "config/parameter_group_ids.h"
|
#include "config/parameter_group_ids.h"
|
||||||
|
|
||||||
|
@ -62,6 +64,7 @@ static uint16_t batteryCriticalVoltage;
|
||||||
static uint32_t batteryRemainingCapacity = 0;
|
static uint32_t batteryRemainingCapacity = 0;
|
||||||
static bool batteryUseCapacityThresholds = false;
|
static bool batteryUseCapacityThresholds = false;
|
||||||
static bool batteryFullWhenPluggedIn = false;
|
static bool batteryFullWhenPluggedIn = false;
|
||||||
|
static bool profileAutoswitchDisable = false;
|
||||||
|
|
||||||
static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
||||||
static uint16_t vbatLatestADC = 0; // most recent unsmoothed raw reading from vbat ADC
|
static uint16_t vbatLatestADC = 0; // most recent unsmoothed raw reading from vbat ADC
|
||||||
|
@ -75,30 +78,45 @@ static int32_t mAhDrawn = 0; // milliampere hours drawn from the b
|
||||||
static int32_t mWhDrawn = 0; // energy (milliWatt hours) drawn from the battery since start
|
static int32_t mWhDrawn = 0; // energy (milliWatt hours) drawn from the battery since start
|
||||||
|
|
||||||
batteryState_e batteryState;
|
batteryState_e batteryState;
|
||||||
|
const batteryProfile_t *currentBatteryProfile;
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 2);
|
PG_REGISTER_ARRAY_WITH_RESET_FN(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles, PG_BATTERY_PROFILES, 0);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
|
void pgResetFn_batteryProfiles(batteryProfile_t *instance)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < MAX_BATTERY_PROFILE_COUNT; i++) {
|
||||||
|
RESET_CONFIG(batteryProfile_t, &instance[i],
|
||||||
|
.cells = 0,
|
||||||
|
|
||||||
.voltage = {
|
.voltage = {
|
||||||
.scale = VBAT_SCALE_DEFAULT,
|
.cellDetect = 430,
|
||||||
.cellDetect = 430,
|
.cellMax = 420,
|
||||||
.cellMax = 420,
|
.cellMin = 330,
|
||||||
.cellMin = 330,
|
.cellWarning = 350
|
||||||
.cellWarning = 350
|
},
|
||||||
},
|
|
||||||
|
.capacity = {
|
||||||
|
.value = 0,
|
||||||
|
.warning = 0,
|
||||||
|
.critical = 0,
|
||||||
|
.unit = BAT_CAPACITY_UNIT_MAH,
|
||||||
|
}
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
PG_REGISTER_WITH_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig, PG_BATTERY_METERS_CONFIG, 0);
|
||||||
|
|
||||||
|
PG_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig,
|
||||||
|
|
||||||
|
.profile_autoswitch = false,
|
||||||
|
|
||||||
|
.voltage_scale = VBAT_SCALE_DEFAULT,
|
||||||
|
|
||||||
.current = {
|
.current = {
|
||||||
.offset = CURRENT_METER_OFFSET,
|
.type = CURRENT_SENSOR_ADC,
|
||||||
.scale = CURRENT_METER_SCALE,
|
.scale = CURRENT_METER_SCALE,
|
||||||
.type = CURRENT_SENSOR_ADC
|
.offset = CURRENT_METER_OFFSET
|
||||||
},
|
|
||||||
|
|
||||||
.capacity = {
|
|
||||||
.value = 0,
|
|
||||||
.warning = 0,
|
|
||||||
.critical = 0,
|
|
||||||
.unit = BAT_CAPACITY_UNIT_MAH,
|
|
||||||
}
|
}
|
||||||
|
|
||||||
);
|
);
|
||||||
|
@ -107,13 +125,13 @@ uint16_t batteryAdcToVoltage(uint16_t src)
|
||||||
{
|
{
|
||||||
// calculate battery voltage based on ADC reading
|
// calculate battery voltage based on ADC reading
|
||||||
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
||||||
return((uint64_t)src * batteryConfig()->voltage.scale * ADCVREF / (0xFFF * 1000));
|
return((uint64_t)src * batteryMetersConfig()->voltage_scale * ADCVREF / (0xFFF * 1000));
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t currentSensorToCentiamps(uint16_t src)
|
int32_t currentSensorToCentiamps(uint16_t src)
|
||||||
{
|
{
|
||||||
int32_t microvolts = ((uint32_t)src * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryConfig()->current.offset * 1000;
|
int32_t microvolts = ((uint32_t)src * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryMetersConfig()->current.offset * 1000;
|
||||||
return microvolts / batteryConfig()->current.scale; // current in 0.01A steps
|
return microvolts / batteryMetersConfig()->current.scale; // current in 0.01A steps
|
||||||
}
|
}
|
||||||
|
|
||||||
void batteryInit(void)
|
void batteryInit(void)
|
||||||
|
@ -125,6 +143,53 @@ void batteryInit(void)
|
||||||
batteryCriticalVoltage = 0;
|
batteryCriticalVoltage = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// profileDetect() profile sorting compare function
|
||||||
|
static int profile_compare(profile_comp_t *a, profile_comp_t *b) {
|
||||||
|
if (a->max_voltage < b->max_voltage)
|
||||||
|
return -1;
|
||||||
|
else if (a->max_voltage > b->max_voltage)
|
||||||
|
return 1;
|
||||||
|
else
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Find profile matching plugged battery for profile_autoselect
|
||||||
|
static int8_t profileDetect() {
|
||||||
|
profile_comp_t profile_comp_array[MAX_BATTERY_PROFILE_COUNT];
|
||||||
|
|
||||||
|
// Prepare profile sort
|
||||||
|
for (uint8_t i = 0; i < MAX_BATTERY_PROFILE_COUNT; ++i) {
|
||||||
|
const batteryProfile_t *profile = batteryProfiles(i);
|
||||||
|
profile_comp_array[i].profile_index = i;
|
||||||
|
profile_comp_array[i].max_voltage = profile->cells * profile->voltage.cellDetect;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Sort profiles by max voltage
|
||||||
|
qsort(profile_comp_array, MAX_BATTERY_PROFILE_COUNT, sizeof(*profile_comp_array), (int (*)(const void *, const void *))profile_compare);
|
||||||
|
|
||||||
|
// Return index of the first profile where vbat <= profile_max_voltage
|
||||||
|
uint16_t vbatLatest = batteryAdcToVoltage(vbatLatestADC);
|
||||||
|
for (uint8_t i = 0; i < MAX_BATTERY_PROFILE_COUNT; ++i)
|
||||||
|
if ((profile_comp_array[i].max_voltage > 0) && (vbatLatest <= profile_comp_array[i].max_voltage))
|
||||||
|
return profile_comp_array[i].profile_index;
|
||||||
|
|
||||||
|
// No matching profile found
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setBatteryProfile(uint8_t profileIndex)
|
||||||
|
{
|
||||||
|
if (profileIndex >= MAX_BATTERY_PROFILE_COUNT) {
|
||||||
|
profileIndex = 0;
|
||||||
|
}
|
||||||
|
currentBatteryProfile = batteryProfiles(profileIndex);
|
||||||
|
}
|
||||||
|
|
||||||
|
void activateBatteryProfile(void)
|
||||||
|
{
|
||||||
|
batteryInit();
|
||||||
|
}
|
||||||
|
|
||||||
static void updateBatteryVoltage(timeUs_t timeDelta)
|
static void updateBatteryVoltage(timeUs_t timeDelta)
|
||||||
{
|
{
|
||||||
uint16_t vbatSample;
|
uint16_t vbatSample;
|
||||||
|
@ -152,17 +217,28 @@ void batteryUpdate(timeUs_t timeDelta)
|
||||||
delay(VBATT_STABLE_DELAY);
|
delay(VBATT_STABLE_DELAY);
|
||||||
updateBatteryVoltage(timeDelta);
|
updateBatteryVoltage(timeDelta);
|
||||||
|
|
||||||
unsigned cells = (batteryAdcToVoltage(vbatLatestADC) / batteryConfig()->voltage.cellDetect) + 1;
|
int8_t detectedProfileIndex = -1;
|
||||||
if (cells > 8) cells = 8; // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
if (batteryMetersConfig()->profile_autoswitch && (!profileAutoswitchDisable))
|
||||||
|
detectedProfileIndex = profileDetect();
|
||||||
|
|
||||||
batteryCellCount = cells;
|
if (detectedProfileIndex != -1) {
|
||||||
batteryFullVoltage = batteryCellCount * batteryConfig()->voltage.cellMax;
|
systemConfigMutable()->current_battery_profile_index = detectedProfileIndex;
|
||||||
batteryWarningVoltage = batteryCellCount * batteryConfig()->voltage.cellWarning;
|
setBatteryProfile(detectedProfileIndex);
|
||||||
batteryCriticalVoltage = batteryCellCount * batteryConfig()->voltage.cellMin;
|
batteryCellCount = currentBatteryProfile->cells;
|
||||||
|
} else if (currentBatteryProfile->cells > 0)
|
||||||
|
batteryCellCount = currentBatteryProfile->cells;
|
||||||
|
else {
|
||||||
|
batteryCellCount = (batteryAdcToVoltage(vbatLatestADC) / currentBatteryProfile->voltage.cellDetect) + 1;
|
||||||
|
if (batteryCellCount > 8) batteryCellCount = 8; // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
||||||
|
}
|
||||||
|
|
||||||
batteryFullWhenPluggedIn = batteryAdcToVoltage(vbatLatestADC) >= (batteryFullVoltage - cells * VBATT_CELL_FULL_MAX_DIFF);
|
batteryFullVoltage = batteryCellCount * currentBatteryProfile->voltage.cellMax;
|
||||||
batteryUseCapacityThresholds = feature(FEATURE_CURRENT_METER) && batteryFullWhenPluggedIn && (batteryConfig()->capacity.value > 0) &&
|
batteryWarningVoltage = batteryCellCount * currentBatteryProfile->voltage.cellWarning;
|
||||||
(batteryConfig()->capacity.warning > 0) && (batteryConfig()->capacity.critical > 0);
|
batteryCriticalVoltage = batteryCellCount * currentBatteryProfile->voltage.cellMin;
|
||||||
|
|
||||||
|
batteryFullWhenPluggedIn = batteryAdcToVoltage(vbatLatestADC) >= (batteryFullVoltage - batteryCellCount * VBATT_CELL_FULL_MAX_DIFF);
|
||||||
|
batteryUseCapacityThresholds = feature(FEATURE_CURRENT_METER) && batteryFullWhenPluggedIn && (currentBatteryProfile->capacity.value > 0) &&
|
||||||
|
(currentBatteryProfile->capacity.warning > 0) && (currentBatteryProfile->capacity.critical > 0);
|
||||||
|
|
||||||
}
|
}
|
||||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD */
|
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD */
|
||||||
|
@ -175,16 +251,16 @@ void batteryUpdate(timeUs_t timeDelta)
|
||||||
|
|
||||||
if (batteryState != BATTERY_NOT_PRESENT) {
|
if (batteryState != BATTERY_NOT_PRESENT) {
|
||||||
|
|
||||||
if ((batteryConfig()->capacity.value > 0) && batteryFullWhenPluggedIn) {
|
if ((currentBatteryProfile->capacity.value > 0) && batteryFullWhenPluggedIn) {
|
||||||
uint32_t capacityDiffBetweenFullAndEmpty = batteryConfig()->capacity.value - batteryConfig()->capacity.critical;
|
uint32_t capacityDiffBetweenFullAndEmpty = currentBatteryProfile->capacity.value - currentBatteryProfile->capacity.critical;
|
||||||
int32_t drawn = (batteryConfig()->capacity.unit == BAT_CAPACITY_UNIT_MWH ? mWhDrawn : mAhDrawn);
|
int32_t drawn = (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH ? mWhDrawn : mAhDrawn);
|
||||||
batteryRemainingCapacity = (drawn > (int32_t)capacityDiffBetweenFullAndEmpty ? 0 : capacityDiffBetweenFullAndEmpty - drawn);
|
batteryRemainingCapacity = (drawn > (int32_t)capacityDiffBetweenFullAndEmpty ? 0 : capacityDiffBetweenFullAndEmpty - drawn);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (batteryUseCapacityThresholds) {
|
if (batteryUseCapacityThresholds) {
|
||||||
if (batteryRemainingCapacity == 0)
|
if (batteryRemainingCapacity == 0)
|
||||||
batteryState = BATTERY_CRITICAL;
|
batteryState = BATTERY_CRITICAL;
|
||||||
else if (batteryRemainingCapacity <= batteryConfig()->capacity.warning - batteryConfig()->capacity.critical)
|
else if (batteryRemainingCapacity <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical)
|
||||||
batteryState = BATTERY_WARNING;
|
batteryState = BATTERY_WARNING;
|
||||||
} else {
|
} else {
|
||||||
switch (batteryState)
|
switch (batteryState)
|
||||||
|
@ -288,7 +364,7 @@ uint32_t getBatteryRemainingCapacity(void)
|
||||||
|
|
||||||
bool isAmperageConfigured(void)
|
bool isAmperageConfigured(void)
|
||||||
{
|
{
|
||||||
return feature(FEATURE_CURRENT_METER) && batteryConfig()->current.type != CURRENT_SENSOR_NONE;
|
return feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type != CURRENT_SENSOR_NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t getAmperage(void)
|
int32_t getAmperage(void)
|
||||||
|
@ -322,19 +398,19 @@ void currentMeterUpdate(timeUs_t timeDelta)
|
||||||
static pt1Filter_t amperageFilterState;
|
static pt1Filter_t amperageFilterState;
|
||||||
static int64_t mAhdrawnRaw = 0;
|
static int64_t mAhdrawnRaw = 0;
|
||||||
|
|
||||||
switch (batteryConfig()->current.type) {
|
switch (batteryMetersConfig()->current.type) {
|
||||||
case CURRENT_SENSOR_ADC:
|
case CURRENT_SENSOR_ADC:
|
||||||
amperageLatestADC = adcGetChannel(ADC_CURRENT);
|
amperageLatestADC = adcGetChannel(ADC_CURRENT);
|
||||||
amperageLatestADC = pt1FilterApply4(&erageFilterState, amperageLatestADC, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
amperageLatestADC = pt1FilterApply4(&erageFilterState, amperageLatestADC, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
||||||
amperage = currentSensorToCentiamps(amperageLatestADC);
|
amperage = currentSensorToCentiamps(amperageLatestADC);
|
||||||
break;
|
break;
|
||||||
case CURRENT_SENSOR_VIRTUAL:
|
case CURRENT_SENSOR_VIRTUAL:
|
||||||
amperage = batteryConfig()->current.offset;
|
amperage = batteryMetersConfig()->current.offset;
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
throttleStatus_e throttleStatus = calculateThrottleStatus();
|
throttleStatus_e throttleStatus = calculateThrottleStatus();
|
||||||
int32_t throttleOffset = ((throttleStatus == THROTTLE_LOW) && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000;
|
int32_t throttleOffset = ((throttleStatus == THROTTLE_LOW) && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000;
|
||||||
int32_t throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
|
int32_t throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
|
||||||
amperage += throttleFactor * batteryConfig()->current.scale / 1000;
|
amperage += throttleFactor * batteryMetersConfig()->current.scale / 1000;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case CURRENT_SENSOR_NONE:
|
case CURRENT_SENSOR_NONE:
|
||||||
|
@ -396,9 +472,13 @@ uint8_t calculateBatteryPercentage(void)
|
||||||
if (batteryState == BATTERY_NOT_PRESENT)
|
if (batteryState == BATTERY_NOT_PRESENT)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
if (batteryFullWhenPluggedIn && feature(FEATURE_CURRENT_METER) && (batteryConfig()->capacity.value > 0) && (batteryConfig()->capacity.critical > 0)) {
|
if (batteryFullWhenPluggedIn && feature(FEATURE_CURRENT_METER) && (currentBatteryProfile->capacity.value > 0) && (currentBatteryProfile->capacity.critical > 0)) {
|
||||||
uint32_t capacityDiffBetweenFullAndEmpty = batteryConfig()->capacity.value - batteryConfig()->capacity.critical;
|
uint32_t capacityDiffBetweenFullAndEmpty = currentBatteryProfile->capacity.value - currentBatteryProfile->capacity.critical;
|
||||||
return constrain(batteryRemainingCapacity * 100 / capacityDiffBetweenFullAndEmpty, 0, 100);
|
return constrain(batteryRemainingCapacity * 100 / capacityDiffBetweenFullAndEmpty, 0, 100);
|
||||||
} else
|
} else
|
||||||
return constrain((vbat - batteryCriticalVoltage) * 100L / (batteryFullVoltage - batteryCriticalVoltage), 0, 100);
|
return constrain((vbat - batteryCriticalVoltage) * 100L / (batteryFullVoltage - batteryCriticalVoltage), 0, 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void batteryDisableProfileAutoswitch(void) {
|
||||||
|
profileAutoswitchDisable = true;
|
||||||
|
}
|
||||||
|
|
|
@ -34,6 +34,10 @@
|
||||||
#define CURRENT_METER_OFFSET 0
|
#define CURRENT_METER_OFFSET 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAX_BATTERY_PROFILE_COUNT
|
||||||
|
#define MAX_BATTERY_PROFILE_COUNT 3
|
||||||
|
#endif
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
CURRENT_SENSOR_NONE = 0,
|
CURRENT_SENSOR_NONE = 0,
|
||||||
CURRENT_SENSOR_ADC,
|
CURRENT_SENSOR_ADC,
|
||||||
|
@ -46,15 +50,16 @@ typedef enum {
|
||||||
BAT_CAPACITY_UNIT_MWH,
|
BAT_CAPACITY_UNIT_MWH,
|
||||||
} batCapacityUnit_e;
|
} batCapacityUnit_e;
|
||||||
|
|
||||||
typedef struct batteryConfig_s {
|
typedef struct {
|
||||||
|
uint8_t profile_index;
|
||||||
|
uint16_t max_voltage;
|
||||||
|
} profile_comp_t;
|
||||||
|
|
||||||
struct {
|
typedef struct batteryMetersConfig_s {
|
||||||
uint16_t scale; // adjust this to match battery voltage to reported value
|
|
||||||
uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V)
|
bool profile_autoswitch;
|
||||||
uint16_t cellMax; // maximum voltage per cell, used for full battery detection and battery gauge voltage in 0.01V units, default is 424 (4.24V)
|
|
||||||
uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
|
uint16_t voltage_scale;
|
||||||
uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)
|
|
||||||
} voltage;
|
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||||
|
@ -62,6 +67,19 @@ typedef struct batteryConfig_s {
|
||||||
currentSensor_e type; // type of current meter used, either ADC or virtual
|
currentSensor_e type; // type of current meter used, either ADC or virtual
|
||||||
} current;
|
} current;
|
||||||
|
|
||||||
|
} batteryMetersConfig_t;
|
||||||
|
|
||||||
|
typedef struct batteryProfile_s {
|
||||||
|
|
||||||
|
uint8_t cells;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V)
|
||||||
|
uint16_t cellMax; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 421 (4.21V)
|
||||||
|
uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
|
||||||
|
uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)
|
||||||
|
} voltage;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
uint32_t value; // mAh or mWh (see capacity.unit)
|
uint32_t value; // mAh or mWh (see capacity.unit)
|
||||||
uint32_t warning; // mAh or mWh (see capacity.unit)
|
uint32_t warning; // mAh or mWh (see capacity.unit)
|
||||||
|
@ -69,9 +87,12 @@ typedef struct batteryConfig_s {
|
||||||
batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical
|
batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical
|
||||||
} capacity;
|
} capacity;
|
||||||
|
|
||||||
} batteryConfig_t;
|
} batteryProfile_t;
|
||||||
|
|
||||||
PG_DECLARE(batteryConfig_t, batteryConfig);
|
PG_DECLARE(batteryMetersConfig_t, batteryMetersConfig);
|
||||||
|
PG_DECLARE_ARRAY(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles);
|
||||||
|
|
||||||
|
extern const batteryProfile_t *currentBatteryProfile;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
BATTERY_OK = 0,
|
BATTERY_OK = 0,
|
||||||
|
@ -80,11 +101,15 @@ typedef enum {
|
||||||
BATTERY_NOT_PRESENT
|
BATTERY_NOT_PRESENT
|
||||||
} batteryState_e;
|
} batteryState_e;
|
||||||
|
|
||||||
|
|
||||||
uint16_t batteryAdcToVoltage(uint16_t src);
|
uint16_t batteryAdcToVoltage(uint16_t src);
|
||||||
batteryState_e getBatteryState(void);
|
batteryState_e getBatteryState(void);
|
||||||
bool batteryWasFullWhenPluggedIn(void);
|
bool batteryWasFullWhenPluggedIn(void);
|
||||||
bool batteryUsesCapacityThresholds(void);
|
bool batteryUsesCapacityThresholds(void);
|
||||||
void batteryInit(void);
|
void batteryInit(void);
|
||||||
|
void setBatteryProfile(uint8_t profileIndex);
|
||||||
|
void activateBatteryProfile(void);
|
||||||
|
void batteryDisableProfileAutoswitch(void);
|
||||||
|
|
||||||
bool isBatteryVoltageConfigured(void);
|
bool isBatteryVoltageConfigured(void);
|
||||||
uint16_t getBatteryVoltage(void);
|
uint16_t getBatteryVoltage(void);
|
||||||
|
|
|
@ -49,7 +49,7 @@ void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
|
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
|
||||||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||||
batteryConfigMutable()->voltage.scale = 200;
|
batteryMetersConfigMutable()->voltage_scale = 200;
|
||||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||||
|
|
||||||
|
|
|
@ -56,8 +56,8 @@
|
||||||
void targetConfiguration(void)
|
void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||||
batteryConfigMutable()->current.offset = CURRENTOFFSET;
|
batteryMetersConfigMutable()->current.offset = CURRENTOFFSET;
|
||||||
batteryConfigMutable()->current.scale = CURRENTSCALE;
|
batteryMetersConfigMutable()->current.scale = CURRENTSCALE;
|
||||||
|
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||||
|
|
|
@ -58,8 +58,8 @@
|
||||||
void targetConfiguration(void)
|
void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||||
batteryConfigMutable()->current.offset = CURRENTOFFSET;
|
batteryMetersConfigMutable()->current.offset = CURRENTOFFSET;
|
||||||
batteryConfigMutable()->current.scale = CURRENTSCALE;
|
batteryMetersConfigMutable()->current.scale = CURRENTSCALE;
|
||||||
|
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
|
|
|
@ -25,6 +25,6 @@
|
||||||
|
|
||||||
void targetConfiguration(void)
|
void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
batteryConfigMutable()->current.scale = 20;
|
batteryMetersConfigMutable()->current.scale = 20;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -33,6 +33,6 @@ void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
rxConfigMutable()->halfDuplex = false;
|
rxConfigMutable()->halfDuplex = false;
|
||||||
telemetryConfigMutable()->smartportUartUnidirectional = true;
|
telemetryConfigMutable()->smartportUartUnidirectional = true;
|
||||||
batteryConfigMutable()->current.scale = CURRENTSCALE;
|
batteryMetersConfigMutable()->current.scale = CURRENTSCALE;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -196,7 +196,7 @@ static void sendThrottleOrBatterySizeAsRpm(void)
|
||||||
throttleForRPM = 0;
|
throttleForRPM = 0;
|
||||||
serialize16(throttleForRPM);
|
serialize16(throttleForRPM);
|
||||||
} else {
|
} else {
|
||||||
serialize16((batteryConfig()->capacity.value / BLADE_NUMBER_DIVIDER));
|
serialize16((currentBatteryProfile->capacity.value / BLADE_NUMBER_DIVIDER));
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -243,7 +243,7 @@ void initIbusTelemetry(void) {
|
||||||
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE1_FLIGHT_MODE, IBUS_MEAS_VALUE_MODE);
|
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE1_FLIGHT_MODE, IBUS_MEAS_VALUE_MODE);
|
||||||
}
|
}
|
||||||
if (type == 6 || type == 7 || type == 8) {
|
if (type == 6 || type == 7 || type == 8) {
|
||||||
if (batteryConfig()->current.type == CURRENT_SENSOR_VIRTUAL)
|
if (batteryMetersConfig()->current.type == CURRENT_SENSOR_VIRTUAL)
|
||||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_FUEL, IBUS_MEAS_VALUE_FUEL);
|
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_FUEL, IBUS_MEAS_VALUE_FUEL);
|
||||||
else changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_BAT_CURR, IBUS_MEAS_VALUE_CURRENT);
|
else changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_BAT_CURR, IBUS_MEAS_VALUE_CURRENT);
|
||||||
changeTypeIbusTelemetry(4, IBUS_MEAS_TYPE1_CMP_HEAD, IBUS_MEAS_VALUE_HEADING);
|
changeTypeIbusTelemetry(4, IBUS_MEAS_TYPE1_CMP_HEAD, IBUS_MEAS_VALUE_HEADING);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue