1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Merge branch 'development' of https://github.com/borisbstyle/betaflight into build_parameterless_parallel

This commit is contained in:
Michael Keller 2016-06-28 07:30:14 +12:00
commit c7b8d94c7b
124 changed files with 2158 additions and 1829 deletions

View file

@ -667,24 +667,36 @@ $(VALID_TARGETS):
$(MAKE) binary hex TARGET=$@ && \
echo "Building $@ succeeded."
## clean : clean up all temporary / machine-generated files
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
## clean : clean up temporary / machine-generated files
clean:
echo "Cleaning $(TARGET)"
rm -f $(CLEAN_ARTIFACTS)
rm -rf $(OBJECT_DIR)/$(TARGET)
echo "Cleaning $(TARGET) succeeded."
## clean_test : clean up all temporary / machine-generated files (tests)
## clean_test : clean up temporary / machine-generated files (tests)
clean_test:
cd src/test && $(MAKE) clean || true
## clean_all_targets : clean all valid target platforms
clean_all:
for clean_target in $(VALID_TARGETS); do \
echo "" && \
echo "Cleaning $$clean_target" && \
$(MAKE) -j TARGET=$$clean_target clean || \
break; \
echo "Cleaning $$clean_target succeeded."; \
done
## clean_<TARGET> : clean up one specific target
$(CLEAN_TARGETS) :
$(MAKE) -j TARGET=$(subst clean_,,$@) clean
## <TARGET>_clean : clean up one specific target (alias for above)
$(TARGETS_CLEAN) :
$(MAKE) -j TARGET=$(subst _clean,,$@) clean
## clean_all : clean all valid targets
clean_all:$(CLEAN_TARGETS)
## all_clean : clean all valid targets (alias for above)
all_clean:$(TARGETS_CLEAN)
flash_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon

View file

@ -1,6 +1,6 @@
# Betaflight
![Betaflight](https://dl.dropboxusercontent.com/u/31537757/betaflight%20logo.jpg)
![Betaflight](https://camo.githubusercontent.com/8178215d6cb90842dc95c9d437b1bdf09b2d57a7/687474703a2f2f7374617469632e726367726f7570732e6e65742f666f72756d732f6174746163686d656e74732f362f312f302f332f372f362f61393038383930302d3232382d62665f6c6f676f2e6a7067)
Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft.

View file

@ -20,7 +20,10 @@ targets=("PUBLISHMETA=True" \
"TARGET=ALIENFLIGHTF3" \
"TARGET=DOGE" \
"TARGET=SINGULARITY" \
"TARGET=SIRINFPV")
"TARGET=SIRINFPV" \
"TARGET=X_RACERSPI")
#fake a travis build environment
export TRAVIS_BUILD_NUMBER=$(date +%s)

View file

@ -228,8 +228,8 @@ enum EP_BUF_NUM
/* GetDADDR */
#define _GetDADDR() ((__IO uint16_t) *DADDR)
/* GetBTABLE */
#define _GetBTABLE() ((__IO uint16_t) *BTABLE)
/* GetBTABLE ; clear low-order bits explicitly to avoid problems in gcc 5.x */
#define _GetBTABLE() (((__IO uint16_t) *BTABLE) & ~0x07)
/* SetENDPOINT */
#define _SetENDPOINT(bEpNum,wRegValue) (*(EP0REG + bEpNum)= \

View file

@ -23,6 +23,8 @@
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/maths.h"
@ -178,7 +180,7 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
accelerometerTrims->values.yaw = 0;
}
static void resetPidProfile(pidProfile_t *pidProfile)
void resetPidProfile(pidProfile_t *pidProfile)
{
#if (defined(STM32F10X))
@ -193,7 +195,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PITCH] = 50;
pidProfile->I8[PITCH] = 40;
pidProfile->D8[PITCH] = 18;
pidProfile->P8[YAW] = 90;
pidProfile->P8[YAW] = 80;
pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20;
pidProfile->P8[PIDALT] = 50;
@ -218,10 +220,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 80;
pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->rollPitchItermIgnoreRate = 180;
pidProfile->yawItermIgnoreRate = 35;
pidProfile->dterm_lpf_hz = 50; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_ERROR;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
pidProfile->dynamic_pid = 1;
#ifdef GTUNE
@ -615,14 +617,14 @@ static void resetConf(void)
masterConfig.vtx_mhz = 5740; //F0
#endif
#ifdef SPRACINGF3
masterConfig.blackbox_device = 1;
#ifdef TRANSPONDER
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
#endif
#ifdef BLACKBOX
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
featureSet(FEATURE_BLACKBOX);
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
@ -630,12 +632,13 @@ static void resetConf(void)
featureSet(FEATURE_BLACKBOX);
masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
#else
masterConfig.blackbox_device = 0;
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
#endif
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
#endif // BLACKBOX
// alternative defaults settings for COLIBRI RACE targets
#if defined(COLIBRI_RACE)
@ -651,20 +654,21 @@ static void resetConf(void)
#if defined(ALIENFLIGHT)
featureClear(FEATURE_ONESHOT125);
#ifdef ALIENFLIGHTF3
#ifdef ALIENFLIGHTF1
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
#else
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
#endif
#ifdef ALIENFLIGHTF3
masterConfig.batteryConfig.vbatscale = 20;
masterConfig.mag_hardware = MAG_NONE; // disabled by default
#else
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
#endif
masterConfig.rxConfig.serialrx_provider = 1;
masterConfig.rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048;
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
masterConfig.motor_pwm_rate = 32000;
currentProfile->pidProfile.pidController = 2;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
@ -684,10 +688,6 @@ static void resetConf(void)
#if defined(SINGULARITY)
// alternative defaults settings for SINGULARITY target
masterConfig.blackbox_device = 1;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
masterConfig.batteryConfig.vbatscale = 77;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
@ -1046,7 +1046,8 @@ void changeProfile(uint8_t profileIndex)
beeperConfirmationBeeps(profileIndex + 1);
}
void changeControlRateProfile(uint8_t profileIndex) {
void changeControlRateProfile(uint8_t profileIndex)
{
if (profileIndex > MAX_RATEPROFILES) {
profileIndex = MAX_RATEPROFILES - 1;
}
@ -1054,17 +1055,6 @@ void changeControlRateProfile(uint8_t profileIndex) {
activateControlRateConfig();
}
void handleOneshotFeatureChangeOnRestart(void)
{
// Shutdown PWM on all motors prior to soft restart
StopPwmAllMotors();
delay(50);
// Apply additional delay when OneShot125 feature changed from on to off state
if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
}
}
void latchActiveFeatures()
{
activeFeaturesLatch = masterConfig.enabledFeatures;

View file

@ -50,7 +50,6 @@ typedef enum {
FEATURE_VTX = 1 << 25,
} features_e;
void handleOneshotFeatureChangeOnRestart(void);
void latchActiveFeatures(void);
bool featureConfigured(uint32_t mask);
bool feature(uint32_t mask);

View file

@ -81,7 +81,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
DISABLE_L3GD20;
spiSetDivisor(L3GD20_SPI, SPI_9MHZ_CLOCK_DIVIDER);
spiSetDivisor(L3GD20_SPI, SPI_CLOCK_STANDARD);
}
void l3gd20GyroInit(uint8_t lpf)

View file

@ -128,13 +128,13 @@ void mpu6000SpiGyroInit(uint8_t lpf)
mpu6000AccAndGyroInit();
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
// Accel and Gyro DLPF Setting
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
delayMicroseconds(1);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); // 18 MHz SPI clock
int16_t data[3];
mpuGyroRead(data);
@ -162,7 +162,7 @@ bool mpu6000SpiDetect(void)
IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);
@ -209,7 +209,7 @@ static void mpu6000AccAndGyroInit(void) {
return;
}
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
// Device Reset
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);
@ -251,7 +251,7 @@ static void mpu6000AccAndGyroInit(void) {
delayMicroseconds(15);
#endif
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
delayMicroseconds(1);
mpuSpi6000InitDone = true;

View file

@ -72,11 +72,7 @@ static void mpu6500SpiInit(void)
IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
#if defined(STM32F4)
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_SLOW_CLOCK);
#else
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_STANDARD_CLOCK);
#endif
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
hardwareInitialised = true;
}

View file

@ -55,7 +55,8 @@ static IO_t mpuSpi9250CsPin = IO_NONE;
#define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin)
#define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin)
void mpu9250ResetGyro(void) {
void mpu9250ResetGyro(void)
{
// Device Reset
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
delay(150);
@ -105,7 +106,7 @@ void mpu9250SpiGyroInit(uint8_t lpf)
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
spiSetDivisor(MPU9250_SPI_INSTANCE, 5); //high speed now that we don't need to write to the slow registers
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers
int16_t data[3];
mpuGyroRead(data);
@ -123,9 +124,8 @@ void mpu9250SpiAccInit(acc_t *acc)
acc->acc_1G = 512 * 8;
}
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) {
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data)
{
uint8_t in;
uint8_t attemptsRemaining = 20;
@ -151,7 +151,7 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) {
return;
}
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed for writing to slow registers
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
delay(50);
@ -177,6 +177,8 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) {
verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
#endif
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
mpuSpi9250InitDone = true; //init done
}
@ -192,7 +194,7 @@ bool mpu9250SpiDetect(void)
IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
do {
@ -207,6 +209,8 @@ bool mpu9250SpiDetect(void)
}
} while (attemptsRemaining--);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
return true;
}

View file

@ -33,6 +33,14 @@
adc_config_t adcConfig[ADC_CHANNEL_COUNT];
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelByTag(ioTag_t ioTag)
{
for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) {
if (ioTag == adcTagMap[i].tag)
return adcTagMap[i].channel;
}
return 0;
}
uint16_t adcGetChannel(uint8_t channel)
{

View file

@ -17,5 +17,52 @@
#pragma once
#include "io.h"
#include "rcc.h"
#if defined(STM32F4)
#define ADC_TAG_MAP_COUNT 16
#elif defined(STM32F3)
#define ADC_TAG_MAP_COUNT 39
#else
#define ADC_TAG_MAP_COUNT 10
#endif
typedef enum ADCDevice {
ADCINVALID = -1,
ADCDEV_1 = 0,
#if defined(STM32F3)
ADCDEV_2,
ADCDEV_MAX = ADCDEV_2,
#elif defined(STM32F4)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
#else
ADCDEV_MAX = ADCDEV_1,
#endif
} ADCDevice;
typedef struct adcTagMap_s {
ioTag_t tag;
uint8_t channel;
} adcTagMap_t;
typedef struct adcDevice_s {
ADC_TypeDef* ADCx;
rccPeriphTag_t rccADC;
rccPeriphTag_t rccDMA;
#if defined(STM32F4)
DMA_Stream_TypeDef* DMAy_Streamx;
uint32_t channel;
#else
DMA_Channel_TypeDef* DMAy_Channelx;
#endif
} adcDevice_t;
extern const adcDevice_t adcHardware[];
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelByTag(ioTag_t ioTag);

View file

@ -29,17 +29,44 @@
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"
#include "adc_impl.h"
#include "io.h"
#include "rcc.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#define ADC_ABP2_PERIPHERAL RCC_APB2Periph_ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#endif
const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }
};
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
return ADCDEV_1;
/* TODO -- ADC2 available on large 10x devices.
if (instance == ADC2)
return ADCDEV_2;
*/
return ADCINVALID;
}
const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12
{ DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12
{ DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12
{ DEFIO_TAG_E__PA3, ADC_Channel_3 }, // ADC12
{ DEFIO_TAG_E__PA4, ADC_Channel_4 }, // ADC12
{ DEFIO_TAG_E__PA5, ADC_Channel_5 }, // ADC12
{ DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12
{ DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12
{ DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12
{ DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12
};
// Driver for STM32F103CB onboard ADC
//
// Naze32
@ -50,77 +77,78 @@
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
//
void adcInit(drv_adc_config_t *init)
{
#if defined(CJMCU) || defined(CC3D)
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
UNUSED(init);
#endif
uint8_t i;
uint8_t configuredAdcChannels = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
#ifdef VBAT_ADC_GPIO
#ifdef VBAT_ADC_PIN
if (init->enableVBat) {
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
}
#endif
#ifdef RSSI_ADC_GPIO
#ifdef RSSI_ADC_PIN
if (init->enableRSSI) {
GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN;
GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_RSSI].enabled = true;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5;
}
#endif
#ifdef EXTERNAL1_ADC_GPIO
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN;
GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_EXTERNAL1].enabled = true;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5;
}
#endif
#ifdef CURRENT_METER_ADC_GPIO
#ifdef CURRENT_METER_ADC_PIN
if (init->enableCurrentMeter) {
GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN;
GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_CURRENT].enabled = true;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5;
}
#endif
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL, ENABLE);
RCC_APB2PeriphClockCmd(ADC_ABP2_PERIPHERAL, ENABLE);
RCC_ClockCmd(adc.rccADC, ENABLE);
RCC_ClockCmd(adc.rccDMA, ENABLE);
// FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(ADC_DMA_CHANNEL);
DMA_DeInit(adc.DMAy_Channelx);
DMA_InitTypeDef DMA_InitStructure;
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
@ -131,8 +159,8 @@ void adcInit(drv_adc_config_t *init)
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure);
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure);
DMA_Cmd(adc.DMAy_Channelx, ENABLE);
ADC_InitTypeDef ADC_InitStructure;
ADC_StructInit(&ADC_InitStructure);
@ -142,23 +170,23 @@ void adcInit(drv_adc_config_t *init)
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels;
ADC_Init(ADC_INSTANCE, &ADC_InitStructure);
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}
ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
}
ADC_DMACmd(ADC_INSTANCE, ENABLE);
ADC_Cmd(ADC_INSTANCE, ENABLE);
ADC_DMACmd(adc.ADCx, ENABLE);
ADC_Cmd(adc.ADCx, ENABLE);
ADC_ResetCalibration(ADC_INSTANCE);
while(ADC_GetResetCalibrationStatus(ADC_INSTANCE));
ADC_StartCalibration(ADC_INSTANCE);
while(ADC_GetCalibrationStatus(ADC_INSTANCE));
ADC_ResetCalibration(adc.ADCx);
while (ADC_GetResetCalibrationStatus(adc.ADCx));
ADC_StartCalibration(adc.ADCx);
while (ADC_GetCalibrationStatus(adc.ADCx));
ADC_SoftwareStartConvCmd(ADC_INSTANCE, ENABLE);
ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE);
}

View file

@ -29,35 +29,88 @@
#include "adc.h"
#include "adc_impl.h"
#include "io.h"
#include "rcc.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#endif
const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 },
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 }
};
const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1
{ DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1
{ DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1
{ DEFIO_TAG_E__PA3, ADC_Channel_4 }, // ADC1
{ DEFIO_TAG_E__PA4, ADC_Channel_1 }, // ADC2
{ DEFIO_TAG_E__PA5, ADC_Channel_2 }, // ADC2
{ DEFIO_TAG_E__PA6, ADC_Channel_3 }, // ADC2
{ DEFIO_TAG_E__PA7, ADC_Channel_4 }, // ADC2
{ DEFIO_TAG_E__PB0, ADC_Channel_12 }, // ADC3
{ DEFIO_TAG_E__PB1, ADC_Channel_1 }, // ADC3
{ DEFIO_TAG_E__PB2, ADC_Channel_12 }, // ADC2
{ DEFIO_TAG_E__PB12, ADC_Channel_3 }, // ADC4
{ DEFIO_TAG_E__PB13, ADC_Channel_5 }, // ADC3
{ DEFIO_TAG_E__PB14, ADC_Channel_4 }, // ADC4
{ DEFIO_TAG_E__PB15, ADC_Channel_5 }, // ADC4
{ DEFIO_TAG_E__PC0, ADC_Channel_6 }, // ADC12
{ DEFIO_TAG_E__PC1, ADC_Channel_7 }, // ADC12
{ DEFIO_TAG_E__PC2, ADC_Channel_8 }, // ADC12
{ DEFIO_TAG_E__PC3, ADC_Channel_9 }, // ADC12
{ DEFIO_TAG_E__PC4, ADC_Channel_5 }, // ADC2
{ DEFIO_TAG_E__PC5, ADC_Channel_11 }, // ADC2
{ DEFIO_TAG_E__PD8, ADC_Channel_12 }, // ADC4
{ DEFIO_TAG_E__PD9, ADC_Channel_13 }, // ADC4
{ DEFIO_TAG_E__PD10, ADC_Channel_7 }, // ADC34
{ DEFIO_TAG_E__PD11, ADC_Channel_8 }, // ADC34
{ DEFIO_TAG_E__PD12, ADC_Channel_9 }, // ADC34
{ DEFIO_TAG_E__PD13, ADC_Channel_10 }, // ADC34
{ DEFIO_TAG_E__PD14, ADC_Channel_11 }, // ADC34
{ DEFIO_TAG_E__PE7, ADC_Channel_13 }, // ADC3
{ DEFIO_TAG_E__PE8, ADC_Channel_6 }, // ADC34
{ DEFIO_TAG_E__PE9, ADC_Channel_2 }, // ADC3
{ DEFIO_TAG_E__PE10, ADC_Channel_14 }, // ADC3
{ DEFIO_TAG_E__PE11, ADC_Channel_15 }, // ADC3
{ DEFIO_TAG_E__PE12, ADC_Channel_16 }, // ADC3
{ DEFIO_TAG_E__PE13, ADC_Channel_3 }, // ADC3
{ DEFIO_TAG_E__PE14, ADC_Channel_1 }, // ADC4
{ DEFIO_TAG_E__PE15, ADC_Channel_2 }, // ADC4
{ DEFIO_TAG_E__PF2, ADC_Channel_10 }, // ADC12
{ DEFIO_TAG_E__PF4, ADC_Channel_5 }, // ADC1
};
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
return ADCDEV_1;
if (instance == ADC2)
return ADCDEV_2;
return ADCINVALID;
}
void adcInit(drv_adc_config_t *init)
{
UNUSED(init);
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
uint8_t i;
uint8_t adcChannelCount = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
#ifdef VBAT_ADC_GPIO
#ifdef VBAT_ADC_PIN
if (init->enableVBat) {
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_BATTERY].enabled = true;
@ -65,12 +118,12 @@ void adcInit(drv_adc_config_t *init)
}
#endif
#ifdef RSSI_ADC_GPIO
#ifdef RSSI_ADC_PIN
if (init->enableRSSI) {
GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN;
GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure);
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
adcConfig[ADC_RSSI].dmaIndex = adcChannelCount;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_RSSI].enabled = true;
@ -80,10 +133,10 @@ void adcInit(drv_adc_config_t *init)
#ifdef CURRENT_METER_ADC_GPIO
if (init->enableCurrentMeter) {
GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN;
GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure);
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_CURRENT].enabled = true;
@ -93,10 +146,10 @@ void adcInit(drv_adc_config_t *init)
#ifdef EXTERNAL1_ADC_GPIO
if (init->enableExternal1) {
GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN;
GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure);
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_EXTERNAL1].enabled = true;
@ -104,13 +157,20 @@ void adcInit(drv_adc_config_t *init)
}
#endif
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL | RCC_AHBPeriph_ADC12, ENABLE);
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
if (device == ADCINVALID)
return;
DMA_DeInit(ADC_DMA_CHANNEL);
adcDevice_t adc = adcHardware[device];
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_ClockCmd(adc.rccADC, ENABLE);
RCC_ClockCmd(adc.rccDMA, ENABLE);
DMA_DeInit(adc.DMAy_Channelx);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = adcChannelCount;
@ -122,20 +182,18 @@ void adcInit(drv_adc_config_t *init)
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure);
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure);
DMA_Cmd(adc.DMAy_Channelx, ENABLE);
// calibrate
ADC_VoltageRegulatorCmd(ADC_INSTANCE, ENABLE);
ADC_VoltageRegulatorCmd(adc.ADCx, ENABLE);
delay(10);
ADC_SelectCalibrationMode(ADC_INSTANCE, ADC_CalibrationMode_Single);
ADC_StartCalibration(ADC_INSTANCE);
while(ADC_GetCalibrationStatus(ADC_INSTANCE) != RESET);
ADC_VoltageRegulatorCmd(ADC_INSTANCE, DISABLE);
ADC_SelectCalibrationMode(adc.ADCx, ADC_CalibrationMode_Single);
ADC_StartCalibration(adc.ADCx);
while (ADC_GetCalibrationStatus(adc.ADCx) != RESET);
ADC_VoltageRegulatorCmd(adc.ADCx, DISABLE);
ADC_CommonInitTypeDef ADC_CommonInitStructure;
@ -145,7 +203,7 @@ void adcInit(drv_adc_config_t *init)
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1;
ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0;
ADC_CommonInit(ADC_INSTANCE, &ADC_CommonInitStructure);
ADC_CommonInit(adc.ADCx, &ADC_CommonInitStructure);
ADC_StructInit(&ADC_InitStructure);
@ -158,24 +216,24 @@ void adcInit(drv_adc_config_t *init)
ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable;
ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount;
ADC_Init(ADC_INSTANCE, &ADC_InitStructure);
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}
ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
}
ADC_Cmd(ADC_INSTANCE, ENABLE);
ADC_Cmd(adc.ADCx, ENABLE);
while(!ADC_GetFlagStatus(ADC_INSTANCE, ADC_FLAG_RDY));
while (!ADC_GetFlagStatus(adc.ADCx, ADC_FLAG_RDY));
ADC_DMAConfig(ADC_INSTANCE, ADC_DMAMode_Circular);
ADC_DMAConfig(adc.ADCx, ADC_DMAMode_Circular);
ADC_DMACmd(ADC_INSTANCE, ENABLE);
ADC_DMACmd(adc.ADCx, ENABLE);
ADC_StartConversion(ADC_INSTANCE);
ADC_StartConversion(adc.ADCx);
}

View file

@ -23,6 +23,8 @@
#include "system.h"
#include "io.h"
#include "io_impl.h"
#include "rcc.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
@ -32,6 +34,56 @@
#include "adc.h"
#include "adc_impl.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#endif
const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 },
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
};
/* note these could be packed up for saving space */
const adcTagMap_t adcTagMap[] = {
/*
{ DEFIO_TAG_E__PF3, ADC_Channel_9 },
{ DEFIO_TAG_E__PF4, ADC_Channel_14 },
{ DEFIO_TAG_E__PF5, ADC_Channel_15 },
{ DEFIO_TAG_E__PF6, ADC_Channel_4 },
{ DEFIO_TAG_E__PF7, ADC_Channel_5 },
{ DEFIO_TAG_E__PF8, ADC_Channel_6 },
{ DEFIO_TAG_E__PF9, ADC_Channel_7 },
{ DEFIO_TAG_E__PF10, ADC_Channel_8 },
*/
{ DEFIO_TAG_E__PC0, ADC_Channel_10 },
{ DEFIO_TAG_E__PC1, ADC_Channel_11 },
{ DEFIO_TAG_E__PC2, ADC_Channel_12 },
{ DEFIO_TAG_E__PC3, ADC_Channel_13 },
{ DEFIO_TAG_E__PC4, ADC_Channel_14 },
{ DEFIO_TAG_E__PC5, ADC_Channel_15 },
{ DEFIO_TAG_E__PB0, ADC_Channel_8 },
{ DEFIO_TAG_E__PB1, ADC_Channel_9 },
{ DEFIO_TAG_E__PA0, ADC_Channel_0 },
{ DEFIO_TAG_E__PA1, ADC_Channel_1 },
{ DEFIO_TAG_E__PA2, ADC_Channel_2 },
{ DEFIO_TAG_E__PA3, ADC_Channel_3 },
{ DEFIO_TAG_E__PA4, ADC_Channel_4 },
{ DEFIO_TAG_E__PA5, ADC_Channel_5 },
{ DEFIO_TAG_E__PA6, ADC_Channel_6 },
{ DEFIO_TAG_E__PA7, ADC_Channel_7 },
};
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
return ADCDEV_1;
/*
if (instance == ADC2) // TODO add ADC2 and 3
return ADCDEV_2;
*/
return ADCINVALID;
}
void adcInit(drv_adc_config_t *init)
{
ADC_InitTypeDef ADC_InitStructure;
@ -50,7 +102,7 @@ void adcInit(drv_adc_config_t *init)
if (init->enableVBat) {
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); //VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles;
@ -61,7 +113,7 @@ void adcInit(drv_adc_config_t *init)
if (init->enableExternal1) {
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL;
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_EXTERNAL1].enabled = true;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles;
@ -72,7 +124,7 @@ void adcInit(drv_adc_config_t *init)
if (init->enableRSSI) {
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL;
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_RSSI].enabled = true;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles;
@ -83,7 +135,7 @@ void adcInit(drv_adc_config_t *init)
if (init->enableCurrentMeter) {
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL;
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_CURRENT].enabled = true;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles;
@ -92,15 +144,20 @@ void adcInit(drv_adc_config_t *init)
//RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
if (device == ADCINVALID)
return;
DMA_DeInit(DMA2_Stream4);
adcDevice_t adc = adcHardware[device];
RCC_ClockCmd(adc.rccDMA, ENABLE);
RCC_ClockCmd(adc.rccADC, ENABLE);
DMA_DeInit(adc.DMAy_Streamx);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
DMA_InitStructure.DMA_Channel = DMA_Channel_0;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
DMA_InitStructure.DMA_Channel = adc.channel;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
@ -110,20 +167,9 @@ void adcInit(drv_adc_config_t *init)
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_Init(DMA2_Stream4, &DMA_InitStructure);
DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure);
DMA_Cmd(DMA2_Stream4, ENABLE);
// calibrate
/*
ADC_VoltageRegulatorCmd(ADC1, ENABLE);
delay(10);
ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single);
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1) != RESET);
ADC_VoltageRegulatorCmd(ADC1, DISABLE);
*/
DMA_Cmd(adc.DMAy_Streamx, ENABLE);
ADC_CommonInitTypeDef ADC_CommonInitStructure;
@ -144,19 +190,19 @@ void adcInit(drv_adc_config_t *init)
ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels;
ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
ADC_Init(ADC1, &ADC_InitStructure);
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
}
ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE);
ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE);
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
ADC_DMACmd(adc.ADCx, ENABLE);
ADC_Cmd(adc.ADCx, ENABLE);
ADC_SoftwareStartConv(ADC1);
ADC_SoftwareStartConv(adc.ADCx);
}

View file

@ -28,12 +28,14 @@
#include "barometer.h"
#include "barometer_bmp280.h"
#define DISABLE_BMP280 GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
#define ENABLE_BMP280 GPIO_ResetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
#define DISABLE_BMP280 IOHi(bmp280CsPin)
#define ENABLE_BMP280 IOLo(bmp280CsPin)
extern int32_t bmp280_up;
extern int32_t bmp280_ut;
static IO_t bmp280CsPin = IO_NONE;
bool bmp280WriteRegister(uint8_t reg, uint8_t data)
{
ENABLE_BMP280;
@ -62,32 +64,13 @@ void bmp280SpiInit(void)
return;
}
#ifdef STM32F303
RCC_AHBPeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI);
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = BMP280_CS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
DISABLE_BMP280;
GPIO_Init(BMP280_CS_GPIO, &GPIO_InitStructure);
#endif
#ifdef STM32F10X
RCC_APB2PeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.pin = BMP280_CS_PIN;
gpio.speed = Speed_50MHz;
gpioInit(BMP280_CS_GPIO, &gpio);
#endif
GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN);
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_CLOCK_STANDARD);
hardwareInitialised = true;
}

View file

@ -82,10 +82,10 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#endif
static i2cDevice_t i2cHardwareMap[] = {
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
#ifdef STM32F4
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = false, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
#endif
};
@ -396,7 +396,7 @@ void i2cInit(I2CDevice device)
i2cUnstick(scl, sda);
// Init pins
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#ifdef STM32F4
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
#else
@ -416,8 +416,7 @@ void i2cInit(I2CDevice device)
if (i2c->overClock) {
i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
}
else {
} else {
i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
}

View file

@ -54,8 +54,8 @@ static volatile uint16_t i2cErrorCount = 0;
//static volatile uint16_t i2c2ErrorCount = 0;
static i2cDevice_t i2cHardwareMap[] = {
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false }
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK }
};
///////////////////////////////////////////////////////////////////////////////
@ -93,13 +93,12 @@ void i2cInit(I2CDevice device)
.I2C_OwnAddress1 = 0x00,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
.I2C_Timing = i2c->overClock ?
0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
//.I2C_Timing = 0x8000050B;
};
if (i2c->overClock) {
i2cInit.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
}
I2C_Init(I2Cx, &i2cInit);
I2C_Cmd(I2Cx, ENABLE);

View file

@ -72,14 +72,14 @@
#endif
static spiDevice_t spiHardwareMap[] = {
#if defined(STM32F10X)
#if defined(STM32F1)
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false },
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false },
#else
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false },
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false },
#endif
#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
#if defined(STM32F3) || defined(STM32F4)
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false }
#endif
};
@ -265,7 +265,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
}
#ifdef STM32F303xC
SPI_SendData8(instance, b);
//SPI_I2S_SendData16(instance, b);
#else
SPI_I2S_SendData(instance, b);
#endif
@ -276,7 +275,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
}
#ifdef STM32F303xC
b = SPI_ReceiveData8(instance);
//b = SPI_I2S_ReceiveData16(instance);
#else
b = SPI_I2S_ReceiveData(instance);
#endif
@ -287,7 +285,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
return true;
}
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
{
#define BR_CLEAR_MASK 0xFFC7

View file

@ -17,41 +17,39 @@
#pragma once
#define SPI_0_28125MHZ_CLOCK_DIVIDER 256
#define SPI_0_5625MHZ_CLOCK_DIVIDER 128
#define SPI_18MHZ_CLOCK_DIVIDER 2
#define SPI_9MHZ_CLOCK_DIVIDER 4
#include <stdint.h>
#include "io.h"
#include "rcc.h"
#if defined(STM32F40_41xxx) || defined (STM32F411xE) || defined(STM32F303xC)
#if defined(STM32F4) || defined(STM32F3)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#elif defined(STM32F10X)
#elif defined(STM32F1)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz)
#else
#error "Unknown processor"
#endif
#if defined(STM32F40_41xxx) || defined (STM32F411xE)
#define SPI_SLOW_CLOCK 128 //00.65625 MHz
#define SPI_STANDARD_CLOCK 8 //11.50000 MHz
#define SPI_FAST_CLOCK 4 //21.00000 MHz
#define SPI_ULTRAFAST_CLOCK 2 //42.00000 MHz
/*
Flash M25p16 tolerates 20mhz, SPI_CLOCK_FAST should sit around 20 or less.
*/
typedef enum {
SPI_CLOCK_INITIALIZATON = 256,
#if defined(STM32F4)
SPI_CLOCK_SLOW = 128, //00.65625 MHz
SPI_CLOCK_STANDARD = 8, //10.50000 MHz
SPI_CLOCK_FAST = 4, //21.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //42.00000 MHz
#else
#define SPI_SLOW_CLOCK 128 //00.56250 MHz
#define SPI_STANDARD_CLOCK 4 //09.00000 MHz
#define SPI_FAST_CLOCK 2 //18.00000 MHz
#define SPI_ULTRAFAST_CLOCK 2 //18.00000 MHz
SPI_CLOCK_SLOW = 128, //00.56250 MHz
SPI_CLOCK_STANDARD = 4, //09.00000 MHz
SPI_CLOCK_FAST = 2, //18.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //18.00000 MHz
#endif
} SPIClockDivider_e;
typedef enum SPIDevice {
SPIINVALID = -1,

View file

@ -33,6 +33,7 @@
#include "gpio.h"
#include "exti.h"
#include "bus_i2c.h"
#include "bus_spi.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
@ -42,7 +43,9 @@
#include "accgyro.h"
#include "accgyro_mpu.h"
#include "accgyro_mpu6500.h"
#include "accgyro_spi_mpu6500.h"
#include "accgyro_spi_mpu9250.h"
#include "compass_ak8963.h"
// This sensor is available in MPU-9250.
@ -83,18 +86,10 @@
#define CNTL_MODE_SELF_TEST 0x08
#define CNTL_MODE_FUSE_ROM 0x0F
typedef bool (*ak8963ReadRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf);
typedef bool (*ak8963WriteRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t data);
typedef struct ak8963Configuration_s {
ak8963ReadRegisterFunc read;
ak8963WriteRegisterFunc write;
} ak8963Configuration_t;
ak8963Configuration_t ak8963config;
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
// FIXME pretend we have real MPU9250 support
// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same.
#if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
#define MPU9250_SPI_INSTANCE
#define verifympu9250WriteRegister mpu6500WriteRegister
@ -102,30 +97,7 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
#define mpu9250ReadRegister mpu6500ReadRegister
#endif
#ifdef USE_SPI
bool ak8963SPIRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
{
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
delay(8);
__disable_irq();
mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
__enable_irq();
return true;
}
bool ak8963SPIWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
mpu6500WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
return true;
}
#endif
#ifdef SPRACINGF3EVO
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
typedef struct queuedReadState_s {
bool waiting;
@ -133,9 +105,36 @@ typedef struct queuedReadState_s {
uint32_t readStartedAt; // time read was queued in micros.
} queuedReadState_t;
typedef enum {
CHECK_STATUS = 0,
WAITING_FOR_STATUS,
WAITING_FOR_DATA
} ak8963ReadState_e;
static queuedReadState_t queuedRead = { false, 0, 0};
bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
{
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
delay(10);
__disable_irq();
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
__enable_irq();
return true;
}
bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
return true;
}
bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
{
if (queuedRead.waiting) {
return false;
@ -153,7 +152,7 @@ bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
return true;
}
static uint32_t ak8963SPIQueuedReadTimeRemaining(void)
static uint32_t ak8963SensorQueuedReadTimeRemaining(void)
{
if (!queuedRead.waiting) {
return 0;
@ -170,9 +169,9 @@ static uint32_t ak8963SPIQueuedReadTimeRemaining(void)
return timeRemaining;
}
bool ak8963SPICompleteRead(uint8_t *buf)
bool ak8963SensorCompleteRead(uint8_t *buf)
{
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining > 0) {
delayMicroseconds(timeRemaining);
@ -183,19 +182,16 @@ bool ak8963SPICompleteRead(uint8_t *buf)
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
return true;
}
#endif
#ifdef USE_I2C
bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data);
}
bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
#else
bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf);
}
bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data);
}
#endif
bool ak8963Detect(mag_t *mag)
@ -203,43 +199,28 @@ bool ak8963Detect(mag_t *mag)
bool ack = false;
uint8_t sig = 0;
#ifdef USE_I2C
// check for AK8963 on I2C bus
ack = i2cRead(MAG_I2C_INSTANCE, AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
// initialze I2C master via SPI bus (MPU9250)
ack = verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
delay(10);
ack = verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
delay(10);
ack = verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
delay(10);
#endif
// check for AK8963
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
{
ak8963config.read = c_i2cRead;
ak8963config.write = c_i2cWrite;
mag->init = ak8963Init;
mag->read = ak8963Read;
return true;
}
#endif
#ifdef USE_SPI
// check for AK8963 on I2C master via SPI bus (as part of MPU9250)
ack = mpu6500WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
delay(10);
ack = mpu6500WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
delay(10);
ack = mpu6500WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
delay(10);
ack = ak8963SPIRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
{
ak8963config.read = ak8963SPIRead;
ak8963config.write = ak8963SPIWrite;
mag->init = ak8963Init;
mag->read = ak8963Read;
return true;
}
#endif
return false;
}
@ -250,49 +231,43 @@ void ak8963Init()
uint8_t calibration[3];
uint8_t status;
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
delay(20);
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
delay(10);
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
delay(10);
magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30);
magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30);
magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30);
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
delay(10);
// Clear status registers
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
// Trigger first measurement
#ifdef SPRACINGF3EVO
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
#else
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
#endif
}
typedef enum {
CHECK_STATUS = 0,
WAITING_FOR_STATUS,
WAITING_FOR_DATA
} ak8963ReadState_e;
bool ak8963Read(int16_t *magData)
{
bool ack;
bool ack = false;
uint8_t buf[7];
#ifdef SPRACINGF3EVO
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
// we currently need a different approach on the SPRacingF3EVO which has an MPU9250 connected via SPI.
// we cannot use the ak8963SPIRead() method, it is to slow and blocks for far too long.
// we currently need a different approach for the MPU9250 connected via SPI.
// we cannot use the ak8963SensorRead() method for SPI, it is to slow and blocks for far too long.
static ak8963ReadState_e state = CHECK_STATUS;
@ -301,17 +276,17 @@ bool ak8963Read(int16_t *magData)
restart:
switch (state) {
case CHECK_STATUS:
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
state++;
return false;
case WAITING_FOR_STATUS: {
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining) {
return false;
}
ack = ak8963SPICompleteRead(&buf[0]);
ack = ak8963SensorCompleteRead(&buf[0]);
uint8_t status = buf[0];
@ -327,7 +302,7 @@ restart:
// read the 6 bytes of data and the status2 register
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
state++;
@ -335,31 +310,16 @@ restart:
}
case WAITING_FOR_DATA: {
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining) {
return false;
}
ack = ak8963SPICompleteRead(&buf[0]);
uint8_t status2 = buf[6];
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
return false;
}
magData[X] = -(int16_t)(buf[1] << 8 | buf[0]) * magGain[X];
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
state = CHECK_STATUS;
return true;
ack = ak8963SensorCompleteRead(&buf[0]);
}
}
return false;
#else
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
uint8_t status = buf[0];
@ -367,8 +327,8 @@ restart:
return false;
}
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]);
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]);
#endif
uint8_t status2 = buf[6];
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
return false;
@ -378,6 +338,10 @@ restart:
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
return ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
state = CHECK_STATUS;
return true;
#else
return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
#endif
}

View file

@ -95,7 +95,7 @@ static void m25p16_writeEnable()
static uint8_t m25p16_readStatus()
{
uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0};
uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
uint8_t in[2];
ENABLE_M25P16;
@ -134,7 +134,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
*/
static bool m25p16_readIdentification()
{
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0};
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
uint8_t in[4];
uint32_t chipID;
@ -210,7 +210,7 @@ bool m25p16_init()
#ifndef M25P16_SPI_SHARED
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER);
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_CLOCK_FAST);
#endif
return m25p16_readIdentification();

View file

@ -55,11 +55,11 @@ uint8_t max7456_send(uint8_t add, uint8_t data) {
}
void max7456_init(uint8_t video_system) {
void max7456_init(uint8_t video_system)
{
uint8_t max_screen_rows;
uint8_t srdata = 0;
uint16_t x;
char buf[LINE];
#ifdef MAX7456_SPI_CS_PIN
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
@ -68,7 +68,7 @@ void max7456_init(uint8_t video_system) {
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
//Minimum spi clock period for max7456 is 100ns (10Mhz)
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
delay(1000);
// force soft reset on Max7456
@ -77,10 +77,10 @@ void max7456_init(uint8_t video_system) {
delay(100);
srdata = max7456_send(0xA0, 0xFF);
if ((0x01 & srdata) == 0x01){ //PAL
if ((0x01 & srdata) == 0x01) { //PAL
video_signal_type = VIDEO_MODE_PAL;
}
else if((0x02 & srdata) == 0x02){ //NTSC
else if ((0x02 & srdata) == 0x02) { //NTSC
video_signal_type = VIDEO_MODE_NTSC;
}

View file

@ -31,7 +31,7 @@
#include "pwm_rx.h"
#include "pwm_mapping.h"
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
@ -327,7 +327,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
} else {
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);

View file

@ -30,14 +30,11 @@
#error Invalid motor/servo/port configuration
#endif
#define PULSE_1MS (1000) // 1ms pulse width
#define MAX_INPUTS 8
#define PWM_TIMER_MHZ 1
#define PWM_BRUSHED_TIMER_MHZ 8
#define PWM_BRUSHED_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define ONESHOT42_TIMER_MHZ 24
#define ONESHOT125_TIMER_MHZ 8

View file

@ -170,12 +170,11 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
uint8_t index;
TIM_TypeDef *lastTimerPtr = NULL;
for(index = 0; index < motorCount; index++){
for (index = 0; index < motorCount; index++) {
// Force the timer to overflow if it's the first motor to output, or if we change timers
if(motors[index]->tim != lastTimerPtr){
if (motors[index]->tim != lastTimerPtr) {
lastTimerPtr = motors[index]->tim;
timerForceOverflow(motors[index]->tim);
}
@ -185,10 +184,10 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
}
}
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
}

View file

@ -23,7 +23,9 @@ typedef enum {
OWNER_FLASH,
OWNER_USB,
OWNER_BEEPER,
OWNER_OSD
OWNER_OSD,
OWNER_BARO,
OWNER_TOTAL_COUNT
} resourceOwner_t;
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)

View file

@ -56,7 +56,7 @@ void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count)
}
}
uint8_t serialRxBytesWaiting(serialPort_t *instance)
uint32_t serialRxBytesWaiting(serialPort_t *instance)
{
return instance->vTable->serialTotalRxWaiting(instance);
}

View file

@ -62,7 +62,7 @@ typedef struct serialPort_s {
struct serialPortVTable {
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
uint8_t (*serialTotalRxWaiting)(serialPort_t *instance);
uint32_t (*serialTotalRxWaiting)(serialPort_t *instance);
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
uint8_t (*serialRead)(serialPort_t *instance);
@ -81,7 +81,7 @@ struct serialPortVTable {
};
void serialWrite(serialPort_t *instance, uint8_t ch);
uint8_t serialRxBytesWaiting(serialPort_t *instance);
uint32_t serialRxBytesWaiting(serialPort_t *instance);
uint8_t serialTxBytesFree(serialPort_t *instance);
void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count);
uint8_t serialRead(serialPort_t *instance);

View file

@ -408,7 +408,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
}
}
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
uint32_t softSerialRxBytesWaiting(serialPort_t *instance)
{
if ((instance->mode & MODE_RX) == 0) {
return 0;

View file

@ -28,7 +28,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
// serialPort API
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
uint8_t softSerialRxBytesWaiting(serialPort_t *instance);
uint32_t softSerialRxBytesWaiting(serialPort_t *instance);
uint8_t softSerialTxBytesFree(serialPort_t *instance);
uint8_t softSerialReadByte(serialPort_t *instance);
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);

View file

@ -292,7 +292,7 @@ void uartStartTxDMA(uartPort_t *s)
#endif
}
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;
#ifdef STM32F4

View file

@ -65,7 +65,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
// serialPort API
void uartWrite(serialPort_t *instance, uint8_t ch);
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance);
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance);
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
uint8_t uartRead(serialPort_t *instance);
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);

View file

@ -66,11 +66,11 @@ static bool isUsbVcpTransmitBufferEmpty(serialPort_t *instance)
return true;
}
static uint8_t usbVcpAvailable(serialPort_t *instance)
static uint32_t usbVcpAvailable(serialPort_t *instance)
{
UNUSED(instance);
return receiveLength & 0xFF; // FIXME use uint32_t return type everywhere
return receiveLength;
}
static uint8_t usbVcpRead(serialPort_t *instance)
@ -117,6 +117,7 @@ static bool usbVcpFlush(vcpPort_t *port)
if (count == 0) {
return true;
}
if (!usbIsConnected() || !usbIsConfigured()) {
return false;
}

View file

@ -17,7 +17,6 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
@ -26,7 +25,6 @@
#include "nvic.h"
#include "gpio.h"
#include "gpio.h"
#include "rcc.h"
#include "system.h"

View file

@ -47,9 +47,10 @@ typedef uint32_t timCCER_t;
typedef uint32_t timSR_t;
typedef uint32_t timCNT_t;
#else
# error "Unknown CPU defined"
#error "Unknown CPU defined"
#endif
// use different types from capture and overflow - multiple overflow handlers are implemented as linked list
struct timerCCHandlerRec_s;
struct timerOvrHandlerRec_s;

View file

@ -68,8 +68,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
tmp = (uint32_t) TIMx;
tmp += CCMR_OFFSET;
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
{
if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) {
tmp += (TIM_Channel>>1);
/* Reset the OCxM bits in the CCMRx register */
@ -77,9 +76,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
}
else
{
} else {
tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1;
/* Reset the OCxM bits in the CCMRx register */

View file

@ -133,7 +133,7 @@ static uint32_t reverse32(uint32_t in)
bool rtc6705Init(void)
{
DISABLE_RTC6705;
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
return rtc6705IsReady();
}

View file

@ -463,7 +463,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
"OFF", "ON", "ALWAYS"
};
static const char * const lookupTableFastPwm[] = {
static const char * const lookupTablePwmProtocol[] = {
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
};
@ -525,7 +525,7 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
{ lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
{ lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) },
{ lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
{ lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) },
#ifdef OSD
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
@ -1903,9 +1903,10 @@ static void dumpValues(uint16_t valueSection)
cliPrintVar(value, 0);
cliPrint("\r\n");
#ifdef STM32F4
delayMicroseconds(1000);
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
}
@ -1979,6 +1980,9 @@ static void cliDump(char *cmdline)
if (yaw < 0)
cliWrite(' ');
cliPrintf("%s\r\n", ftoa(yaw, buf));
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
#ifdef USE_SERVOS
@ -2000,6 +2004,10 @@ static void cliDump(char *cmdline)
masterConfig.customServoMixer[i].max,
masterConfig.customServoMixer[i].box
);
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
#endif
@ -2012,12 +2020,18 @@ static void cliDump(char *cmdline)
if (featureNames[i] == NULL)
break;
cliPrintf("feature -%s\r\n", featureNames[i]);
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
for (i = 0; ; i++) { // reenable what we want.
if (featureNames[i] == NULL)
break;
if (mask & (1 << i))
cliPrintf("feature %s\r\n", featureNames[i]);
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
@ -2077,6 +2091,9 @@ static void cliDump(char *cmdline)
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
if (servoDirection(i, channel) < 0) {
cliPrintf("smix reverse %d %d r\r\n", i , channel);
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
}
}
@ -2109,6 +2126,9 @@ static void cliDump(char *cmdline)
changeControlRateProfile(currentRateIndex);
cliRateProfile("");
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
cliPrint("\r\n# restore original profile selection\r\n");
@ -2133,7 +2153,8 @@ static void cliDump(char *cmdline)
}
}
void cliDumpProfile(uint8_t profileIndex) {
void cliDumpProfile(uint8_t profileIndex)
{
if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
return;
@ -2148,7 +2169,8 @@ void cliDumpProfile(uint8_t profileIndex) {
cliRateProfile("");
}
void cliDumpRateProfile(uint8_t rateProfileIndex) {
void cliDumpRateProfile(uint8_t rateProfileIndex)
{
if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
return;
@ -2541,12 +2563,12 @@ static void cliRateProfile(char *cmdline) {
}
}
static void cliReboot(void) {
static void cliReboot(void)
{
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort);
stopMotors();
handleOneshotFeatureChangeOnRestart();
systemReset();
}
@ -2653,7 +2675,7 @@ static void cliPrintVarRange(const clivalue_t *var)
{
switch (var->type & VALUE_MODE_MASK) {
case (MODE_DIRECT): {
cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max);
cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
}
break;
case (MODE_LOOKUP): {
@ -2665,7 +2687,7 @@ static void cliPrintVarRange(const clivalue_t *var)
cliPrint(",");
cliPrintf(" %s", tableEntry->values[i]);
}
cliPrint("\n");
cliPrint("\r\n");
}
break;
}
@ -2717,6 +2739,10 @@ static void cliSet(char *cmdline)
cliPrintf("%s = ", valueTable[i].name);
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
cliPrint("\r\n");
#ifdef USE_SLOW_SERIAL_CLI
delay(2);
#endif
}
} else if ((eqptr = strstr(cmdline, "=")) != NULL) {
// has equals
@ -2891,14 +2917,14 @@ static void cliTasks(char *cmdline)
subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
if (masterConfig.pid_process_denom > 1) {
taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
} else {
taskFrequency = subTaskFrequency;
cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
}
} else {
taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
}
cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
@ -2909,7 +2935,7 @@ static void cliTasks(char *cmdline)
cliPrintf("%dms", taskTotalTime);
}
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
cliPrintf("\r\n", taskTotalTime);
}
}
@ -3038,7 +3064,7 @@ void cliProcess(void)
}
}
const char * const ownerNames[] = {
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"FREE",
"PWM IN",
"PPM IN",
@ -3060,6 +3086,8 @@ const char * const ownerNames[] = {
"FLASH",
"USB",
"BEEPER",
"OSD",
"BARO",
};
static void cliResource(char *cmdline)

View file

@ -1272,11 +1272,10 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(currentProfile->pidProfile.yaw_lpf_hz);
break;
case MSP_ADVANCED_TUNING:
headSerialReply(4 * 2 + 2);
headSerialReply(3 * 2 + 2);
serialize16(currentProfile->pidProfile.rollPitchItermIgnoreRate);
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
serialize16(currentProfile->pidProfile.yaw_p_limit);
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
serialize8(currentProfile->pidProfile.deltaMethod);
serialize8(masterConfig.batteryConfig.vbatPidCompensation);
break;
@ -1516,7 +1515,7 @@ static bool processInCommand(void)
break;
case MSP_SET_RESET_CURR_PID:
//resetPidProfile(&currentProfile->pidProfile);
resetPidProfile(&currentProfile->pidProfile);
break;
case MSP_SET_SENSOR_ALIGNMENT:
@ -1857,6 +1856,7 @@ static bool processInCommand(void)
currentProfile->pidProfile.yawItermIgnoreRate = read16();
currentProfile->pidProfile.yaw_p_limit = read16();
currentProfile->pidProfile.deltaMethod = read8();
masterConfig.batteryConfig.vbatPidCompensation = read8();
break;
case MSP_SET_SPECIAL_PARAMETERS:
currentControlRateProfile->rcYawRate8 = read8();
@ -1969,7 +1969,6 @@ void mspProcess(void)
if (isRebootScheduled) {
waitForSerialPortToFinishTransmitting(candidatePort->port);
stopMotors();
handleOneshotFeatureChangeOnRestart();
// On real flight controllers, systemReset() will do a soft reset of the device,
// reloading the program. But to support offline testing this flag needs to be
// cleared so that the software doesn't continuously attempt to reboot itself.

View file

@ -17,11 +17,11 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
@ -153,9 +153,6 @@ static uint8_t systemState = SYSTEM_STATE_INITIALISING;
void init(void)
{
uint8_t i;
drv_pwm_config_t pwm_params;
printfSupportInit();
initEEPROM();
@ -260,6 +257,7 @@ void init(void)
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
#endif
drv_pwm_config_t pwm_params;
memset(&pwm_params, 0, sizeof(pwm_params));
#ifdef SONAR
@ -322,7 +320,9 @@ void init(void)
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) {
featureClear(FEATURE_3D);
pwm_params.idlePulse = 0; // brushed motors
use_unsyncedPwm = false;
}
@ -331,13 +331,17 @@ void init(void)
#endif
pwmRxInit(masterConfig.inputFilteringMode);
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
/*
// TODO is this needed here? enables at the end
if (!feature(FEATURE_ONESHOT125))
motorControlEnable = true;
*/
systemState |= SYSTEM_STATE_MOTORS_READY;
#ifdef BEEPER
@ -499,7 +503,7 @@ void init(void)
LED0_OFF;
LED2_OFF;
for (i = 0; i < 10; i++) {
for (int i = 0; i < 10; i++) {
LED1_TOGGLE;
LED0_TOGGLE;
delay(25);
@ -724,7 +728,7 @@ void main_init(void)
#endif
#ifdef MAG
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
#ifdef SPRACINGF3EVO
#if defined(USE_SPI) && defined(USE_MAG_AK8963)
// fixme temporary solution for AK6983 via slave I2C on MPU9250
rescheduleTask(TASK_COMPASS, 1000000 / 40);
#endif

View file

@ -698,6 +698,8 @@ void subTaskMainSubprocesses(void) {
#endif
#if defined(BARO) || defined(SONAR)
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
updateRcCommands();
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) {
applyAltHold(&masterConfig.airplaneConfig);
@ -878,8 +880,10 @@ void taskUpdateRxMain(void)
processRx();
isRXDataNew = true;
#if !defined(BARO) && !defined(SONAR)
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
updateRcCommands();
#endif
updateLEDs();
#ifdef BARO

View file

@ -45,7 +45,7 @@ acc_t acc; // acc access functions
sensor_align_e accAlign = 0;
uint32_t accTargetLooptime;
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
extern uint16_t InflightcalibratingA;
extern bool AccInflightCalibrationArmed;

View file

@ -20,6 +20,10 @@
#include <math.h>
#include "platform.h"
int32_t BaroAlt = 0;
#ifdef BARO
#include "common/maths.h"
#include "drivers/barometer.h"
@ -32,9 +36,6 @@ baro_t baro; // barometer access functions
uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
int32_t baroPressure = 0;
int32_t baroTemperature = 0;
int32_t BaroAlt = 0;
#ifdef BARO
static int32_t baroGroundAltitude = 0;
static int32_t baroGroundPressure = 0;

View file

@ -40,12 +40,14 @@
#endif
mag_t mag; // mag access functions
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
static int16_t magADCRaw[XYZ_AXIS_COUNT];
static uint8_t magInit = 0;
void compassInit(void)
@ -57,27 +59,19 @@ void compassInit(void)
magInit = 1;
}
#define COMPASS_UPDATE_FREQUENCY_10HZ (1000 * 100)
void updateCompass(flightDynamicsTrims_t *magZero)
{
static uint32_t nextUpdateAt, tCal = 0;
static uint32_t tCal = 0;
static flightDynamicsTrims_t magZeroTempMin;
static flightDynamicsTrims_t magZeroTempMax;
int16_t magADCRaw[XYZ_AXIS_COUNT];
uint32_t axis;
if ((int32_t)(currentTime - nextUpdateAt) < 0)
return;
nextUpdateAt = currentTime + COMPASS_UPDATE_FREQUENCY_10HZ;
mag.read(magADCRaw);
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis];
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis]; // int32_t copy to work with
alignSensors(magADC, magADC, magAlign);
if (STATE(CALIBRATE_MAG)) {
tCal = nextUpdateAt;
tCal = currentTime;
for (axis = 0; axis < 3; axis++) {
magZero->raw[axis] = 0;
magZeroTempMin.raw[axis] = magADC[axis];
@ -93,7 +87,7 @@ void updateCompass(flightDynamicsTrims_t *magZero)
}
if (tCal != 0) {
if ((nextUpdateAt - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions
if ((currentTime - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions
LED0_TOGGLE;
for (axis = 0; axis < 3; axis++) {
if (magADC[axis] < magZeroTempMin.raw[axis])

View file

@ -161,10 +161,12 @@ void gyroUpdate(void)
if (gyroLpfCutFreq) {
if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (gyroFilterStateIsSet) {
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++){
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]);
} else {
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
}
}
}

View file

@ -216,7 +216,7 @@ bool detectGyro(void)
; // fallthrough
case GYRO_MPU6500:
#ifdef USE_GYRO_MPU6500
#if defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500)
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500GyroDetect(&gyro) || mpu6500SpiGyroDetect(&gyro))
#else
@ -361,7 +361,7 @@ retry:
#endif
; // fallthrough
case ACC_MPU6500:
#ifdef USE_ACC_MPU6500
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
#ifdef USE_ACC_SPI_MPU6500
if (mpu6500AccDetect(&acc) || mpu6500SpiAccDetect(&acc))
#else

View file

@ -45,7 +45,6 @@
// Using MPU6050 for the moment.
#define GYRO
#define USE_GYRO_MPU6050
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6050_ALIGN CW270_DEG
@ -53,7 +52,6 @@
#define ACC
#define USE_ACC_MPU6050
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6050_ALIGN CW270_DEG
@ -100,8 +98,8 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL_PIN PA9
#define I2C2_SDA_PIN PA10
#define I2C2_SCL PA9
#define I2C2_SDA PA10
// SPI3
// PA15 38 SPI3_NSS
@ -118,14 +116,8 @@
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define VBAT_ADC_PIN PA4
// alternative defaults for AlienFlight F3 target
#define ALIENFLIGHT
@ -139,8 +131,8 @@
#define BINDPLUG_PIN PB12
#define BRUSHED_MOTORS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -19,11 +19,6 @@
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_MSP_PORT 1
#define CONFIG_RX_SERIAL_PORT 2
#define USBD_PRODUCT_STRING "AlienFlight F4"
@ -45,22 +40,14 @@
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6500
#define USE_ACC_SPI_MPU9250
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU9250_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_MPU9250
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU9250_ALIGN CW270_DEG
#define MAG
#define USE_MAG_HMC5883
@ -152,18 +139,10 @@
#define USE_ADC
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC0
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_PIN PC1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_0
#define RSSI_ADC_PIN PC4
#define RSSI_ADC_CHANNEL ADC_Channel_4
#define EXTERNAL1_ADC_GPIO_PIN PC5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
// LED strip configuration using RC5 pin.
//#define LED_STRIP
@ -191,9 +170,11 @@
// Hardware bind plug at PB2 (Pin 28)
#define BINDPLUG_PIN PB2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define BRUSHED_MOTORS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -4,7 +4,6 @@ FEATURES += SDCARD VCP
TARGET_SRC = \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_bmp280.c \
drivers/barometer_ms5611.c \
drivers/compass_ak8963.c \

View file

@ -19,11 +19,6 @@
#define TARGET_BOARD_IDENTIFIER "BJF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_RX_SERIAL_PORT 3
#define USBD_PRODUCT_STRING "BlueJayF4"
@ -138,9 +133,12 @@
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define VBAT_ADC_CHANNEL ADC_Channel_13
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff

View file

@ -92,18 +92,9 @@
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define USE_ADC
#define CURRENT_METER_ADC_GPIO GPIOB
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_0
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_0
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PB0
#define LED_STRIP
#define LED_STRIP_TIMER TIM3

View file

@ -101,26 +101,11 @@
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define VBAT_ADC_GPIO GPIOC
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_6
#define CURRENT_METER_ADC_GPIO GPIOC
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
#define RSSI_ADC_GPIO GPIOC
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define EXTERNAL1_ADC_GPIO GPIOC
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff

View file

@ -1545,7 +1545,6 @@ void taskBstMasterProcess(void)
bstMasterWriteLoop();
if (isRebootScheduled) {
stopMotors();
handleOneshotFeatureChangeOnRestart();
systemReset();
}
resetBstChecker();
@ -1555,12 +1554,14 @@ void taskBstMasterProcess(void)
static uint8_t masterWriteBufferPointer;
static uint8_t masterWriteData[DATA_BUFFER_SIZE];
static void bstMasterStartBuffer(uint8_t address) {
static void bstMasterStartBuffer(uint8_t address)
{
masterWriteData[0] = address;
masterWriteBufferPointer = 2;
}
static void bstMasterWrite8(uint8_t data) {
static void bstMasterWrite8(uint8_t data)
{
masterWriteData[masterWriteBufferPointer++] = data;
masterWriteData[1] = masterWriteBufferPointer;
}

View file

@ -103,16 +103,8 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL_GPIO GPIOA
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_9
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SCL_PIN PA9
#define I2C2_SDA_PIN PA10
#define USE_BST
#define BST_DEVICE (BSTDEV_1)
@ -120,27 +112,12 @@
#define BST_CRC_POLYNOM 0xD5
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_GPIO GPIOC
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_6
#define CURRENT_METER_ADC_GPIO GPIOC
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
#define RSSI_ADC_GPIO GPIOC
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define EXTERNAL1_ADC_GPIO GPIOC
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define LED_STRIP
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG

View file

@ -34,44 +34,29 @@
#define BEEPER_INVERTED
// tqfp48 pin 3
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOC
#define MPU6500_CS_GPIO GPIOC
#define MPU6500_CS_PIN PC14
#define MPU6500_SPI_INSTANCE SPI1
// tqfp48 pin 25
#define BMP280_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BMP280_CS_GPIO GPIOB
#define BMP280_CS_PIN GPIO_Pin_12
#define BMP280_CS_PIN PB12
#define BMP280_SPI_INSTANCE SPI2
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI1_GPIO GPIOB
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
// tqfp48 pin 39
#define SPI1_SCK_PIN PB3
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
// tqfp48 pin 40
#define SPI1_MISO_PIN PB4
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
// tqfp48 pin 41
#define SPI1_MOSI_PIN PB5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
// tqfp48 pin 26
#define SPI2_SCK_PIN PB13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
// tqfp48 pin 27
#define SPI2_MISO_PIN PB14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
// tqfp48 pin 28
#define SPI2_MOSI_PIN PB15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define USE_FLASHFS
#define USE_FLASH_M25P16
@ -139,20 +124,9 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define ADC_DMA_CHANNEL DMA2_Channel1
// tqfp48 pin 14
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
// tqfp48 pin 15
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
// mpu_int definition in sensors/initialisation.c
#define USE_EXTI

View file

@ -97,22 +97,10 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_GPIO GPIOB
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_4
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_1
#define EXTERNAL1_ADC_GPIO GPIOA
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
//#define LED_STRIP
#define LED_STRIP_TIMER TIM3

View file

@ -11,6 +11,7 @@ TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu3050.c \
drivers/accgyro_mpu6050.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6000.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp085.c \

View file

@ -150,22 +150,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_2
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PA2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1

View file

@ -144,15 +144,9 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC1
#define VBAT_ADC_CHANNEL ADC_Channel_11
#define RSSI_ADC_GPIO_PIN PC2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define CURRENT_METER_ADC_PIN PC3
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_13
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View file

@ -80,29 +80,15 @@
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define M25P16_CS_GPIO GPIOB
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define SPEKTRUM_BIND
// USART3,

View file

@ -72,23 +72,11 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
//#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define SPEKTRUM_BIND

View file

@ -88,29 +88,13 @@
#define I2C_DEVICE (I2CDEV_2)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define VBAT_ADC_GPIO GPIOC
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_6
#define CURRENT_METER_ADC_GPIO GPIOC
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
#define RSSI_ADC_GPIO GPIOC
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define EXTERNAL1_ADC_GPIO GPIOC
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
#define WS2811_GPIO GPIOA

View file

@ -119,22 +119,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_5
#define VBAT_ADC_CHANNEL ADC_Channel_2
//#define CURRENT_METER_ADC_GPIO GPIOA
//#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
//#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1

View file

@ -147,22 +147,10 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_GPIO GPIOB
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_4
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_1
#define EXTERNAL1_ADC_GPIO GPIOA
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define LED_STRIP

View file

@ -83,22 +83,10 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_GPIO GPIOB
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_4
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_1
#define EXTERNAL1_ADC_GPIO GPIOA
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM3

View file

@ -159,23 +159,11 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -210,6 +198,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define BUTTONS
#define BUTTON_A_PORT GPIOB

View file

@ -87,22 +87,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_5
#define VBAT_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define CURRENT_METER_ADC_PIN PA2
#define VBAT_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1

View file

@ -38,22 +38,17 @@
#define USE_SPI_DEVICE_2
#define PORT103R_SPI_INSTANCE SPI2
#define PORT103R_SPI_CS_GPIO GPIOB
#define PORT103R_SPI_CS_PIN PB12
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
#define M25P16_CS_GPIO PORT103R_SPI_CS_GPIO
#define M25P16_CS_PIN PORT103R_SPI_CS_PIN
#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6000_CS_GPIO PORT103R_SPI_CS_GPIO
#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6500_CS_GPIO PORT103R_SPI_CS_GPIO
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
#define GYRO
#define USE_FAKE_GYRO
@ -115,22 +110,10 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_GPIO GPIOB
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_4
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_1
#define EXTERNAL1_ADC_GPIO GPIOA
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM3

View file

@ -11,6 +11,7 @@ TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu3050.c \
drivers/accgyro_mpu6050.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6000.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp085.c \

View file

@ -20,16 +20,10 @@
#define TARGET_BOARD_IDENTIFIER "REVO"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_MSP_PORT 2
#define CONFIG_RX_SERIAL_PORT 1
#define USBD_PRODUCT_STRING "Revolution"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8020000"
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#define LED0 PB5
@ -110,13 +104,9 @@
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_11
#define VBAT_ADC_PIN PC2
#define VBAT_ADC_CHANNEL ADC_Channel_12
#define RSSI_ADC_GPIO_PIN PA0
#define RSSI_ADC_CHANNEL ADC_Channel_0
#define SENSORS_SET (SENSOR_ACC)

View file

@ -19,16 +19,10 @@
#define TARGET_BOARD_IDENTIFIER "REVN"
#define CONFIG_START_FLASH_ADDRESS (0x08060000) //0x08060000 to 0x08080000 (FLASH_Sector_7)
#define CONFIG_SERIALRX_PROVIDER 2
#define CONFIG_BLACKBOX_DEVICE 1
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_MSP_PORT 1
#define CONFIG_RX_SERIAL_PORT 2
#define USBD_PRODUCT_STRING "Revo Nano"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8010000"
#define USBD_SERIALNUMBER_STRING "0x8010000"
#endif
#define LED0 PC14
@ -87,18 +81,9 @@
#define I2C_DEVICE (I2CDEV_3)
#define USE_ADC
//FLEXI-IO 6
#define CURRENT_METER_ADC_PIN PA7
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
//FLEXI-IO 7
#define VBAT_ADC_PIN PA6
#define VBAT_ADC_CHANNEL ADC_Channel_6
//FLEXI-IO 8
#define RSSI_ADC_PIN PA5
#define RSSI_ADC_CHANNEL ADC_Channel_5
//#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG)

View file

@ -106,23 +106,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1

View file

@ -94,12 +94,7 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOB
#define VBAT_ADC_GPIO_PIN GPIO_Pin_2
#define VBAT_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -117,8 +112,10 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL)
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define SPEKTRUM_BIND
// USART2, PA15

View file

@ -135,17 +135,12 @@
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define VBAT_ADC_PIN PA0
//#define USE_QUAD_MIXER_ONLY
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
@ -155,6 +150,7 @@
#define USE_SERVOS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -87,30 +87,10 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL_GPIO GPIOA
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_9
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_7
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_4
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA7
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View file

@ -114,23 +114,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -148,6 +135,8 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX

View file

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP ONBOARDFLASH
FEATURES = ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \

View file

@ -136,22 +136,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -185,7 +173,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
#define SPEKTRUM_BIND
// USART3,

View file

@ -145,20 +145,9 @@
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -193,6 +182,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define BUTTONS
#define BUTTON_A_PORT GPIOB

View file

@ -139,26 +139,11 @@
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define VBAT_ADC_GPIO GPIOC
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_6
#define CURRENT_METER_ADC_GPIO GPIOC
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
#define RSSI_ADC_GPIO GPIOC
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define EXTERNAL1_ADC_GPIO GPIOC
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define LED_STRIP
#define LED_STRIP_TIMER TIM16

View file

@ -0,0 +1,105 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP
};

View file

@ -0,0 +1,161 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "XRC3"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PC14
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define MPU6000_CS_PIN PA15
#define MPU6000_SPI_INSTANCE SPI1
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PC13
#define USE_EXTI
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#ifndef UART1_GPIO
#define UART1_TX_PIN GPIO_Pin_9 // PA9
#define UART1_RX_PIN GPIO_Pin_10 // PA10
#define UART1_GPIO GPIOA
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
#endif
#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK
#define UART2_RX_PIN GPIO_Pin_3 // PA15
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource2
#define UART2_RX_PINSOURCE GPIO_PinSource3
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
#define SOFTSERIAL_2_TIMER TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
//GPIO_AF_1
#define SPI1_NSS_PIN PA15
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View file

@ -0,0 +1,16 @@
F3_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH
TARGET_FLAGS = -DSPRACINGF3
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_spi_mpu6000.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/display_ug2864hsweg01.h \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_softserial.c \
drivers/sonar_hcsr04.c

View file

@ -0,0 +1,104 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP
};

View file

@ -0,0 +1,126 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "ZCF3"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB8
#define BEEPER PC15
#define BEEPER_INVERTED
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_BMP280
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define SERIAL_PORT_COUNT 3
#ifndef UART1_GPIO
#define UART1_TX_PIN GPIO_Pin_9 // PA9
#define UART1_RX_PIN GPIO_Pin_10 // PA10
#define UART1_GPIO GPIOA
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
#endif
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
#define UART2_RX_PIN GPIO_Pin_15 // PA15
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource14
#define UART2_RX_PINSOURCE GPIO_PinSource15
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_SPI
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard)
#define SPI1_NSS_PIN PB9
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define MPU6500_CS_PIN PB9
#define MPU6500_SPI_INSTANCE SPI1
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View file

@ -0,0 +1,11 @@
F3_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp280.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c

View file

@ -17,12 +17,23 @@
#pragma once
#define I2C1_OVERCLOCK true
#define I2C2_OVERCLOCK true
/* STM32F4 specific settings that apply to all F4 targets */
#ifdef STM32F4
#define TASK_GYROPID_DESIRED_PERIOD 125
#define SCHEDULER_DELAY_LIMIT 10
#else
#define USE_SLOW_SERIAL_CLI
#define I2C3_OVERCLOCK true
#else /* when not an F4 */
#define TASK_GYROPID_DESIRED_PERIOD 1000
#define SCHEDULER_DELAY_LIMIT 100
#endif
#define SERIAL_RX

View file

@ -153,12 +153,11 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
*******************************************************************************/
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
{
if(USB_Tx_State!=1)
{
VCP_DataTx(ptrBuffer,sendLength);
return sendLength;
}
if (USB_Tx_State)
return 0;
VCP_DataTx(ptrBuffer, sendLength);
return sendLength;
}
/**
@ -171,7 +170,6 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
*/
static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len)
{
uint16_t ptr = APP_Rx_ptr_in;
uint32_t i;