1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Merge branch 'master' of github.com:betaflight/betaflight into feature/f4-dma-osd

This commit is contained in:
nathan 2016-07-16 09:25:40 -07:00
commit 338d548e11
134 changed files with 1669 additions and 1624 deletions

View file

@ -548,8 +548,8 @@ VPATH := $(VPATH):$(STDPERIPH_DIR)/src
# Find out if ccache is installed on the system
CCACHE := ccache
RESULT = $(shell which $(CCACHE))
ifeq ($(RESULT),)
RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
ifneq ($(RESULT),0)
CCACHE :=
endif

View file

@ -632,7 +632,7 @@ static void writeInterframe(void)
arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT);
blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
/*
/*
* The PID I field changes very slowly, most of the time +-2, so use an encoding
* that can pack all three fields into one byte in that situation.
*/
@ -1140,6 +1140,7 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName);
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
@ -1218,6 +1219,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_q:%d", (int)(masterConfig.gyro_soft_notch_q * 10.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
@ -1314,7 +1317,7 @@ static void blackboxCheckAndLogFlightMode()
}
}
/*
/*
* Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
* the portion of logged loop iterations.
*/

View file

@ -507,7 +507,7 @@ void blackboxWriteFloat(float value)
/**
* If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now.
*
*
* Intended to be called regularly for the blackbox device to perform housekeeping.
*/
void blackboxDeviceFlush(void)

View file

@ -56,24 +56,39 @@ float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT)
}
/* sets up a biquad Filter */
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate)
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate)
{
biquadFilterInit(filter, filterFreq, refreshRate, BIQUAD_Q, FILTER_LPF);
}
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType)
{
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
// setup variables
const float omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate;
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
const float omega = 2 * M_PI_FLOAT * filterFreq / sampleRate;
const float sn = sinf(omega);
const float cs = cosf(omega);
//this is wrong, should be hyperbolic sine
//alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn);
const float alpha = sn / (2 * BIQUAD_Q);
const float alpha = sn / (2 * Q);
const float b0 = (1 - cs) / 2;
const float b1 = 1 - cs;
const float b2 = (1 - cs) / 2;
const float a0 = 1 + alpha;
const float a1 = -2 * cs;
const float a2 = 1 - alpha;
float b0, b1, b2, a0, a1, a2;
switch (filterType) {
case FILTER_LPF:
b0 = (1 - cs) / 2;
b1 = 1 - cs;
b2 = (1 - cs) / 2;
a0 = 1 + alpha;
a1 = -2 * cs;
a2 = 1 - alpha;
break;
case FILTER_NOTCH:
b0 = 1;
b1 = -2 * cs;
b2 = 1;
a0 = 1 + alpha;
a1 = -2 * cs;
a2 = 1 - alpha;
break;
}
// precompute the coefficients
filter->b0 = b0 / a0;

View file

@ -29,8 +29,13 @@ typedef struct biquadFilter_s {
float d1, d2;
} biquadFilter_t;
typedef enum {
FILTER_LPF,
FILTER_NOTCH
} filterType_e;
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate);
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate);
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType);
float biquadFilterApply(biquadFilter_t *filter, float input);
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);

View file

@ -231,7 +231,7 @@ int32_t quickMedianFilter5(int32_t * v)
QMF_SORT(p[0], p[1]); QMF_SORT(p[3], p[4]); QMF_SORT(p[0], p[3]);
QMF_SORT(p[1], p[4]); QMF_SORT(p[1], p[2]); QMF_SORT(p[2], p[3]);
QMF_SORT(p[1], p[2]);
QMF_SORT(p[1], p[2]);
return p[2];
}
@ -279,7 +279,7 @@ float quickMedianFilter5f(float * v)
QMF_SORTF(p[0], p[1]); QMF_SORTF(p[3], p[4]); QMF_SORTF(p[0], p[3]);
QMF_SORTF(p[1], p[4]); QMF_SORTF(p[1], p[2]); QMF_SORTF(p[2], p[3]);
QMF_SORTF(p[1], p[2]);
QMF_SORTF(p[1], p[2]);
return p[2];
}

View file

@ -56,7 +56,7 @@ typedef void (*putcf) (void *, char);
static putcf stdout_putf;
static void *stdout_putp;
// print bf, padded from left to at least n characters.
// print bf, padded from left to at least n characters.
// padding is zero ('0') if z!=0, space (' ') otherwise
static int putchw(void *putp, putcf putf, int n, char z, char *bf)
{

View file

@ -159,7 +159,7 @@ size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
#else
// use the last flash pages for storage
#ifndef CONFIG_START_FLASH_ADDRESS
#ifndef CONFIG_START_FLASH_ADDRESS
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif
#endif
@ -349,7 +349,7 @@ void resetSerialConfig(serialConfig_t *serialConfig)
serialConfig->reboot_character = 'R';
}
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
{
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
@ -366,7 +366,7 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
}
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
{
rcControlsConfig->deadband = 0;
rcControlsConfig->yaw_deadband = 0;
@ -374,7 +374,7 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
rcControlsConfig->alt_hold_fast_change = 1;
}
void resetMixerConfig(mixerConfig_t *mixerConfig)
void resetMixerConfig(mixerConfig_t *mixerConfig)
{
mixerConfig->yaw_motor_direction = 1;
#ifdef USE_SERVOS
@ -441,6 +441,7 @@ static void resetConf(void)
featureSet(FEATURE_VBAT);
#endif
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
@ -455,6 +456,8 @@ static void resetConf(void)
masterConfig.gyro_sync_denom = 4;
#endif
masterConfig.gyro_soft_lpf_hz = 100;
masterConfig.gyro_soft_notch_hz = 0;
masterConfig.gyro_soft_notch_q = 5;
masterConfig.pid_process_denom = 2;
@ -657,6 +660,7 @@ static void resetConf(void)
targetConfiguration();
#endif
// copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
@ -715,7 +719,7 @@ void activateConfig(void)
&currentProfile->pidProfile
);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz, masterConfig.gyro_soft_notch_hz, masterConfig.gyro_soft_notch_q);
#ifdef TELEMETRY
telemetryUseConfig(&masterConfig.telemetryConfig);

View file

@ -24,6 +24,8 @@
#endif
#define MAX_RATEPROFILES 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
#define MAX_NAME_LENGTH 16
typedef enum {
FEATURE_RX_PPM = 1 << 0,

View file

@ -56,9 +56,11 @@ typedef struct master_t {
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
uint8_t gyro_sync_denom; // Gyro sample divider
uint8_t gyro_soft_lpf_hz; // Biqyad gyro lpf hz
uint8_t gyro_soft_lpf_hz; // Biquad gyro lpf hz
uint16_t gyro_soft_notch_hz; // Biquad gyro notch hz
uint8_t gyro_soft_notch_q; // Biquad gyro notch quality
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
@ -137,7 +139,7 @@ typedef struct master_t {
profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index;
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
@ -161,6 +163,9 @@ typedef struct master_t {
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
char name[MAX_NAME_LENGTH+1];
} master_t;
extern master_t masterConfig;

View file

@ -50,5 +50,6 @@ typedef enum {
DEBUG_MIXER,
DEBUG_AIRMODE,
DEBUG_PIDLOOP,
DEBUG_NOTCH,
DEBUG_COUNT
} debugType_e;

View file

@ -252,7 +252,7 @@ void mpuIntExtiInit(void)
EXTIEnable(mpuIntIO, true);
#endif
mpuExtiInitDone = true;
mpuExtiInitDone = true;
}
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)

View file

@ -18,7 +18,7 @@
#pragma once
#include "exti.h"
// MPU6050
#define MPU_RA_WHO_AM_I 0x75
#define MPU_RA_WHO_AM_I_LEGACY 0x00
@ -119,7 +119,7 @@
typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data);
typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data);
typedef void(*mpuResetFuncPtr)(void);
typedef void(*mpuResetFuncPtr)(void);
typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each

View file

@ -104,7 +104,7 @@ static void mpu6050GyroInit(uint8_t lpf)
delay(100);
ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure
delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure
ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec

View file

@ -158,7 +158,7 @@ bool mpu6000SpiDetect(void)
uint8_t in;
uint8_t attemptsRemaining = 5;
#ifdef MPU6000_CS_PIN
#ifdef MPU6000_CS_PIN
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
#endif
IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
@ -253,7 +253,7 @@ static void mpu6000AccAndGyroInit(void) {
delayMicroseconds(15);
#endif
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
delayMicroseconds(1);
mpuSpi6000InitDone = true;

View file

@ -54,7 +54,7 @@ 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);
@ -123,7 +123,7 @@ 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;
@ -176,7 +176,7 @@ 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);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
mpuSpi9250InitDone = true; //init done
}
@ -208,7 +208,7 @@ bool mpu9250SpiDetect(void)
}
} while (attemptsRemaining--);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
return true;
}

View file

@ -24,14 +24,14 @@
#define ADC_TAG_MAP_COUNT 16
#elif defined(STM32F3)
#define ADC_TAG_MAP_COUNT 39
#else
#else
#define ADC_TAG_MAP_COUNT 10
#endif
#endif
typedef enum ADCDevice {
ADCINVALID = -1,
ADCDEV_1 = 0,
#if defined(STM32F3)
#if defined(STM32F3)
ADCDEV_2,
ADCDEV_MAX = ADCDEV_2,
#elif defined(STM32F4)

View file

@ -24,9 +24,6 @@
#include "build_config.h"
#include "system.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"
@ -38,13 +35,13 @@
#define ADC_INSTANCE ADC1
#endif
const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }
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)
if (instance == ADC1)
return ADCDEV_1;
/* TODO -- ADC2 available on large 10x devices.
@ -54,7 +51,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
return ADCINVALID;
}
const adcTagMap_t adcTagMap[] = {
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
@ -64,7 +61,7 @@ const adcTagMap_t adcTagMap[] = {
{ 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
{ DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12
};
// Driver for STM32F103CB onboard ADC
@ -84,7 +81,6 @@ void adcInit(drv_adc_config_t *init)
UNUSED(init);
#endif
uint8_t i;
uint8_t configuredAdcChannels = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -117,9 +113,9 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
const adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -163,7 +159,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View file

@ -21,7 +21,6 @@
#include "platform.h"
#include "system.h"
#include "common/utils.h"
#include "gpio.h"
#include "sensor.h"
@ -32,16 +31,18 @@
#include "io.h"
#include "rcc.h"
#include "common/utils.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#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 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[] = {
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
@ -85,7 +86,7 @@ const adcTagMap_t adcTagMap[] = {
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
if (instance == ADC1)
return ADCDEV_1;
if (instance == ADC2)
@ -100,7 +101,6 @@ void adcInit(drv_adc_config_t *init)
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint8_t i;
uint8_t adcChannelCount = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -133,9 +133,9 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -203,7 +203,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View file

@ -26,8 +26,6 @@
#include "io_impl.h"
#include "rcc.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
@ -38,13 +36,13 @@
#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 }
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[] = {
const adcTagMap_t adcTagMap[] = {
/*
{ DEFIO_TAG_E__PF3, ADC_Channel_9 },
{ DEFIO_TAG_E__PF4, ADC_Channel_14 },
@ -75,7 +73,7 @@ const adcTagMap_t adcTagMap[] = {
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
if (instance == ADC1)
return ADCDEV_1;
/*
if (instance == ADC2) // TODO add ADC2 and 3
@ -128,7 +126,7 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)

View file

@ -35,7 +35,7 @@
#ifdef BARO
#if defined(BARO_EOC_GPIO)
#if defined(BARO_EOC_GPIO)
static IO_t eocIO;
@ -49,7 +49,7 @@ void bmp085_extiHandler(extiCallbackRec_t* cb)
isConversionComplete = true;
}
bool bmp085TestEOCConnected(const bmp085Config_t *config);
bool bmp085TestEOCConnected(const bmp085Config_t *config);
# endif
typedef struct {
@ -139,7 +139,7 @@ static IO_t xclrIO;
#endif
void bmp085InitXclrIO(const bmp085Config_t *config)
void bmp085InitXclrIO(const bmp085Config_t *config)
{
if (!xclrIO && config && config->xclrIO) {
xclrIO = IOGetByTag(config->xclrIO);
@ -184,7 +184,7 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
delay(20); // datasheet says 10ms, we'll be careful and do 20.
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3;

View file

@ -19,7 +19,7 @@
typedef struct bmp085Config_s {
ioTag_t xclrIO;
ioTag_t eocIO;
ioTag_t eocIO;
} bmp085Config_t;
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);

View file

@ -26,7 +26,7 @@
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
#endif
#endif
typedef enum I2CDevice {
I2CINVALID = -1,

View file

@ -47,35 +47,35 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#define IOCFG_I2C IOCFG_AF_OD
#endif
#ifndef I2C1_SCL
#define I2C1_SCL PB8
#ifndef I2C1_SCL
#define I2C1_SCL PB8
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB9
#ifndef I2C1_SDA
#define I2C1_SDA PB9
#endif
#else
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
#ifdef STM32F4
#ifndef I2C3_SCL
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PB4
#ifndef I2C3_SDA
#define I2C3_SDA PB4
#endif
#endif
@ -93,7 +93,7 @@ static i2cState_t i2cState[] = {
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 }
};
};
void I2C1_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_1);
@ -121,7 +121,7 @@ void I2C3_EV_IRQHandler(void) {
}
#endif
static bool i2cHandleHardwareFailure(I2CDevice device)
static bool i2cHandleHardwareFailure(I2CDevice device)
{
i2cErrorCount++;
// reinit peripheral + clock out garbage
@ -129,7 +129,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device)
return false;
}
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
if (device == I2CINVALID)
@ -138,7 +138,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
@ -171,12 +171,12 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
return !(state->error);
}
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWriteBuffer(device, addr_, reg_, 1, &data);
}
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
if (device == I2CINVALID)
return false;
@ -369,7 +369,7 @@ void i2c_ev_handler(I2CDevice device) {
}
}
void i2cInit(I2CDevice device)
void i2cInit(I2CDevice device)
{
if (device == I2CINVALID)
return;
@ -392,7 +392,7 @@ void i2cInit(I2CDevice device)
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
i2cUnstick(scl, sda);
// Init pins
#ifdef STM32F4
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);

View file

@ -39,18 +39,18 @@
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_GPIO_AF GPIO_AF_4
#define I2C_GPIO_AF GPIO_AF_4
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PF4
#ifndef I2C2_SCL
#define I2C2_SCL PF4
#endif
#ifndef I2C2_SDA
#ifndef I2C2_SDA
#define I2C2_SDA PA10
#endif
@ -82,7 +82,7 @@ void i2cInit(I2CDevice device)
I2C_TypeDef *I2Cx;
I2Cx = i2c->dev;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
@ -108,7 +108,7 @@ void i2cInit(I2CDevice device)
I2C_Init(I2Cx, &i2cInit);
I2C_StretchClockCmd(I2Cx, ENABLE);
I2C_Cmd(I2Cx, ENABLE);
}
@ -122,7 +122,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
addr_ <<= 1;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;
@ -188,7 +188,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t*
addr_ <<= 1;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;

View file

@ -36,7 +36,7 @@
#ifndef GPIO_AF_SPI3
#define GPIO_AF_SPI3 GPIO_AF_6
#endif
#endif
#endif
#ifndef SPI1_SCK_PIN
#define SPI1_NSS_PIN PA4
@ -84,7 +84,7 @@ static spiDevice_t spiHardwareMap[] = {
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
{
if (instance == SPI1)
if (instance == SPI1)
return SPIDEV_1;
if (instance == SPI2)

View file

@ -31,8 +31,6 @@
#define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz)
#else
#error "Unknown processor"
#endif
/*

View file

@ -65,7 +65,7 @@ typedef struct dmaChannelDescriptor_s {
#define DMA_IT_TEIF ((uint32_t)0x00000008)
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
#define DMA_IT_FEIF ((uint32_t)0x00000001)
#else
typedef enum {

View file

@ -45,7 +45,6 @@ static dmaChannelDescriptor_t dmaDescriptors[] = {
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream5, 38, DMA2_Stream5_IRQn, RCC_AHB1Periph_DMA2),
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream6, 48, DMA2_Stream6_IRQn, RCC_AHB1Periph_DMA2),
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream7, 54, DMA2_Stream7_IRQn, RCC_AHB1Periph_DMA2),
};
/*
@ -68,7 +67,6 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
void dmaInit(void)
{
// TODO: Do we need this?

View file

@ -24,22 +24,22 @@ static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
#if defined(STM32F1) || defined(STM32F4)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_IRQn,
EXTI3_IRQn,
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_IRQn,
EXTI3_IRQn,
EXTI4_IRQn,
EXTI9_5_IRQn,
EXTI9_5_IRQn,
EXTI15_10_IRQn
};
#elif defined(STM32F3)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_TS_IRQn,
EXTI3_IRQn,
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_TS_IRQn,
EXTI3_IRQn,
EXTI4_IRQn,
EXTI9_5_IRQn,
EXTI9_5_IRQn,
EXTI15_10_IRQn
};
#else

View file

@ -199,7 +199,7 @@ static bool m25p16_readIdentification()
bool m25p16_init()
{
#ifdef M25P16_CS_PIN
#ifdef M25P16_CS_PIN
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
#endif
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0);

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef INVERTER
#ifdef INVERTER
#include "io.h"
#include "io_impl.h"

View file

@ -52,7 +52,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)

View file

@ -12,7 +12,7 @@ typedef struct ioRec_s {
GPIO_TypeDef *gpio;
uint16_t pin;
resourceOwner_t owner;
resourceType_t resource;
resourceType_t resource;
uint8_t index;
} ioRec_t;
@ -26,7 +26,7 @@ int IO_GPIO_PortSource(IO_t io);
#if defined(STM32F3) || defined(STM32F4)
int IO_EXTI_PortSourceGPIO(IO_t io);
int IO_EXTI_PinSource(IO_t io);
int IO_EXTI_PinSource(IO_t io);
#endif
GPIO_TypeDef* IO_GPIO(IO_t io);

View file

@ -27,12 +27,12 @@ static const IO_t leds[] = {
DEFIO_IO(LED0),
#else
DEFIO_IO(NONE),
#endif
#endif
#ifdef LED1
DEFIO_IO(LED1),
#else
DEFIO_IO(NONE),
#endif
#endif
#ifdef LED2
DEFIO_IO(LED2),
#else
@ -78,15 +78,14 @@ uint8_t ledPolarity = 0
#endif
;
uint8_t ledOffset = 0;
static uint8_t ledOffset = 0;
void ledInit(bool alternative_led)
{
uint32_t i;
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led)
if (alternative_led) {
ledOffset = LED_NUMBER;
}
#else
UNUSED(alternative_led);
#endif
@ -95,7 +94,7 @@ void ledInit(bool alternative_led)
LED1_OFF;
LED2_OFF;
for (i = 0; i < LED_NUMBER; i++) {
for (int i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
@ -114,6 +113,6 @@ void ledToggle(int led)
void ledSet(int led, bool on)
{
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
}

View file

@ -31,8 +31,8 @@
#ifdef LED_STRIP
#if !defined(WS2811_PIN)
#define WS2811_PIN PA0
#if !defined(WS2811_PIN)
#define WS2811_PIN PA0
#define WS2811_TIMER TIM5
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2

View file

@ -157,7 +157,7 @@ void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor) {
}
#endif
void max7456_init(uint8_t video_system)
void max7456_init(uint8_t video_system)
{
uint8_t max_screen_rows;
uint8_t srdata = 0;

View file

@ -30,11 +30,6 @@
#include "pwm_rx.h"
#include "pwm_mapping.h"
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);
/*
Configuration maps
@ -100,7 +95,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
int channelIndex = 0;
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
// this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ]
if (init->airplane)
i = 2; // switch to air hardware config
@ -265,7 +260,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(WS2811_TIMER)
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
if (init->useLEDStrip) {
if (init->useLEDStrip) {
if (timerIndex >= PWM13 && timerIndex <= PWM14) {
type = MAP_TO_SERVO_OUTPUT;
}
@ -313,14 +308,14 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
}
#endif
if (init->useFastPwm) {
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 ;
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT;
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_MOTOR_MODE_BRUSHED;
} else {
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM ;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM;
}
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].index = pwmOutputConfiguration.motorCount;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].timerHardware = timerHardwarePtr;

View file

@ -30,24 +30,8 @@
#error Invalid motor/servo/port configuration
#endif
#define PULSE_1MS (1000) // 1ms pulse width
#define MAX_INPUTS 8
#define PWM_TIMER_MHZ 1
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT42_TIMER_MHZ 21
#define ONESHOT125_TIMER_MHZ 12
#define PWM_BRUSHED_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#else
#define PWM_BRUSHED_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define ONESHOT42_TIMER_MHZ 24
#define ONESHOT125_TIMER_MHZ 8
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef struct sonarIOConfig_s {
ioTag_t triggerTag;
@ -133,7 +117,7 @@ enum {
PWM13,
PWM14,
PWM15,
PWM16,
PWM16,
PWM17,
PWM18,
PWM19,

View file

@ -17,21 +17,31 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
#include "platform.h"
#include "io.h"
#include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h"
#include "pwm_output.h"
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT125_TIMER_MHZ 12
#define ONESHOT42_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#define PWM_BRUSHED_TIMER_MHZ 21
#else
#define ONESHOT125_TIMER_MHZ 8
#define ONESHOT42_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define PWM_BRUSHED_TIMER_MHZ 24
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct {
@ -52,6 +62,8 @@ static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
static uint8_t allocatedOutputPortCount = 0;
static bool pwmMotorsEnabled = true;
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t ouputPolarity)
{
TIM_OCInitTypeDef TIM_OCInitStructure;
@ -65,22 +77,22 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
switch (channel) {
case TIM_Channel_1:
TIM_OC1Init(tim, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_2:
TIM_OC2Init(tim, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_3:
TIM_OC3Init(tim, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_4:
TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_1:
TIM_OC1Init(tim, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_2:
TIM_OC2Init(tim, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_3:
TIM_OC3Init(tim, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_4:
TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break;
}
}
@ -90,7 +102,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz);
IO_t io = IOGetByTag(timerHardware->tag);
const IO_t io = IOGetByTag(timerHardware->tag);
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
IOConfigGPIO(io, IOCFG_AF_PP);
@ -102,24 +114,24 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
TIM_Cmd(timerHardware->tim, ENABLE);
switch (timerHardware->channel) {
case TIM_Channel_1:
p->ccr = &timerHardware->tim->CCR1;
break;
case TIM_Channel_2:
p->ccr = &timerHardware->tim->CCR2;
break;
case TIM_Channel_3:
p->ccr = &timerHardware->tim->CCR3;
break;
case TIM_Channel_4:
p->ccr = &timerHardware->tim->CCR4;
break;
case TIM_Channel_1:
p->ccr = &timerHardware->tim->CCR1;
break;
case TIM_Channel_2:
p->ccr = &timerHardware->tim->CCR2;
break;
case TIM_Channel_3:
p->ccr = &timerHardware->tim->CCR3;
break;
case TIM_Channel_4:
p->ccr = &timerHardware->tim->CCR4;
break;
}
p->period = period;
p->tim = timerHardware->tim;
*p->ccr = 0;
return p;
}
@ -133,16 +145,16 @@ static void pwmWriteStandard(uint8_t index, uint16_t value)
*motors[index]->ccr = value;
}
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteOneShot125(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f));
}
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteMultiShot(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW);
@ -150,15 +162,14 @@ static void pwmWriteMultiShot(uint8_t index, uint16_t value)
void pwmWriteMotor(uint8_t index, uint16_t value)
{
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled)
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) {
motors[index]->pwmWritePtr(index, value);
}
}
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
{
uint8_t index;
for(index = 0; index < motorCount; index++){
for(int index = 0; index < motorCount; index++){
// Set the compare register to 0, which stops the output pulsing if the timer overflows
*motors[index]->ccr = 0;
}
@ -176,17 +187,14 @@ void pwmEnableMotors(void)
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
{
uint8_t index;
TIM_TypeDef *lastTimerPtr = NULL;
for (index = 0; index < motorCount; index++) {
for (int 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) {
lastTimerPtr = motors[index]->tim;
timerForceOverflow(motors[index]->tim);
}
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
// This compare register will be set to the output value on the next main loop.
*motors[index]->ccr = 0;
@ -195,44 +203,46 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
const uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
}
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_TIMER_MHZ * 1000000;
const uint32_t hz = PWM_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
}
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse)
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType)
{
uint32_t timerMhzCounter;
pwmWriteFuncPtr pwmWritePtr;
switch (fastPwmProtocolType) {
default:
case (PWM_TYPE_ONESHOT125):
timerMhzCounter = ONESHOT125_TIMER_MHZ;
break;
case (PWM_TYPE_ONESHOT42):
timerMhzCounter = ONESHOT42_TIMER_MHZ;
break;
case (PWM_TYPE_MULTISHOT):
timerMhzCounter = MULTISHOT_TIMER_MHZ;
default:
case (PWM_TYPE_ONESHOT125):
timerMhzCounter = ONESHOT125_TIMER_MHZ;
pwmWritePtr = pwmWriteOneShot125;
break;
case (PWM_TYPE_ONESHOT42):
timerMhzCounter = ONESHOT42_TIMER_MHZ;
pwmWritePtr = pwmWriteOneShot42;
break;
case (PWM_TYPE_MULTISHOT):
timerMhzCounter = MULTISHOT_TIMER_MHZ;
pwmWritePtr = pwmWriteMultiShot;
break;
}
if (motorPwmRate > 0) {
uint32_t hz = timerMhzCounter * 1000000;
const uint32_t hz = timerMhzCounter * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse);
} else {
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0);
}
motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot :
((fastPwmProtocolType == PWM_TYPE_ONESHOT125) ? pwmWriteOneShot125 :
pwmWriteOneShot42);
motors[motorIndex]->pwmWritePtr = pwmWritePtr;
}
#ifdef USE_SERVOS
@ -243,7 +253,8 @@ void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
void pwmWriteServo(uint8_t index, uint16_t value)
{
if (servos[index] && index < MAX_SERVOS)
if (servos[index] && index < MAX_SERVOS) {
*servos[index]->ccr = value;
}
}
#endif

View file

@ -25,6 +25,12 @@ typedef enum {
PWM_TYPE_BRUSHED
} motorPwmProtocolTypes_e;
struct timerHardware_s;
void pwmBrushedMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType);
void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);

View file

@ -1,7 +1,7 @@
#pragma once
#define RESOURCE_INDEX(x) x + 1
#define RESOURCE_INDEX(x) (x + 1)
typedef enum {
OWNER_FREE = 0,

View file

@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void)
#ifdef SDCARD_DETECT_PIN
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0);
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
#endif
}
@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void)
#ifdef SDCARD_DETECT_PIN
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0);
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
#endif
}

View file

@ -114,8 +114,8 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
{
if (options & SERIAL_BIDIR) {
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
(options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD,
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
(options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD,
(options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
);

View file

@ -64,17 +64,17 @@ typedef struct uartDevice_s {
//static uartPort_t uartPort[MAX_UARTS];
#ifdef USE_UART1
static uartDevice_t uart1 =
{
static uartDevice_t uart1 =
{
.DMAChannel = DMA_Channel_4,
.txDMAStream = DMA2_Stream7,
#ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA2_Stream5,
#endif
.dev = USART1,
.rx = IO_TAG(UART1_RX_PIN),
.tx = IO_TAG(UART1_TX_PIN),
.af = GPIO_AF_USART1,
.dev = USART1,
.rx = IO_TAG(UART1_RX_PIN),
.tx = IO_TAG(UART1_TX_PIN),
.af = GPIO_AF_USART1,
#ifdef UART1_AHB1_PERIPHERALS
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
#endif
@ -87,17 +87,17 @@ static uartDevice_t uart1 =
#endif
#ifdef USE_UART2
static uartDevice_t uart2 =
{
static uartDevice_t uart2 =
{
.DMAChannel = DMA_Channel_4,
#ifdef USE_UART2_RX_DMA
.rxDMAStream = DMA1_Stream5,
#endif
.txDMAStream = DMA1_Stream6,
.dev = USART2,
.rx = IO_TAG(UART2_RX_PIN),
.tx = IO_TAG(UART2_TX_PIN),
.af = GPIO_AF_USART2,
.dev = USART2,
.rx = IO_TAG(UART2_RX_PIN),
.tx = IO_TAG(UART2_TX_PIN),
.af = GPIO_AF_USART2,
#ifdef UART2_AHB1_PERIPHERALS
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
#endif
@ -110,17 +110,17 @@ static uartDevice_t uart2 =
#endif
#ifdef USE_UART3
static uartDevice_t uart3 =
{
static uartDevice_t uart3 =
{
.DMAChannel = DMA_Channel_4,
#ifdef USE_UART3_RX_DMA
.rxDMAStream = DMA1_Stream1,
#endif
.txDMAStream = DMA1_Stream3,
.dev = USART3,
.rx = IO_TAG(UART3_RX_PIN),
.tx = IO_TAG(UART3_TX_PIN),
.af = GPIO_AF_USART3,
.dev = USART3,
.rx = IO_TAG(UART3_RX_PIN),
.tx = IO_TAG(UART3_TX_PIN),
.af = GPIO_AF_USART3,
#ifdef UART3_AHB1_PERIPHERALS
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
#endif
@ -133,17 +133,17 @@ static uartDevice_t uart3 =
#endif
#ifdef USE_UART4
static uartDevice_t uart4 =
{
static uartDevice_t uart4 =
{
.DMAChannel = DMA_Channel_4,
#ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA1_Stream2,
#endif
.txDMAStream = DMA1_Stream4,
.dev = UART4,
.rx = IO_TAG(UART4_RX_PIN),
.tx = IO_TAG(UART4_TX_PIN),
.af = GPIO_AF_UART4,
.dev = UART4,
.rx = IO_TAG(UART4_RX_PIN),
.tx = IO_TAG(UART4_TX_PIN),
.af = GPIO_AF_UART4,
#ifdef UART4_AHB1_PERIPHERALS
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
#endif
@ -156,17 +156,17 @@ static uartDevice_t uart4 =
#endif
#ifdef USE_UART5
static uartDevice_t uart5 =
{
static uartDevice_t uart5 =
{
.DMAChannel = DMA_Channel_4,
#ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA1_Stream0,
#endif
.txDMAStream = DMA2_Stream7,
.dev = UART5,
.rx = IO_TAG(UART5_RX_PIN),
.tx = IO_TAG(UART5_TX_PIN),
.af = GPIO_AF_UART5,
.dev = UART5,
.rx = IO_TAG(UART5_RX_PIN),
.tx = IO_TAG(UART5_TX_PIN),
.af = GPIO_AF_UART5,
#ifdef UART5_AHB1_PERIPHERALS
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
#endif
@ -179,17 +179,17 @@ static uartDevice_t uart5 =
#endif
#ifdef USE_UART6
static uartDevice_t uart6 =
{
static uartDevice_t uart6 =
{
.DMAChannel = DMA_Channel_5,
#ifdef USE_UART6_RX_DMA
.rxDMAStream = DMA2_Stream1,
#endif
.txDMAStream = DMA2_Stream6,
.dev = USART6,
.rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN),
.af = GPIO_AF_USART6,
.dev = USART6,
.rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN),
.af = GPIO_AF_USART6,
#ifdef UART6_AHB1_PERIPHERALS
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
#endif
@ -344,7 +344,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
}
if (mode & MODE_RX) {
if (mode & MODE_RX) {
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
}
@ -376,6 +376,7 @@ void USART1_IRQHandler(void)
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART2

View file

@ -36,7 +36,7 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void)
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC

View file

@ -34,7 +34,7 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void)
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC

View file

@ -41,7 +41,7 @@ void systemReset(void)
NVIC_SystemReset();
}
void systemResetToBootloader(void)
void systemResetToBootloader(void)
{
if (mpuConfiguration.reset)
mpuConfiguration.reset();

View file

@ -253,7 +253,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
}
#else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
#endif
#endif
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;

View file

@ -87,7 +87,7 @@ typedef struct timerHardware_s {
} timerHardware_t;
enum {
TIMER_OUTPUT_ENABLED = 0x01,
TIMER_OUTPUT_ENABLED = 0x01,
TIMER_OUTPUT_INVERTED = 0x02
};

View file

@ -23,10 +23,10 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM8, .rcc = RCC_APB1(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
#endif
};

View file

@ -54,7 +54,7 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
*/
#define CCMR_OFFSET ((uint16_t)0x0018)
#define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F)
#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF)
#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF)
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode)
{

View file

@ -66,7 +66,7 @@ bool usbCableIsInserted(void)
void usbGenerateDisconnectPulse(void)
{
/* Pull down PA12 to create USB disconnect pulse */
IO_t usbPin = IOGetByTag(IO_TAG(PA12));
IO_t usbPin = IOGetByTag(IO_TAG(PA12));
IOConfigGPIO(usbPin, IOCFG_OUT_OD);
IOHi(usbPin);

View file

@ -179,7 +179,7 @@ void rtc6705SetFreq(uint16_t freq)
uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers)
uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers)
val_hex |= RTC6705_SET_WRITE;
val_hex |= (val_a << 5);
val_hex |= (val_n << 12);

View file

@ -956,7 +956,7 @@ void filterServos(void)
if (mixerConfig->servo_lowpass_enable) {
for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) {
if (!servoFilterIsSet) {
biquadFilterInit(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime);
biquadFilterInitLPF(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime);
servoFilterIsSet = true;
}

View file

@ -71,12 +71,12 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using
void setTargetPidLooptime(uint8_t pidProcessDenom)
void setTargetPidLooptime(uint8_t pidProcessDenom)
{
targetPidLooptime = gyro.targetLooptime * pidProcessDenom;
}
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)
{
uint16_t dynamicKi;
uint16_t resetRate;

View file

@ -1069,7 +1069,7 @@ static void gpsHandlePassthrough(uint8_t data)
#endif
}
void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
{

View file

@ -672,8 +672,8 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx
applyStepAdjustment(controlRateConfig, adjustmentFunction, delta);
} else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) {
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
applySelectAdjustment(adjustmentFunction, position);
}

View file

@ -465,7 +465,7 @@ static void nopConsumer(uint8_t data)
arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
for specialized data processing.
*/
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
*leftC, serialConsumer *rightC)
{
waitForSerialPortToFinishTransmitting(left);

View file

@ -16,7 +16,7 @@
* Author: 4712
* have a look at https://github.com/sim-/tgy/blob/master/boot.inc
* for info about the stk500v2 implementation
*/
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>

View file

@ -112,13 +112,14 @@ static void cliRxFail(char *cmdline);
static void cliAdjustmentRange(char *cmdline);
static void cliMotorMix(char *cmdline);
static void cliDefaults(char *cmdline);
void cliDfu(char *cmdLine);
void cliDfu(char *cmdLine);
static void cliDump(char *cmdLine);
void cliDumpProfile(uint8_t profileIndex);
void cliDumpRateProfile(uint8_t rateProfileIndex) ;
static void cliExit(char *cmdline);
static void cliFeature(char *cmdline);
static void cliMotor(char *cmdline);
static void cliName(char *cmdline);
static void cliPlaySound(char *cmdline);
static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
@ -340,6 +341,7 @@ const clicmd_t cmdTable[] = {
#ifdef VTX
CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
#endif
CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName),
};
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
@ -451,6 +453,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
"MIXER",
"AIRMODE",
"PIDLOOP",
"NOTCH",
};
#ifdef OSD
static const char * const lookupTableOsdType[] = {
@ -486,7 +489,7 @@ typedef enum {
TABLE_GPS_SBAS_MODE,
#endif
#ifdef BLACKBOX
TABLE_BLACKBOX_DEVICE,
TABLE_BLACKBOX_DEVICE,
#endif
TABLE_CURRENT_SENSOR,
TABLE_GIMBAL_MODE,
@ -696,6 +699,8 @@ const clivalue_t valueTable[] = {
{ "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
{ "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
{ "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
{ "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
{ "gyro_notch_q", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_notch_q, .config.minmax = { 1, 100 } },
{ "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
@ -1941,7 +1946,7 @@ static void cliDump(char *cmdline)
dumpMask = DUMP_PROFILE; // only
}
if (strcasecmp(cmdline, "rates") == 0) {
dumpMask = DUMP_RATES;
dumpMask = DUMP_RATES;
}
if (strcasecmp(cmdline, "all") == 0) {
@ -1953,6 +1958,8 @@ static void cliDump(char *cmdline)
cliPrint("\r\n# version\r\n");
cliVersion(NULL);
cliPrint("\r\n# name\r\n");
cliName(NULL);
cliPrint("\r\n# dump master\r\n");
cliPrint("\r\n# mixer\r\n");
@ -2494,6 +2501,18 @@ static void cliMotor(char *cmdline)
cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
}
static void cliName(char *cmdline)
{
uint32_t len = strlen(cmdline);
if (len > 0) {
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
}
cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
return;
}
static void cliPlaySound(char *cmdline)
{
#if FLASH_SIZE <= 64
@ -2681,7 +2700,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
break;
}
}
static void cliPrintVarRange(const clivalue_t *var)
static void cliPrintVarRange(const clivalue_t *var)
{
switch (var->type & VALUE_MODE_MASK) {
case (MODE_DIRECT): {
@ -2693,7 +2712,7 @@ static void cliPrintVarRange(const clivalue_t *var)
cliPrint("Allowed values:");
uint8_t i;
for (i = 0; i < tableEntry->valueCount ; i++) {
if (i > 0)
if (i > 0)
cliPrint(",");
cliPrintf(" %s", tableEntry->values[i]);
}
@ -2907,7 +2926,7 @@ static void cliStatus(char *cmdline)
#ifdef USE_SDCARD
cliSdInfo(NULL);
#endif
#endif
}
#ifndef SKIP_TASK_STATISTICS

View file

@ -659,7 +659,7 @@ static uint32_t packFlightModeFlags(void)
static bool processOutCommand(uint8_t cmdMSP)
{
uint32_t i;
uint8_t len;
#ifdef GPS
uint8_t wp_no;
int32_t lat = 0, lon = 0;
@ -750,6 +750,14 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(constrain(averageSystemLoadPercent, 0, 100));
break;
case MSP_NAME:
len = strlen(masterConfig.name);
headSerialReply(len);
for (uint8_t i=0; i<len; i++) {
serialize8(masterConfig.name[i]);
}
break;
case MSP_STATUS:
headSerialReply(11);
serialize16(cycleTime);
@ -1868,6 +1876,13 @@ static bool processInCommand(void)
masterConfig.baro_hardware = read8();
masterConfig.mag_hardware = read8();
break;
case MSP_SET_NAME:
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
for (i = 0; i < MIN(MAX_NAME_LENGTH, currentPort->dataSize); i++) {
masterConfig.name[i] = read8();
}
break;
default:
// we do not know how to handle the (valid) message, indicate error MSP $M!
return false;

View file

@ -99,6 +99,10 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_BOARD_INFO 4 //out message
#define MSP_BUILD_INFO 5 //out message
#define MSP_NAME 10
#define MSP_SET_NAME 11
//
// MSP commands for Cleanflight original features
//
@ -147,6 +151,23 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters
#define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
#define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip
#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
@ -177,22 +198,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_VTX_CONFIG 88 //in message Get vtx settings
#define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
// Betaflight Additional Commands
#define MSP_PID_ADVANCED_CONFIG 90
#define MSP_SET_PID_ADVANCED_CONFIG 91

View file

@ -14,7 +14,7 @@
* 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 VTX_BAND_MIN 1

View file

@ -313,7 +313,7 @@ void init(void)
bool use_unsyncedPwm = masterConfig.use_unsyncedPwm;
// Configurator feature abused for enabling Fast PWM
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;

View file

@ -226,7 +226,7 @@ static void xBusUnpackRJ01Frame(void)
uint8_t outerCrc = 0;
uint8_t i = 0;
// When using the Align RJ01 receiver with
// When using the Align RJ01 receiver with
// a MODE B setting in the radio (XG14 tested)
// the MODE_B -frame is packed within some
// at the moment unknown bytes before and after:
@ -234,7 +234,7 @@ static void xBusUnpackRJ01Frame(void)
// Compared to a standard MODE B frame that only
// contains the "middle" package.
// Hence, at the moment, the unknown header and footer
// of the RJ01 MODEB packages are discarded.
// of the RJ01 MODEB packages are discarded.
// However, the LAST byte (CRC_OUTER) is infact an 8-bit
// CRC for the whole package, using the Dallas-One-Wire CRC
// method.

View file

@ -190,7 +190,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
if (!accFilterInitialised) {
if (accTargetLooptime) { /* Initialisation needs to happen once sample rate is known */
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&accFilter[axis], accLpfCutHz, accTargetLooptime);
biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, accTargetLooptime);
}
accFilterInitialised = true;
}

View file

@ -70,7 +70,7 @@ static void updateBatteryVoltage(void)
if (debugMode == DEBUG_BATTERY) debug[0] = vbatSample;
if (!vbatFilterIsInitialised) {
biquadFilterInit(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update
biquadFilterInitLPF(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update
vbatFilterIsInitialised = true;
}
vbatSample = biquadFilterApply(&vbatFilter, vbatSample);
@ -91,7 +91,7 @@ void updateBattery(void)
/* Actual battery state is calculated below, this is really BATTERY_PRESENT */
batteryState = BATTERY_OK;
/* wait for VBatt to stabilise then we can calc number of cells
(using the filtered value takes a long time to ramp up)
(using the filtered value takes a long time to ramp up)
We only do this on the ground so don't care if we do block, not
worse than original code anyway*/
delay(VBATTERY_STABLE_DELAY);

View file

@ -27,12 +27,14 @@
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
gyro_t gyro; // gyro access functions
@ -43,21 +45,27 @@ float gyroADCf[XYZ_AXIS_COUNT];
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
static const gyroConfig_t *gyroConfig;
static biquadFilter_t gyroFilter[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterNotch[XYZ_AXIS_COUNT];
static uint16_t gyroSoftNotchHz;
static uint8_t gyroSoftNotchQ;
static uint8_t gyroSoftLpfHz;
static uint16_t calibratingG = 0;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz)
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q)
{
gyroConfig = gyroConfigToUse;
gyroSoftLpfHz = gyro_soft_lpf_hz;
gyroSoftNotchHz = gyro_soft_notch_hz;
gyroSoftNotchQ = gyro_soft_notch_q;
}
void gyroInit(void)
{
if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known
for (int axis = 0; axis < 3; axis++) {
biquadFilterInit(&gyroFilter[axis], gyroSoftLpfHz, gyro.targetLooptime);
biquadFilterInit(&gyroFilterNotch[axis], gyroSoftNotchHz, gyro.targetLooptime, ((float) gyroSoftNotchQ) / 10, FILTER_NOTCH);
biquadFilterInitLPF(&gyroFilterLPF[axis], gyroSoftLpfHz, gyro.targetLooptime);
}
}
}
@ -157,7 +165,17 @@ void gyroUpdate(void)
if (gyroSoftLpfHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADCf[axis] = biquadFilterApply(&gyroFilter[axis], (float)gyroADC[axis]);
float sample = (float) gyroADC[axis];
if (gyroSoftNotchHz) {
sample = biquadFilterApply(&gyroFilterNotch[axis], sample);
}
if (debugMode == DEBUG_NOTCH && axis < 2){
debug[axis*2 + 0] = gyroADC[axis];
debug[axis*2 + 1] = lrintf(sample);
}
gyroADCf[axis] = biquadFilterApply(&gyroFilterLPF[axis], sample);;
gyroADC[axis] = lrintf(gyroADCf[axis]);
}
} else {

View file

@ -40,7 +40,7 @@ typedef struct gyroConfig_s {
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
} gyroConfig_t;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz);
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q);
void gyroSetCalibrationCycles(void);
void gyroInit(void);
void gyroUpdate(void);

View file

@ -89,7 +89,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
#if defined(MPU_INT_EXTI)
static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) };
return &mpuIntExtiConfig;
#elif defined(USE_HARDWARE_REVISION_DETECTION)
#elif defined(USE_HARDWARE_REVISION_DETECTION)
return selectMPUIntExtiConfigByHardwareRevision();
#else
return NULL;
@ -118,9 +118,15 @@ static bool fakeGyroReadTemp(int16_t *tempData)
return true;
}
static bool fakeGyroInitStatus(void) {
return true;
}
bool fakeGyroDetect(gyro_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemp;
gyro->scale = 1.0f / 16.4f;
@ -143,6 +149,7 @@ bool fakeAccDetect(acc_t *acc)
{
acc->init = fakeAccInit;
acc->read = fakeAccRead;
acc->acc_1G = 512*8;
acc->revisionCode = 0;
return true;
}
@ -584,10 +591,14 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
uint8_t accHardwareToUse,
uint8_t magHardwareToUse,
uint8_t baroHardwareToUse,
int16_t magDeclinationFromConfig,
uint8_t gyroLpf,
uint8_t gyroSyncDenominator)
{
int16_t deg, min;
memset(&acc, 0, sizeof(acc));
memset(&gyro, 0, sizeof(gyro));
@ -605,7 +616,6 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
detectAcc(accHardwareToUse);
detectBaro(baroHardwareToUse);
// Now time to init things, acc first
if (sensors(SENSOR_ACC)) {
acc.acc_1G = 256; // set default
@ -623,9 +633,8 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
if (sensors(SENSOR_MAG)) {
// calculate magnetic declination
deg = magDeclinationFromConfig / 100;
min = magDeclinationFromConfig % 100;
const int16_t deg = magDeclinationFromConfig / 100;
const int16_t min = magDeclinationFromConfig % 100;
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
} else {
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.

View file

@ -21,18 +21,16 @@
#define USE_CLI
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB5 // Blue LED - PB5
#define LED0 PB5 // Blue LED - PB5
#define BEEPER PA0
#define BEEPER PA0
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
@ -41,20 +39,18 @@
#define ACC
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW180_DEG
#define GYRO_MPU6050_ALIGN CW180_DEG
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
//#define BARO
//#define USE_BARO_MS5611
@ -66,31 +62,30 @@
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 //(AF7)
#define UART3_RX_PIN PB11 //(AF7)
#define UART3_TX_PIN PB10 //(AF7)
#define UART3_RX_PIN PB11 //(AF7)
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_SPI
#define USE_SPI_DEVICE_2
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
#define SENSORS_SET (SENSOR_ACC)
#undef GPS
#define DISPLAY
@ -99,10 +94,10 @@
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1
@ -135,17 +130,17 @@
#define SPEKTRUM_BIND
// USART2, PB4
#define BIND_PIN PB4
#define BIND_PIN PB4
#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_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))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#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(15) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -15,7 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/exti.h"
typedef enum awf3HardwareRevision_t {

View file

@ -23,17 +23,17 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2
#define HW_PIN PB2
// LED's V1
#define LED0 PB4 // LED - PB4
#define LED1 PB5 // LED - PB5
#define LED0 PB4
#define LED1 PB5
// LED's V2
#define LED0_A PB8 // LED - PB8
#define LED1_A PB9 // LED - PB9
#define LED0_A PB8
#define LED1_A PB9
#define BEEPER PA5 // LED - PA5
#define BEEPER PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -48,15 +48,15 @@
#define USE_GYRO_MPU6050
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6050_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6050_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6050_ALIGN CW270_DEG
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU6050_ALIGN CW270_DEG
#define ACC_MPU6500_ALIGN CW270_DEG
// No baro support.
//#define BARO
@ -65,29 +65,28 @@
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
#define MAG
#define USE_MAG_AK8963
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define USE_VCP
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)
#define USE_UART2 // Receiver - RX (PA3)
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2 // PA2
#define UART2_RX_PIN PA3 // PA3
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define I2C2_SCL PA9
#define I2C2_SDA PA10
// SPI3
// PA15 38 SPI3_NSS
@ -98,22 +97,22 @@
#define USE_SPI
#define USE_SPI_DEVICE_3
#define MPU6500_CS_PIN PA15
#define MPU6500_SPI_INSTANCE SPI3
#define MPU6500_CS_PIN PA15
#define MPU6500_SPI_INSTANCE SPI3
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define VBAT_SCALE_DEFAULT 20
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define VBAT_SCALE_DEFAULT 20
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define BIND_PIN PA3
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB12 (Pin 25)
#define BINDPLUG_PIN PB12
#define BINDPLUG_PIN PB12
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
@ -124,12 +123,11 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View file

@ -23,39 +23,39 @@
#define USBD_PRODUCT_STRING "AlienFlight F4"
#define LED0 PC12
#define LED1 PD2
#define LED0 PC12
#define LED1 PD2
#define BEEPER PC13
#define BEEPER PC13
#define INVERTER PC15
#define INVERTER_USART USART2
#define INVERTER PC15
#define INVERTER_USART USART2
// MPU interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define MPU_INT_EXTI PC14
#define MPU_INT_EXTI PC14
#define USE_EXTI
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU6500_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
#define MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8963
#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_AK8963_ALIGN CW270_DEG
#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_AK8963_ALIGN CW270_DEG
#define BARO
#define USE_BARO_MS5611
@ -65,14 +65,14 @@
//#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB10
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_DETECT_PIN PB10
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
@ -93,57 +93,55 @@
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2 //inverter
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2 //inverter
//#define USE_UART3
//#define UART3_RX_PIN PB11
//#define UART3_TX_PIN PB10
//#define UART3_RX_PIN PB11
//#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PC10
#define UART4_TX_PIN PC11
#define UART4_RX_PIN PC10
#define UART4_TX_PIN PC11
//#define USE_UART5
//#define UART5_RX_PIN PD2
//#define UART5_TX_PIN PC12
//#define UART5_RX_PIN PD2
//#define UART5_TX_PIN PC12
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define USE_SPI_DEVICE_3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
//#define I2C_DEVICE_EXT (I2CDEV_2)
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define I2C_DEVICE (I2CDEV_1)
//#define I2C_DEVICE_EXT (I2CDEV_2)
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ADC
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC4
#define EXTERNAL1_ADC_GPIO_PIN PC5
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC4
#define EXTERNAL1_ADC_GPIO_PIN PC5
// LED strip configuration using RC5 pin.
//#define LED_STRIP
@ -156,11 +154,11 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define BIND_PIN PA3
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB2 (Pin 28)
#define BINDPLUG_PIN PB2
#define BINDPLUG_PIN PB2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
@ -172,10 +170,10 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )

View file

@ -33,7 +33,7 @@ const uint16_t multiPPM[] = {
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),

View file

@ -20,40 +20,40 @@
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "BlueJayF4"
#define USBD_PRODUCT_STRING "BlueJayF4"
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_EXTI
#define INVERTER PB15
#define INVERTER_USART USART6
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define BEEPER PB7
#define BEEPER PB7
#define BEEPER_INVERTED
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define INVERTER PB15
#define INVERTER_USART USART6
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
//#define MAG
//#define USE_MAG_AK8963
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
@ -76,8 +76,8 @@
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
//#define M25P16_CS_PIN PB3
//#define M25P16_SPI_INSTANCE SPI3
//#define M25P16_CS_PIN PB3
//#define M25P16_SPI_INSTANCE SPI3
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
@ -96,22 +96,21 @@
//#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define SERIAL_PORT_COUNT 5
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
@ -134,15 +133,15 @@
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_PULLUP
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define VBAT_ADC_PIN PC3
#define LED_STRIP
// LED Strip can run off Pin 6 (PB1) of the ESC outputs.
#define WS2811_PIN PB1
#define WS2811_PIN PB1
#define WS2811_TIMER TIM3
#define WS2811_TIMER_CHANNEL TIM_Channel_4
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
@ -155,15 +154,15 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9))

View file

@ -17,25 +17,25 @@
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
#define LED0 PB3 // PB3 (LED)
#define LED0 PB3
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define BEEPER PB15 // PB15 (Beeper)
#define BEEPER_OPT PB2 // PB15 (Beeper)
#define BEEPER PB15
#define BEEPER_OPT PB2
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PA3
#define MPU_INT_EXTI PA3
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define M25P16_CS_GPIO GPIOB
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define M25P16_CS_GPIO GPIOB
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_FLASHFS
#define USE_FLASH_M25P16
@ -72,18 +72,18 @@
#define USE_UART1
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#ifdef USE_UART1_RX_DMA
#undef USE_UART1_RX_DMA
#endif
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_SPI
#define USE_SPI_DEVICE_1
@ -93,15 +93,15 @@
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PB0
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PB0
#define LED_STRIP
#define WS2811_PIN PB4
#define WS2811_TIMER TIM3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#define WS2811_PIN PB4
#define WS2811_TIMER TIM3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#define SPEKTRUM_BIND
// USART3, PB11 (Flexport)
@ -111,12 +111,13 @@
#define DISPLAY
#define SONAR
#define SONAR_ECHO_PIN PB0
#define SONAR_TRIGGER_PIN PB5
#define SONAR_ECHO_PIN PB0
#define SONAR_TRIGGER_PIN PB5
#undef GPS
#undef BARO
#undef MAG
#ifdef CC3D_OPBL
#define SKIP_CLI_COMMAND_HELP
@ -128,8 +129,8 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// IO - from schematics
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(14) )
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(14) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View file

@ -22,14 +22,14 @@
#ifndef STM32F3DISCOVERY
#define STM32F3DISCOVERY
#endif
#define LED0 PE8 // Blue LEDs - PE8/PE12
#endif
#define LED0 PE8 // Blue LEDs - PE8/PE12
#define LED0_INVERTED
#define LED1 PE10 // Orange LEDs - PE10/PE14
#define LED1 PE10 // Orange LEDs - PE10/PE14
#define LED1_INVERTED
#define BEEPER PE9 // Red LEDs - PE9/PE13
#define BEEPER PE9 // Red LEDs - PE9/PE13
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 18
@ -81,16 +81,14 @@
#define ACC
#define USE_ACC_MPU6050
#define USE_ACC_LSM303DLHC
#define ACC_MPU6050_ALIGN CW0_DEG
#define ACC_MPU6050_ALIGN CW0_DEG
#define BARO
#define USE_BARO_MS5611
#define MAG
#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define USE_VCP
#define USE_UART1
@ -101,20 +99,19 @@
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define ADC_INSTANCE ADC1
#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
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View file

@ -17,7 +17,7 @@
#pragma once
#include "drivers/exti.h"
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0,
REV_1, // Blue LED3

View file

@ -20,9 +20,9 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define LED0 PC14 // PC14 (LED)
#define LED1 PC13 // PC13 (LED)
#define LED2 PC15 // PC15 (LED)
#define LED0 PC14
#define LED1 PC13
#define LED2 PC15
#define ACC
#define USE_ACC_MPU6050
@ -38,7 +38,7 @@
#define USE_UART1
#define USE_UART2
#define SERIAL_PORT_COUNT 2
#define SERIAL_PORT_COUNT 2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
@ -49,7 +49,7 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define BIND_PIN PA3
#if (FLASH_SIZE > 64)
@ -64,8 +64,8 @@
#endif
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -18,17 +18,17 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "CLBR"
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define BEEPER_INVERTED
#define USE_EXTI
@ -53,17 +53,17 @@
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define GYRO_MPU6000_ALIGN CW270_DEG
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define ACC_MPU6000_ALIGN CW270_DEG
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU6500_ALIGN CW270_DEG
#define BARO
#define USE_BARO_MS5611
@ -80,34 +80,34 @@
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL_PIN PA9
#define I2C2_SDA_PIN PA10
#define I2C2_SCL_PIN PA9
#define I2C2_SDA_PIN PA10
#define USE_BST
#define BST_DEVICE (BSTDEV_1)
/* Configure the CRC peripheral to use the polynomial x8 + x7 + x6 + x4 + x2 + 1 */
#define BST_CRC_POLYNOM 0xD5
#define BST_CRC_POLYNOM 0xD5
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define ADC_INSTANCE ADC1
#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
@ -122,7 +122,7 @@
// MPU6500 interrupt
#define USE_EXTI
#define MPU_INT_EXTI PA5
#define MPU_INT_EXTI PA5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -135,11 +135,11 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -43,7 +43,7 @@ const uint16_t multiPWM[] = {
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};

View file

@ -20,17 +20,15 @@
#define TARGET_BOARD_IDENTIFIER "DOGE"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
// tqfp48 pin 34
#define LED0 PA13
#define LED0 PA13
// tqfp48 pin 37
#define LED1 PA14
#define LED1 PA14
// tqfp48 pin 38
#define LED2 PA15
#define LED2 PA15
#define BEEPER PB2
#define BEEPER PB2
#define BEEPER_INVERTED
#define USE_SPI
@ -81,13 +79,13 @@
// #define USE_FAKE_GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG // ??
#define GYRO_MPU6500_ALIGN CW270_DEG // ??
#define ACC
// #define USE_FAKE_ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG // ??
#define ACC_MPU6500_ALIGN CW270_DEG // ??
#define BARO
#define USE_BARO_BMP280
@ -100,20 +98,20 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
// mpu_int definition in sensors/initialisation.c
#define USE_EXTI
@ -135,19 +133,19 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define SPEKTRUM_BIND
// Use UART3 for speksat
#define BIND_PIN PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// !!TODO - check the TARGET_IO_PORTs are correct
#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 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))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))

View file

@ -19,21 +19,21 @@
#define TARGET_BOARD_IDENTIFIER "EUF1"
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_EXTI
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
#define MPU6500_CS_GPIO GPIOB
#define MPU6500_CS_PIN PB12
#define MPU6500_SPI_INSTANCE SPI2
#define MPU6500_CS_GPIO GPIOB
#define MPU6500_CS_PIN PB12
#define MPU6500_SPI_INSTANCE SPI2
#define GYRO
#define USE_FAKE_GYRO
@ -44,7 +44,7 @@
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define ACC
#define USE_FAKE_ACC
@ -55,7 +55,7 @@
//#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6050_ALIGN CW0_DEG
#define ACC_MPU6050_ALIGN CW0_DEG
#define BARO
#define USE_BARO_MS5611
@ -66,7 +66,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define SONAR
#define SONAR_TRIGGER_PIN PB0
@ -80,12 +80,12 @@
#define USE_UART2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_TIMER TIM3
#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 TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
@ -97,21 +97,20 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define BIND_PIN PA3
// IO - stm32f103RCT6 in 64pin package (TODO)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -30,11 +30,11 @@ const uint16_t multiPWM[] = {
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_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
@ -69,11 +69,11 @@ const uint16_t airPWM[] = {
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),
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
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), // servo #2
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
@ -101,7 +101,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
};

View file

@ -20,46 +20,47 @@
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "Swift-Flyer F4BY"
#define USBD_PRODUCT_STRING "Swift-Flyer F4BY"
#define LED0 PE3 // Blue LED
#define LED1 PE2 // Red LED
#define LED2 PE1 // Blue LED
#define BEEPER PE5
#define LED0 PE3 // Blue LED
#define LED1 PE2 // Red LED
#define LED2 PE1 // Blue LED
#define INVERTER PD3
#define INVERTER_USART USART6
#define BEEPER PE5
#define INVERTER PD3
#define INVERTER_USART USART6
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PB0
#define MPU_INT_EXTI PB0
#define USE_EXTI
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define ACC_MPU6000_ALIGN CW90_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW90_DEG
#define GYRO_MPU6000_ALIGN CW90_DEG
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
#define MAG_HMC5883_ALIGN CW90_DEG
#define BARO
#define USE_BARO_MS5611
#define USE_SDCARD
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PE15
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PE15
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
@ -76,43 +77,41 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_VCP
#define VBUS_SENSING_PIN PA9
#define VBUS_SENSING_PIN PA9
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PD6
#define UART2_TX_PIN PD5
#define UART2_RX_PIN PD6
#define UART2_TX_PIN PD5
#define USE_UART3
#define UART3_RX_PIN PD9
#define UART3_TX_PIN PD8
#define UART3_RX_PIN PD9
#define UART3_TX_PIN PD8
#define USE_UART4
#define UART4_RX_PIN PC11
#define UART4_TX_PIN PC10
#define UART4_RX_PIN PC11
#define UART4_TX_PIN PC10
//#define USE_UART5 - error in DMA!!!
//#define UART5_RX_PIN PD2
//#define UART5_TX_PIN PC12
//#define UART5_RX_PIN PD2
//#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6
#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI1_NSS_PIN NONE
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI1_NSS_PIN NONE
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN NONE
@ -121,24 +120,23 @@
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_PULLUP
#define I2C2_SCL PB10
#define I2C2_SDA PB11
#define I2C2_SCL PB10
#define I2C2_SDA PB11
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC3
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC1
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC1
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
@ -148,15 +146,15 @@
#define SPEKTRUM_BIND
// UART6, PC7
#define BIND_PIN PC7
#define BIND_PIN PC7
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9))
#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9))

View file

@ -76,7 +76,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2
{ TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP
};

View file

@ -21,13 +21,13 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define MPU_INT_EXTI PC4
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define CONFIG_PREFER_ACC_ON
#define LED0 PC14
#define BEEPER PC15
#define LED0 PC14
#define BEEPER PC15
#define BEEPER_INVERTED
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect
@ -36,26 +36,25 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define ACC
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW90_DEG
#define GYRO_MPU6500_ALIGN CW90_DEG
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW90_DEG
#define ACC_MPU6500_ALIGN CW90_DEG
#define BARO
#define USE_BARO_MS5611
@ -113,31 +112,31 @@
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14
#define UART2_RX_PIN PA15 // PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 1
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL_PIN PB8
#define I2C1_SDA_PIN PB9
#define I2C1_SCL_PIN PB8
#define I2C1_SDA_PIN PB9
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PA2
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PA2
#define LED_STRIP
@ -150,23 +149,23 @@
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))

View file

@ -20,44 +20,45 @@
#define TARGET_BOARD_IDENTIFIER "FYF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "FuryF4"
#define USBD_PRODUCT_STRING "FuryF4"
#define LED0 PB5
#define LED1 PB4
#define BEEPER PA8
#define LED0 PB5
#define LED1 PB4
#define BEEPER PA8
#define BEEPER_INVERTED
#define INVERTER PC0 // PC0 used as inverter select GPIO
#define INVERTER_USART USART1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define ACC_MPU6500_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PC4
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
@ -97,29 +98,29 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
#define USE_SPI
@ -138,16 +139,16 @@
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA
#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA
#define USE_I2C_PULLUP
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC1
#define RSSI_ADC_GPIO_PIN PC2
#define CURRENT_METER_ADC_PIN PC3
#define VBAT_ADC_PIN PC1
#define RSSI_ADC_GPIO_PIN PC2
#define CURRENT_METER_ADC_PIN PC3
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
@ -157,14 +158,14 @@
#define SPEKTRUM_BIND
// USART3 Rx, PB11
#define BIND_PIN PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))

View file

@ -21,7 +21,7 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3
#define LED0 PB3
#define USABLE_TIMER_CHANNEL_COUNT 17
@ -32,11 +32,11 @@
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define ACC_MPU6050_ALIGN CW270_DEG
#define BARO
#define USE_BARO_BMP085
@ -49,17 +49,17 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 3
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
@ -67,16 +67,16 @@
#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 USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
/*
@ -100,11 +100,10 @@
*/
// 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(4))
#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(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))
#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

@ -23,51 +23,50 @@
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
#define LED0 PB1
#define BEEPER PB13
#define LED0 PB1
#define BEEPER PB13
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USE_EXTI
#define MPU_INT_EXTI PB2
#define MPU_INT_EXTI PB2
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW180_DEG
#define GYRO_MPU6050_ALIGN CW180_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_ADC
#define VBAT_SCALE_DEFAULT 160
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
//#define CURRENT_METER_ADC_PIN PA5
//#define RSSI_ADC_PIN PB2
#define VBAT_SCALE_DEFAULT 160
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
//#define CURRENT_METER_ADC_PIN PA5
//#define RSSI_ADC_PIN PB2
#define DEFAULT_FEATURES FEATURE_VBAT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
@ -75,12 +74,12 @@
#define SERIALRX_UART SERIAL_PORT_USART2
#define SPEKTRUM_BIND
#define BIND_PIN PB4
#define BIND_PIN PB4
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View file

@ -21,12 +21,12 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define BEEPER_INVERTED
#define USE_SPI
@ -47,12 +47,12 @@
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU6500_ALIGN CW270_DEG
#define USB_IO
@ -60,26 +60,26 @@
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define ADC_INSTANCE ADC1
#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 WS2811_PIN PA6 // TIM16_CH1
@ -97,20 +97,20 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define SPEKTRUM_BIND
// USART1, PC5
#define BIND_PIN PC5
#define BIND_PIN PC5
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -21,18 +21,18 @@
#define USE_CLI
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9
#define BEEPER PA0
#define LED0 PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9
#define BEEPER PA0
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
@ -41,20 +41,20 @@
#define ACC
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW180_DEG
#define GYRO_MPU6050_ALIGN CW180_DEG
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
//#define BARO
//#define USE_BARO_MS5611
@ -66,42 +66,42 @@
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3 // PB3
#define UART2_RX_PIN PB4 // PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_SPI
#define USE_SPI_DEVICE_2
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
#undef GPS
#define DISPLAY
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1
@ -135,17 +135,17 @@
#define SPEKTRUM_BIND
// USART2, PB4
#define BIND_PIN PB4
#define BIND_PIN PB4
#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_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))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#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(15) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -22,19 +22,19 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define BEEPER PA12 // PA12 (Beeper)
#define BEEPER PA12
#ifdef AFROMINI
#define BEEPER_INVERTED
#endif
#define BARO_XCLR_PIN PC13
#define BARO_EOC_PIN PC14
#define BARO_XCLR_PIN PC13
#define BARO_EOC_PIN PC14
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_EXTI
@ -47,24 +47,22 @@
#define USE_SPI
#define USE_SPI_DEVICE_2
#define NAZE_SPI_INSTANCE SPI2
#define NAZE_SPI_CS_GPIO GPIOB
#define NAZE_SPI_CS_PIN PB12
#define NAZE_SPI_INSTANCE SPI2
#define NAZE_SPI_CS_GPIO GPIOB
#define NAZE_SPI_CS_PIN PB12
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
@ -75,17 +73,16 @@
//#define DEBUG_MAG_DATA_READY_INTERRUPT
#define USE_MAG_DATA_READY_SIGNAL
#define MAG_INT_EXTI PC14
#define GYRO
#define USE_GYRO_MPU3050
#define USE_GYRO_MPU6050
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU3050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
#define GYRO_MPU3050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC_ADXL345
@ -95,11 +92,11 @@
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_ADXL345_ALIGN CW270_DEG
#define ACC_MPU6050_ALIGN CW0_DEG
#define ACC_MMA8452_ALIGN CW90_DEG
#define ACC_BMA280_ALIGN CW0_DEG
#define ACC_MPU6500_ALIGN CW0_DEG
#define ACC_ADXL345_ALIGN CW270_DEG
#define ACC_MPU6050_ALIGN CW0_DEG
#define ACC_MMA8452_ALIGN CW90_DEG
#define ACC_BMA280_ALIGN CW0_DEG
#define ACC_MPU6500_ALIGN CW0_DEG
#define BARO
#define USE_BARO_MS5611
@ -108,8 +105,7 @@
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_HMC5883_ALIGN CW180_DEG
#define SONAR
#define SONAR_TRIGGER_PIN PB0
@ -124,7 +120,7 @@
#define USE_UART3
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define SERIAL_PORT_COUNT 5
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
@ -134,8 +130,8 @@
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
// USART3 only on NAZE32_SP - Flex Port
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
@ -145,23 +141,23 @@
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#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 WS2811_TIMER TIM3
#define WS2811_PIN PA6
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#define WS2811_TIMER TIM3
#define WS2811_PIN PA6
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#undef GPS
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define BIND_PIN PA3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
@ -186,8 +182,8 @@
#endif // ALIENFLIGHTF1
// IO - assuming all IOs on 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_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View file

@ -23,12 +23,12 @@
//#define OLIMEXINO_UNCUT_LED2_E_JUMPER
#ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER
#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#endif
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit()
#define LED1 PA1 // D3, PA1/UART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#define LED1 PA1 // D3, PA1/UART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#endif
#define GYRO
@ -59,14 +59,14 @@
#define USE_MAG_HMC5883
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define USE_UART1
#define USE_UART2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
@ -79,17 +79,16 @@
#define I2C_DEVICE (I2CDEV_2)
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
// IO - assuming all IOs on smt32f103rb LQFP64 package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -21,9 +21,9 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3
#define LED0 PB3
#define BEEPER PC15
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
@ -35,19 +35,19 @@
#define MPU_INT_EXTI PC13
#define USE_EXTI
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW90_DEG
#define GYRO_MPU6000_ALIGN CW90_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define ACC_MPU6000_ALIGN CW90_DEG
#define BMP280_SPI_INSTANCE SPI1
#define BMP280_CS_PIN PA13
#define BMP280_SPI_INSTANCE SPI1
#define BMP280_CS_PIN PA13
#define BARO
#define USE_BARO_BMP280
@ -60,13 +60,12 @@
//#define MAG_AK8975_ALIGN CW90_DEG_FLIP
//#define SONAR
//#define SONAR_ECHO_PIN PB1
//#define SONAR_TRIGGER_PIN PB0
//#define SONAR_ECHO_PIN PB1
//#define SONAR_TRIGGER_PIN PB0
#define USB_IO
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN PB5
#define USB_DETECT_PIN PB5
#define USE_VCP
#define USE_UART1
@ -74,14 +73,14 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
//#define USE_I2C
//#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
@ -100,8 +99,8 @@
#define OSD
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN PB1
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN PB1
//#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3
//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER
@ -169,27 +168,28 @@
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define BUTTONS
#define BUTTON_A_PORT GPIOB
#define BUTTON_A_PIN Pin_1
#define BUTTON_B_PORT GPIOB
#define BUTTON_B_PIN Pin_0
#define BUTTON_A_PORT GPIOB
#define BUTTON_A_PIN Pin_1
#define BUTTON_B_PORT GPIOB
#define BUTTON_B_PIN Pin_0
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define BIND_PIN PB11
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PIN PB0
#define BINDPLUG_PIN PB0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#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(4))
#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(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))

View file

@ -93,7 +93,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT
@ -101,5 +101,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -22,63 +22,63 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB9
#define LED1 PB5
#define LED0 PB9
#define LED1 PB5
#define BEEPER PA0
#define BEEPER PA0
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define ACC
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3 // PB3
#define UART2_RX_PIN PB4 // PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_SPI
#define USE_SPI_DEVICE_2
#define SENSORS_SET (SENSOR_ACC)
#define SENSORS_SET (SENSOR_ACC)
#define TELEMETRY
#define BLACKBOX
#define SERIAL_RX
#define USE_SERVOS
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define CURRENT_METER_ADC_PIN PA2
#define VBAT_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define USE_ADC
#define ADC_INSTANCE ADC2
#define CURRENT_METER_ADC_PIN PA2
#define VBAT_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1
@ -124,16 +124,17 @@
#define SPEKTRUM_BIND
// USART3, PB11
#define BIND_PIN PB11
#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))
#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))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#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(15) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -19,36 +19,36 @@
#define TARGET_BOARD_IDENTIFIER "103R"
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED2 PD2 // PD2 (LED) - Labelled LED4
#define LED0 PB3
#define LED1 PB4
#define LED2 PD2 // PD2 (LED) - Labelled LED4
#define BEEPER PA12 // PA12 (Beeper)
#define BEEPER PA12 // PA12 (Beeper)
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN PC13
#define BARO_EOC_GPIO GPIOC
#define BARO_EOC_PIN PC14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN PC13
#define BARO_EOC_GPIO GPIOC
#define BARO_EOC_PIN PC14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_SPI
#define USE_SPI_DEVICE_2
#define PORT103R_SPI_INSTANCE SPI2
#define PORT103R_SPI_CS_PIN PB12
#define PORT103R_SPI_INSTANCE SPI2
#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_PIN PORT103R_SPI_CS_PIN
#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define M25P16_CS_PIN PORT103R_SPI_CS_PIN
#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define GYRO
#define USE_FAKE_GYRO
@ -93,37 +93,35 @@
#define USE_UART2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_TIMER TIM3
#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 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_2)
#define I2C_DEVICE (I2CDEV_2)
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f103RCT6 in 64pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

Some files were not shown because too many files have changed in this diff Show more