1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-27 02:05:26 +03:00

Added batteryConfig parameter group

This commit is contained in:
Martin Budden 2017-01-07 13:03:09 +00:00
parent 35b17c5507
commit ec22adcf74
10 changed files with 77 additions and 84 deletions

View file

@ -93,8 +93,8 @@ static OSD_Entry menuMiscEntries[]=
//!!TODO - fix up CMS menu entries to use parameter groups //!!TODO - fix up CMS menu entries to use parameter groups
// { "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig()->minthrottle, 1000, 2000, 1 }, 0 }, // { "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig()->minthrottle, 1000, 2000, 1 }, 0 },
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig()->vbatscale, 1, 250, 1 }, 0 }, // { "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig()->vbatscale, 1, 250, 1 }, 0 },
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig()->vbatmaxcellvoltage, 10, 50, 1 }, 0 }, // { "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig()->vbatmaxcellvoltage, 10, 50, 1 }, 0 },
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0}, { "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
{ "BACK", OME_Back, NULL, NULL, 0}, { "BACK", OME_Back, NULL, NULL, 0},

View file

@ -47,9 +47,6 @@
#include "io/serial.h" #include "io/serial.h"
#include "io/servos.h" #include "io/servos.h"
#include "sensors/sensors.h"
#include "sensors/battery.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#define flight3DConfig(x) (&masterConfig.flight3DConfig) #define flight3DConfig(x) (&masterConfig.flight3DConfig)
@ -60,8 +57,6 @@
#define servoMixerConfigMutable(x) (&masterConfig.servoMixerConfig) #define servoMixerConfigMutable(x) (&masterConfig.servoMixerConfig)
#define imuConfig(x) (&masterConfig.imuConfig) #define imuConfig(x) (&masterConfig.imuConfig)
#define imuConfigMutable(x) (&masterConfig.imuConfig) #define imuConfigMutable(x) (&masterConfig.imuConfig)
#define batteryConfig(x) (&masterConfig.batteryConfig)
#define batteryConfigMutable(x) (&masterConfig.batteryConfig)
#define rcControlsConfig(x) (&masterConfig.rcControlsConfig) #define rcControlsConfig(x) (&masterConfig.rcControlsConfig)
#define rcControlsConfigMutable(x) (&masterConfig.rcControlsConfig) #define rcControlsConfigMutable(x) (&masterConfig.rcControlsConfig)
#define gpsConfig(x) (&masterConfig.gpsConfig) #define gpsConfig(x) (&masterConfig.gpsConfig)
@ -132,8 +127,6 @@ typedef struct master_s {
imuConfig_t imuConfig; imuConfig_t imuConfig;
batteryConfig_t batteryConfig;
#ifdef GPS #ifdef GPS
gpsConfig_t gpsConfig; gpsConfig_t gpsConfig;
#endif #endif

View file

@ -22,11 +22,11 @@
#define PG_MOTOR_MIXER 4 #define PG_MOTOR_MIXER 4
#define PG_BLACKBOX_CONFIG 5 #define PG_BLACKBOX_CONFIG 5
#define PG_MOTOR_CONFIG 6 #define PG_MOTOR_CONFIG 6
//#define PG_SENSOR_SELECTION_CONFIG 7 //#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in iNav
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 //#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav
//#define PG_SENSOR_TRIMS 9 //#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_CONFIG 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

View file

@ -266,20 +266,6 @@ void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
} }
#endif #endif
void resetBatteryConfig(batteryConfig_t *batteryConfig)
{
batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
batteryConfig->vbatmaxcellvoltage = 43;
batteryConfig->vbatmincellvoltage = 33;
batteryConfig->vbatwarningcellvoltage = 35;
batteryConfig->currentMeterOffset = 0;
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
batteryConfig->batteryCapacity = 0;
batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
}
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
#define FIRST_PORT_INDEX 1 #define FIRST_PORT_INDEX 1
#define SECOND_PORT_INDEX 0 #define SECOND_PORT_INDEX 0
@ -429,8 +415,6 @@ void createDefaultConfig(master_t *config)
config->imuConfig.dcm_ki_mag = 0; // 0.00 * 10000 config->imuConfig.dcm_ki_mag = 0; // 0.00 * 10000
config->imuConfig.small_angle = 25; config->imuConfig.small_angle = 25;
resetBatteryConfig(&config->batteryConfig);
#ifdef TELEMETRY #ifdef TELEMETRY
resetTelemetryConfig(&config->telemetryConfig); resetTelemetryConfig(&config->telemetryConfig);
#endif #endif

View file

@ -625,7 +625,7 @@ void init(void)
// Now that everything has powered up the voltage and cell count be determined. // Now that everything has powered up the voltage and cell count be determined.
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER)) if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
batteryInit(&masterConfig.batteryConfig); batteryInit();
#ifdef CJMCU #ifdef CJMCU
LED2_ON; LED2_ON;

View file

@ -577,7 +577,7 @@ static const clivalue_t valueTable[] = {
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 32000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, motorPwmRate) }, { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 32000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, motorPwmRate) },
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, motorPwmProtocol) }, { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, motorPwmProtocol) },
// PG_FAILSAFE_CONFIG // PG_FAILSAFE_CONFIG
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_delay) }, { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_delay) },
{ "failsafe_recovery_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_recovery_delay) }, { "failsafe_recovery_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_recovery_delay) },
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_off_delay) }, { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_off_delay) },
@ -595,6 +595,18 @@ static const clivalue_t valueTable[] = {
#ifdef USE_SERVOS #ifdef USE_SERVOS
{ "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GIMBAL_MODE }, PG_GIMBAL_CONFIG, offsetof(gimbalConfig_t, mode) }, { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GIMBAL_MODE }, PG_GIMBAL_CONFIG, offsetof(gimbalConfig_t, mode) },
#endif #endif
// PG_BATTERY_CONFIG
{ "battery_capacity", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryCapacity) },
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatscale) },
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmaxcellvoltage) },
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) },
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatwarningcellvoltage) },
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -10000, 10000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterScale) },
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 3300 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterOffset) },
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, multiwiiCurrentMeterOutput) },
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_SENSOR }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterType) },
}; };
#else #else
@ -736,16 +748,6 @@ const clivalue_t valueTable[] = {
#endif #endif
#endif #endif
{ "battery_capacity", VAR_UINT16 | MASTER_VALUE, &batteryConfig()->batteryCapacity, .config.minmax = { 0, 20000 } },
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->vbatmincellvoltage, .config.minmax = { 10, 50 } },
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &batteryConfig()->currentMeterScale, .config.minmax = { -10000, 10000 } },
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &batteryConfig()->currentMeterOffset, .config.minmax = { 0, 3300 } },
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_kp_acc, .config.minmax = { 0, 65535 } }, { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_kp_acc, .config.minmax = { 0, 65535 } },
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_ki_acc, .config.minmax = { 0, 65535 } }, { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_ki_acc, .config.minmax = { 0, 65535 } },
{ "imu_dcm_kp_mag", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_kp_mag, .config.minmax = { 0, 65535 } }, { "imu_dcm_kp_mag", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_kp_mag, .config.minmax = { 0, 65535 } },

View file

@ -33,49 +33,46 @@
// XXX Must review what's included // XXX Must review what's included
#include "build/debug.h"
#include "build/version.h" #include "build/version.h"
#include "common/utils.h" #include "cms/cms.h"
#include "cms/cms_types.h"
#include "drivers/system.h" #include "cms/cms_menu_osd.h"
#include "common/axis.h" #include "common/axis.h"
#include "io/gimbal.h" #include "common/printf.h"
#include "common/utils.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#include "drivers/display.h" #include "drivers/display.h"
#include "drivers/max7456.h"
#include "cms/cms.h" #include "drivers/max7456_symbols.h"
#include "cms/cms_types.h" #include "drivers/system.h"
#include "cms/cms_menu_osd.h"
#include "io/displayport_max7456.h" #include "io/displayport_max7456.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gimbal.h"
#include "io/osd.h" #include "io/osd.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
#include "drivers/max7456.h"
#include "drivers/max7456_symbols.h"
#include "common/printf.h"
#include "build/debug.h"
// Character coordinate and attributes // Character coordinate and attributes
#define OSD_POS(x,y) (x | (y << 5)) #define OSD_POS(x,y) (x | (y << 5))

View file

@ -23,6 +23,9 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/filter.h" #include "common/filter.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/adc.h" #include "drivers/adc.h"
#include "drivers/system.h" #include "drivers/system.h"
@ -54,15 +57,28 @@ uint16_t amperageLatestADC = 0; // most recent raw reading from current ADC
int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A) int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
batteryConfig_t *batteryConfig;
static batteryState_e batteryState; static batteryState_e batteryState;
PG_REGISTER_WITH_RESET_TEMPLATE(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
.vbatscale = VBAT_SCALE_DEFAULT,
.vbatresdivval = VBAT_RESDIVVAL_DEFAULT,
.vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT,
.vbatmaxcellvoltage = 43,
.vbatmincellvoltage = 33,
.vbatwarningcellvoltage = 35,
.currentMeterOffset = 0,
.currentMeterScale = 400, // for Allegro ACS758LCB-100U (40mV/A)
.batteryCapacity = 0,
.currentMeterType = CURRENT_SENSOR_ADC
);
uint16_t batteryAdcToVoltage(uint16_t src) 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.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V // result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
return ((((uint32_t)src * batteryConfig->vbatscale * 33 + (0xFFF * 5)) / (0xFFF * batteryConfig->vbatresdivval))/batteryConfig->vbatresdivmultiplier); return ((((uint32_t)src * batteryConfig()->vbatscale * 33 + (0xFFF * 5)) / (0xFFF * batteryConfig()->vbatresdivval))/batteryConfig()->vbatresdivmultiplier);
} }
static void updateBatteryVoltage(uint32_t vbatTimeDelta) static void updateBatteryVoltage(uint32_t vbatTimeDelta)
@ -96,14 +112,14 @@ void updateBattery(uint32_t vbatTimeDelta)
delay(VBATTERY_STABLE_DELAY); delay(VBATTERY_STABLE_DELAY);
updateBatteryVoltage(vbatTimeDelta); updateBatteryVoltage(vbatTimeDelta);
unsigned cells = (batteryAdcToVoltage(vbatLatestADC) / batteryConfig->vbatmaxcellvoltage) + 1; unsigned cells = (batteryAdcToVoltage(vbatLatestADC) / batteryConfig()->vbatmaxcellvoltage) + 1;
if (cells > 8) { if (cells > 8) {
// something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells) // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
cells = 8; cells = 8;
} }
batteryCellCount = cells; batteryCellCount = cells;
batteryWarningVoltage = batteryCellCount * batteryConfig->vbatwarningcellvoltage; batteryWarningVoltage = batteryCellCount * batteryConfig()->vbatwarningcellvoltage;
batteryCriticalVoltage = batteryCellCount * batteryConfig->vbatmincellvoltage; batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
} }
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD_MV */ /* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD_MV */
else if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD_MV) else if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD_MV)
@ -157,9 +173,8 @@ const char * getBatteryStateString(void)
return batteryStateStrings[batteryState]; return batteryStateStrings[batteryState];
} }
void batteryInit(batteryConfig_t *initialBatteryConfig) void batteryInit(void)
{ {
batteryConfig = initialBatteryConfig;
batteryState = BATTERY_NOT_PRESENT; batteryState = BATTERY_NOT_PRESENT;
batteryCellCount = 1; batteryCellCount = 1;
batteryWarningVoltage = 0; batteryWarningVoltage = 0;
@ -172,9 +187,9 @@ int32_t currentSensorToCentiamps(uint16_t src)
int32_t millivolts; int32_t millivolts;
millivolts = ((uint32_t)src * ADCVREF) / 4096; millivolts = ((uint32_t)src * ADCVREF) / 4096;
millivolts -= batteryConfig->currentMeterOffset; millivolts -= batteryConfig()->currentMeterOffset;
return (millivolts * 1000) / (int32_t)batteryConfig->currentMeterScale; // current in 0.01A steps return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps
} }
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle) void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
@ -184,20 +199,20 @@ void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
int32_t throttleFactor = 0; int32_t throttleFactor = 0;
int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000; int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
switch(batteryConfig->currentMeterType) { switch(batteryConfig()->currentMeterType) {
case CURRENT_SENSOR_ADC: case CURRENT_SENSOR_ADC:
amperageRaw -= amperageRaw / 8; amperageRaw -= amperageRaw / 8;
amperageRaw += (amperageLatestADC = adcGetChannel(ADC_CURRENT)); amperageRaw += (amperageLatestADC = adcGetChannel(ADC_CURRENT));
amperage = currentSensorToCentiamps(amperageRaw / 8); amperage = currentSensorToCentiamps(amperageRaw / 8);
break; break;
case CURRENT_SENSOR_VIRTUAL: case CURRENT_SENSOR_VIRTUAL:
amperage = (int32_t)batteryConfig->currentMeterOffset; amperage = (int32_t)batteryConfig()->currentMeterOffset;
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle); throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle);
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
throttleOffset = 0; throttleOffset = 0;
throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
amperage += throttleFactor * (int32_t)batteryConfig->currentMeterScale / 1000; amperage += throttleFactor * (int32_t)batteryConfig()->currentMeterScale / 1000;
} }
break; break;
case CURRENT_SENSOR_NONE: case CURRENT_SENSOR_NONE:
@ -211,12 +226,12 @@ void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
uint8_t calculateBatteryPercentage(void) uint8_t calculateBatteryPercentage(void)
{ {
return constrain((((uint32_t)vbat - (batteryConfig->vbatmincellvoltage * batteryCellCount)) * 100) / ((batteryConfig->vbatmaxcellvoltage - batteryConfig->vbatmincellvoltage) * batteryCellCount), 0, 100); return constrain((((uint32_t)vbat - (batteryConfig()->vbatmincellvoltage * batteryCellCount)) * 100) / ((batteryConfig()->vbatmaxcellvoltage - batteryConfig()->vbatmincellvoltage) * batteryCellCount), 0, 100);
} }
uint8_t calculateBatteryCapacityRemainingPercentage(void) uint8_t calculateBatteryCapacityRemainingPercentage(void)
{ {
uint16_t batteryCapacity = batteryConfig->batteryCapacity; uint16_t batteryCapacity = batteryConfig()->batteryCapacity;
return constrain((batteryCapacity - constrain(mAhDrawn, 0, 0xFFFF)) * 100.0f / batteryCapacity , 0, 100); return constrain((batteryCapacity - constrain(mAhDrawn, 0, 0xFFFF)) * 100.0f / batteryCapacity , 0, 100);
} }

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "config/parameter_group.h"
#ifndef VBAT_SCALE_DEFAULT #ifndef VBAT_SCALE_DEFAULT
#define VBAT_SCALE_DEFAULT 110 #define VBAT_SCALE_DEFAULT 110
#endif #endif
@ -49,6 +51,8 @@ typedef struct batteryConfig_s {
uint16_t batteryCapacity; // mAh uint16_t batteryCapacity; // mAh
} batteryConfig_t; } batteryConfig_t;
PG_DECLARE(batteryConfig_t, batteryConfig);
typedef enum { typedef enum {
BATTERY_OK = 0, BATTERY_OK = 0,
BATTERY_WARNING, BATTERY_WARNING,
@ -69,7 +73,7 @@ uint16_t batteryAdcToVoltage(uint16_t src);
batteryState_e getBatteryState(void); batteryState_e getBatteryState(void);
const char * getBatteryStateString(void); const char * getBatteryStateString(void);
void updateBattery(uint32_t vbatTimeDelta); void updateBattery(uint32_t vbatTimeDelta);
void batteryInit(batteryConfig_t *initialBatteryConfig); void batteryInit(void);
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle); void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle);
int32_t currentMeterToCentiamps(uint16_t src); int32_t currentMeterToCentiamps(uint16_t src);

View file

@ -69,8 +69,6 @@ static bool frskyTelemetryEnabled = false;
static portSharing_e frskyPortSharing; static portSharing_e frskyPortSharing;
extern batteryConfig_t *batteryConfig;
extern int16_t telemTemperature1; // FIXME dependency on mw.c extern int16_t telemTemperature1; // FIXME dependency on mw.c
#define CYCLETIME 125 #define CYCLETIME 125
@ -200,7 +198,7 @@ static void sendThrottleOrBatterySizeAsRpm(uint16_t deadband3d_throttle)
throttleForRPM = 0; throttleForRPM = 0;
serialize16(throttleForRPM); serialize16(throttleForRPM);
} else { } else {
serialize16((batteryConfig->batteryCapacity / BLADE_NUMBER_DIVIDER)); serialize16((batteryConfig()->batteryCapacity / BLADE_NUMBER_DIVIDER));
} }
} }
@ -429,7 +427,7 @@ static void sendFuelLevel(void)
{ {
sendDataHead(ID_FUEL_LEVEL); sendDataHead(ID_FUEL_LEVEL);
if (batteryConfig->batteryCapacity > 0) { if (batteryConfig()->batteryCapacity > 0) {
serialize16((uint16_t)calculateBatteryCapacityRemainingPercentage()); serialize16((uint16_t)calculateBatteryCapacityRemainingPercentage());
} else { } else {
serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF));