implemented using one of RC inputs as ADC channel for power meter.

added MSP_ACC_TRIM stuff for android GUI.


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@231 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2012-10-19 02:43:27 +00:00
parent e59f639951
commit 23acf529d7
14 changed files with 3007 additions and 2936 deletions

File diff suppressed because it is too large Load Diff

View File

@ -48,6 +48,7 @@ typedef enum {
FEATURE_FAILSAFE = 1 << 9,
FEATURE_SONAR = 1 << 10,
FEATURE_TELEMETRY = 1 << 11,
FEATURE_POWERMETER = 1 << 12,
} AvailableFeatures;
typedef enum {

View File

@ -116,6 +116,7 @@ const clivalue_t valueTable[] = {
{ "vbatscale", VAR_UINT8, &cfg.vbatscale, 10, 200 },
{ "vbatmaxcellvoltage", VAR_UINT8, &cfg.vbatmaxcellvoltage, 10, 50 },
{ "vbatmincellvoltage", VAR_UINT8, &cfg.vbatmincellvoltage, 10, 50 },
{ "power_adc_channel", VAR_UINT8, &cfg.power_adc_channel, 0, 9 },
{ "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 },
{ "tri_yaw_middle", VAR_UINT16, &cfg.tri_yaw_middle, 0, 2000 },
{ "tri_yaw_min", VAR_UINT16, &cfg.tri_yaw_min, 0, 2000 },

View File

@ -192,6 +192,7 @@ static void resetConf(void)
cfg.vbatscale = 110;
cfg.vbatmaxcellvoltage = 43;
cfg.vbatmincellvoltage = 33;
// cfg.power_adc_channel = 0;
// Radio
parseRcChannels("AETR1234");

View File

@ -1,21 +1,25 @@
#include "board.h"
static volatile uint16_t adc1Ch4Value = 0;
#define ADC_BATTERY 0
#define ADC_CURRENT 1
void adcInit(void)
// static volatile uint16_t adc1Ch4Value = 0;
static volatile uint16_t adcValues[2];
void adcInit(drv_adc_config_t *init)
{
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
bool multiChannel = init->powerAdcChannel > 0;
// ADC assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(DMA1_Channel1);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&adc1Ch4Value;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = 1;
DMA_InitStructure.DMA_BufferSize = multiChannel ? 2 : 1;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
DMA_InitStructure.DMA_MemoryInc = multiChannel ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
@ -26,14 +30,16 @@ void adcInit(void)
DMA_Cmd(DMA1_Channel1, ENABLE);
ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_InitStructure.ADC_ScanConvMode = DISABLE;
ADC_InitStructure.ADC_ScanConvMode = multiChannel ? ENABLE : DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfChannel = 1;
ADC_InitStructure.ADC_NbrOfChannel = multiChannel ? 2 : 1;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_4, 1, ADC_SampleTime_28Cycles5);
if (multiChannel)
ADC_RegularChannelConfig(ADC1, init->powerAdcChannel, 2, ADC_SampleTime_28Cycles5);
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
@ -48,7 +54,7 @@ void adcInit(void)
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
}
uint16_t adcGetBattery(void)
uint16_t adcGetChannel(uint8_t channel)
{
return adc1Ch4Value;
return adcValues[channel];
}

View File

@ -1,7 +1,15 @@
#pragma once
void adcInit(void);
uint16_t adcGetBattery(void);
#define ADC_BATTERY 0
#define ADC_CURRENT 1
typedef struct drv_adc_config_t {
uint8_t powerAdcChannel; // which channel used for current monitor, allowed PA1, PB1 (ADC_Channel_1, ADC_Channel_9)
} drv_adc_config_t;
void adcInit(drv_adc_config_t *init);
uint16_t adcGetChannel(uint8_t channel);
#ifdef FY90Q
void adcSensorInit(sensor_t *acc, sensor_t *gyro);
#endif

View File

@ -74,34 +74,6 @@
typedef void pwmCallbackPtr(uint8_t port, uint16_t capture);
// This indexes into the read-only hardware definition structure below, as well as into pwmPorts[] structure with dynamic data.
enum {
PWM1 = 0,
PWM2,
PWM3,
PWM4,
PWM5,
PWM6,
PWM7,
PWM8,
PWM9,
PWM10,
PWM11,
PWM12,
PWM13,
PWM14,
MAX_PORTS
};
typedef struct {
TIM_TypeDef *tim;
GPIO_TypeDef *gpio;
uint32_t pin;
uint8_t channel;
uint8_t irq;
uint8_t outputEnable;
} pwmHardware_t;
static pwmHardware_t timerHardware[] = {
{ TIM2, GPIOA, GPIO_Pin_0, TIM_Channel_1, TIM2_IRQn, 0, }, // PWM1
{ TIM2, GPIOA, GPIO_Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2
@ -481,6 +453,10 @@ bool pwmInit(drv_pwm_config_t *init)
if (init->useUART && (port == PWM3 || port == PWM4))
continue;
// skip ADC for powerMeter if configured
if (init->adcChannel && (init->adcChannel == PWM2 || init->adcChannel == PWM8))
continue;
// hacks to allow current functionality
if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput)
mask = 0;

View File

@ -11,10 +11,39 @@ typedef struct drv_pwm_config_t {
bool useServos;
bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors
bool airplane; // fixed wing hardware config, lots of servos etc
uint8_t adcChannel; // steal one RC input for current sensor
uint16_t motorPwmRate;
uint16_t servoPwmRate;
} drv_pwm_config_t;
// This indexes into the read-only hardware definition structure in drv_pwm.c, as well as into pwmPorts[] structure with dynamic data.
enum {
PWM1 = 0,
PWM2,
PWM3,
PWM4,
PWM5,
PWM6,
PWM7,
PWM8,
PWM9,
PWM10,
PWM11,
PWM12,
PWM13,
PWM14,
MAX_PORTS
};
typedef struct {
TIM_TypeDef *tim;
GPIO_TypeDef *gpio;
uint32_t pin;
uint8_t channel;
uint8_t irq;
uint8_t outputEnable;
} pwmHardware_t;
bool pwmInit(drv_pwm_config_t *init); // returns whether driver is asking to calibrate throttle or not
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmWriteServo(uint8_t index, uint16_t value);

View File

@ -94,7 +94,6 @@ void systemInit(void)
SysTick_Config(SystemCoreClock / 1000);
// Configure the rest of the stuff
adcInit();
#ifndef FY90Q
i2cInit(I2C2);
#endif

View File

@ -18,6 +18,7 @@ int main(void)
{
uint8_t i;
drv_pwm_config_t pwm_params;
drv_adc_config_t adc_params;
#if 0
// PC12, PA15
@ -46,6 +47,16 @@ int main(void)
checkFirstTime(false);
readEEPROM();
// configure power ADC
if (cfg.power_adc_channel > 0 && (cfg.power_adc_channel == 1 || cfg.power_adc_channel == 9))
adc_params.powerAdcChannel = cfg.power_adc_channel;
else {
adc_params.powerAdcChannel = 0;
cfg.power_adc_channel = 0;
}
adcInit(&adc_params);
serialInit(cfg.serial_baudrate);
// We have these sensors
@ -87,6 +98,17 @@ int main(void)
pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.motorPwmRate = cfg.motor_pwm_rate;
pwm_params.servoPwmRate = cfg.servo_pwm_rate;
switch (cfg.power_adc_channel) {
case 1:
pwm_params.adcChannel = PWM2;
break;
case 9:
pwm_params.adcChannel = PWM8;
break;
default:
pwm_params.adcChannel = 0;
break;
}
pwmInit(&pwm_params);

View File

@ -147,7 +147,7 @@ void annexCode(void)
if (feature(FEATURE_VBAT)) {
if (!(++vbatTimer % VBATFREQ)) {
vbatRawArray[(ind++) % 8] = adcGetBattery();
vbatRawArray[(ind++) % 8] = adcGetChannel(ADC_BATTERY);
for (i = 0; i < 8; i++)
vbatRaw += vbatRawArray[i];
vbat = batteryAdcToVoltage(vbatRaw / 8);

View File

@ -164,6 +164,7 @@ typedef struct config_t {
uint8_t vbatscale; // adjust this to match battery voltage to reported value
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
uint8_t power_adc_channel; // which channel is used for current sensor. Right now, only 2 places are supported: RC_CH2 (unused when in CPPM mode, = 1), RC_CH8 (last channel in PWM mode, = 9)
// Radio/ESC-related configuration
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
@ -175,7 +176,7 @@ typedef struct config_t {
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
// Failsafe related configuration
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)

View File

@ -137,7 +137,7 @@ void batteryInit(void)
// average up some voltage readings
for (i = 0; i < 32; i++) {
voltage += adcGetBattery();
voltage += adcGetChannel(ADC_BATTERY);
delay(10);
}

View File

@ -41,6 +41,9 @@
#define MSP_DEBUGMSG 253 //out message debug string buffer
#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
#define MSP_ACC_TRIM 240 //out message get acc angle trim values
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
#define INBUF_SIZE 64
static const char boxnames[] =
@ -179,6 +182,11 @@ static void evaluateCommand(void)
rcData[i] = read16();
headSerialReply(0);
break;
case MSP_SET_ACC_TRIM:
cfg.angleTrim[PITCH] = read16();
cfg.angleTrim[ROLL] = read16();
headSerialReply(0);
break;
case MSP_SET_RAW_GPS:
f.GPS_FIX = read8();
GPS_numSat = read8();
@ -360,6 +368,11 @@ static void evaluateCommand(void)
writeParams(0);
headSerialReply(0);
break;
case MSP_ACC_TRIM:
headSerialReply(4);
serialize16(cfg.angleTrim[PITCH]);
serialize16(cfg.angleTrim[ROLL]);
break;
case MSP_DEBUG:
headSerialReply(8);
for (i = 0; i < 4; i++)