Add virtual current sensor support

Virtual current sensor calculates an estimate of current based on
throttle position, current_meter_scale, and current_meter_offset.
Documentation to follow later.
This commit is contained in:
tracernz 2015-01-16 22:00:45 +13:00
parent b893e457f1
commit 999f0ce002
4 changed files with 38 additions and 7 deletions

View File

@ -108,7 +108,7 @@ profile_t *currentProfile;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
static const uint8_t EEPROM_CONF_VERSION = 88;
static const uint8_t EEPROM_CONF_VERSION = 89;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{

View File

@ -305,7 +305,7 @@ const clivalue_t valueTable[] = {
{ "current_meter_scale", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, 1, 10000 },
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 1650 },
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterType, 0, CURRENT_SENSOR_MAX },
{ "align_gyro", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
{ "align_acc", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },

View File

@ -20,9 +20,14 @@
#include "common/maths.h"
#include "config/runtime_config.h"
#include "drivers/adc.h"
#include "drivers/system.h"
#include "rx/rx.h"
#include "io/rc_controls.h"
#include "sensors/battery.h"
// Battery monitoring stuff
@ -112,13 +117,29 @@ void updateCurrentMeter(int32_t lastUpdateAt)
{
static int32_t amperageRaw = 0;
static int64_t mAhdrawnRaw = 0;
int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
int32_t throttleFactor = 0;
amperageRaw -= amperageRaw / 8;
amperageRaw += adcGetChannel(ADC_CURRENT);
amperage = currentSensorToCentiamps(amperageRaw / 8);
switch(batteryConfig->currentMeterType) {
case CURRENT_SENSOR_ADC:
amperageRaw -= amperageRaw / 8;
amperageRaw += adcGetChannel(ADC_CURRENT);
amperage = currentSensorToCentiamps(amperageRaw / 8);
break;
case CURRENT_SENSOR_VIRTUAL:
amperage = (int32_t)batteryConfig->currentMeterOffset;
if(ARMING_FLAG(ARMED)) {
throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
amperage += throttleFactor * (int32_t)batteryConfig->currentMeterScale / 1000;
}
break;
case CURRENT_SENSOR_NONE:
amperage = 0;
break;
}
mAhdrawnRaw += (amperage * lastUpdateAt) / 1000;
mAhDrawn = mAhdrawnRaw / (3600 * 100);
mAhdrawnRaw += (amperage * lastUpdateAt) / 1000;
mAhDrawn = mAhdrawnRaw / (3600 * 100);
}
uint8_t calculateBatteryPercentage(void)

View File

@ -20,6 +20,15 @@
#define VBAT_SCALE_DEFAULT 110
#define VBAT_SCALE_MIN 0
#define VBAT_SCALE_MAX 255
#define VIRTUAL_CURRENT_MIN 0
#define VIRTUAL_CURRENT_MAX 0xffff
typedef enum {
CURRENT_SENSOR_NONE = 0,
CURRENT_SENSOR_ADC,
CURRENT_SENSOR_VIRTUAL,
CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL
} currentSensor_e;
typedef struct batteryConfig_s {
uint8_t vbatscale; // adjust this to match battery voltage to reported value
@ -29,6 +38,7 @@ typedef struct batteryConfig_s {
uint16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
uint16_t currentMeterOffset; // offset of the current sensor in millivolt steps
currentSensor_e currentMeterType; // type of current meter used, either ADC or virtual
// FIXME this doesn't belong in here since it's a concern of MSP, not of the battery code.
uint8_t multiwiiCurrentMeterOutput; // if set to 1 output the amperage in milliamp steps instead of 0.01A steps via msp