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:
commit
338d548e11
134 changed files with 1669 additions and 1624 deletions
4
Makefile
4
Makefile
|
@ -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
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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)
|
|||
¤tProfile->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);
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
@ -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;
|
||||
|
|
|
@ -50,5 +50,6 @@ typedef enum {
|
|||
DEBUG_MIXER,
|
||||
DEBUG_AIRMODE,
|
||||
DEBUG_PIDLOOP,
|
||||
DEBUG_NOTCH,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -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"
|
||||
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -21,7 +21,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
#include "system.h"
|
||||
#include "common/utils.h"
|
||||
#include "gpio.h"
|
||||
|
||||
#include "sensor.h"
|
||||
|
@ -32,6 +31,8 @@
|
|||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#ifndef ADC_INSTANCE
|
||||
#define ADC_INSTANCE ADC1
|
||||
#endif
|
||||
|
@ -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));
|
||||
|
@ -135,7 +135,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
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;
|
||||
}
|
||||
|
|
|
@ -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"
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
/*
|
||||
|
|
|
@ -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?
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
||||
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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,18 +114,18 @@ 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;
|
||||
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define RESOURCE_INDEX(x) x + 1
|
||||
#define RESOURCE_INDEX(x) (x + 1)
|
||||
|
||||
typedef enum {
|
||||
OWNER_FREE = 0,
|
||||
|
|
|
@ -376,6 +376,7 @@ void USART1_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
|
@ -119,6 +119,7 @@ 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[] = {
|
||||
|
@ -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 } },
|
||||
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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 {
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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.
|
||||
|
|
|
@ -22,17 +22,15 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define LED0 PB5 // Blue LED - PB5
|
||||
|
||||
|
||||
#define BEEPER PA0
|
||||
#define LED0 PB5 // Blue LED - PB5
|
||||
|
||||
#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))
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
||||
|
|
|
@ -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,11 +133,11 @@
|
|||
#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.
|
||||
|
@ -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))
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
|
|
@ -24,12 +24,12 @@
|
|||
#define STM32F3DISCOVERY
|
||||
#endif
|
||||
|
||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
||||
#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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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 LED0 PC15
|
||||
#define LED1 PC14
|
||||
#define LED2 PC13
|
||||
|
||||
#define BEEPER PB13
|
||||
#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))
|
||||
|
||||
|
|
|
@ -22,15 +22,13 @@
|
|||
#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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -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 LED0 PC14
|
||||
|
||||
#define BEEPER PC15
|
||||
#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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -22,11 +22,11 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define LED0 PC15
|
||||
#define LED1 PC14
|
||||
#define LED2 PC13
|
||||
#define LED0 PC15
|
||||
#define LED1 PC14
|
||||
#define LED2 PC13
|
||||
|
||||
#define BEEPER PB13
|
||||
#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))
|
||||
|
||||
|
|
|
@ -22,17 +22,17 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define LED0 PB5 // Blue LEDs - PB5
|
||||
//#define LED1 PB9 // Green LEDs - PB9
|
||||
#define LED0 PB5 // Blue LEDs - PB5
|
||||
//#define LED1 PB9 // Green LEDs - PB9
|
||||
|
||||
#define BEEPER PA0
|
||||
#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))
|
||||
|
||||
|
|
|
@ -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
|
||||
|
@ -82,10 +80,9 @@
|
|||
#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) )
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
||||
|
|
|
@ -21,40 +21,40 @@
|
|||
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||
|
||||
#define USBD_PRODUCT_STRING "Revolution"
|
||||
#define USBD_PRODUCT_STRING "Revolution"
|
||||
#ifdef OPBL
|
||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||
#endif
|
||||
|
||||
#define LED0 PB5
|
||||
#define LED1 PB4
|
||||
#define BEEPER PB4
|
||||
#define INVERTER PC0 // PC0 used as inverter select GPIO
|
||||
#define INVERTER_USART USART1
|
||||
#define LED0 PB5
|
||||
#define LED1 PB4
|
||||
#define BEEPER PB4
|
||||
#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 ACC
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define USE_EXTI
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define MAG_HMC5883_ALIGN CW90_DEG
|
||||
#define MAG_HMC5883_ALIGN CW90_DEG
|
||||
|
||||
//#define USE_MAG_NAZA
|
||||
//#define MAG_NAZA_ALIGN CW180_DEG_FLIP
|
||||
//#define MAG_NAZA_ALIGN CW180_DEG_FLIP
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_MS5611
|
||||
|
@ -63,8 +63,8 @@
|
|||
//#define USE_PITOT_MS4525
|
||||
//#define MS4525_BUS I2C_DEVICE_EXT
|
||||
|
||||
#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
|
||||
|
@ -72,22 +72,22 @@
|
|||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#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
|
||||
|
||||
|
@ -103,22 +103,22 @@
|
|||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define RSSI_ADC_GPIO_PIN PA0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define RSSI_ADC_GPIO_PIN PA0
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125)
|
||||
|
||||
#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_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
|
||||
|
|
|
@ -25,24 +25,26 @@
|
|||
#define USBD_SERIALNUMBER_STRING "0x8010000"
|
||||
#endif
|
||||
|
||||
#define LED0 PC14
|
||||
#define LED1 PC13
|
||||
#define BEEPER PC13
|
||||
#define INVERTER PC15
|
||||
#define INVERTER_USART USART2 //Sbus on USART 2 of nano.
|
||||
#define LED0 PC14
|
||||
#define LED1 PC13
|
||||
|
||||
#define MPU9250_CS_PIN PB12
|
||||
#define MPU9250_SPI_INSTANCE SPI2
|
||||
#define BEEPER PC13
|
||||
|
||||
#define INVERTER PC15
|
||||
#define INVERTER_USART USART2 //Sbus on USART 2 of nano.
|
||||
|
||||
#define MPU9250_CS_PIN PB12
|
||||
#define MPU9250_SPI_INSTANCE SPI2
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU9250
|
||||
#define USE_ACC_SPI_MPU9250
|
||||
#define ACC_MPU9250_ALIGN CW270_DEG
|
||||
#define ACC_MPU9250_ALIGN CW270_DEG
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU9250
|
||||
#define USE_GYRO_SPI_MPU9250
|
||||
#define GYRO_MPU9250_ALIGN CW270_DEG
|
||||
#define GYRO_MPU9250_ALIGN CW270_DEG
|
||||
|
||||
//#define MAG
|
||||
//#define USE_MAG_HMC5883
|
||||
|
@ -54,23 +56,23 @@
|
|||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
//#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled)
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define USE_EXTI
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
|
||||
#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_RX_PIN PB7
|
||||
#define UART1_TX_PIN PB6
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2
|
||||
#define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2
|
||||
|
||||
#define USE_SPI
|
||||
//#define USE_SPI_DEVICE_1
|
||||
|
@ -81,9 +83,9 @@
|
|||
#define I2C_DEVICE (I2CDEV_3)
|
||||
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PA7
|
||||
#define VBAT_ADC_PIN PA6
|
||||
#define RSSI_ADC_PIN PA5
|
||||
#define CURRENT_METER_ADC_PIN PA7
|
||||
#define VBAT_ADC_PIN PA6
|
||||
#define RSSI_ADC_PIN PA5
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
|
@ -92,10 +94,9 @@
|
|||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) )
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) )
|
||||
|
||||
|
|
|
@ -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 17
|
||||
|
@ -39,11 +39,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_BMP280
|
||||
|
@ -52,34 +52,34 @@
|
|||
#define USE_FLASH_M25P16
|
||||
|
||||
#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_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#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 / SWCLK
|
||||
#define UART2_RX_PIN PA15 // PA15
|
||||
#define UART2_TX_PIN PA14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA15 // 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 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_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
|
||||
|
@ -88,12 +88,12 @@
|
|||
#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 LED_STRIP
|
||||
|
||||
|
@ -109,15 +109,15 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#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)|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))
|
||||
|
|
|
@ -21,23 +21,23 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define LED0 PB3
|
||||
#define LED0 PB3
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER PC15
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP
|
||||
#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6050
|
||||
#define ACC_MPU6050_ALIGN CW0_DEG_FLIP
|
||||
#define ACC_MPU6050_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
@ -49,22 +49,22 @@
|
|||
#define USE_SOFTSERIAL1 // Telemetry
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define UART2_TX_PIN PA14 //Not connected
|
||||
#define UART2_RX_PIN PA15
|
||||
#define UART2_TX_PIN PA14 //Not connected
|
||||
#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 SOFTSERIAL_1_TIMER TIM15
|
||||
#define SOFTSERIAL_1_TIMER TIM15
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 8
|
||||
|
||||
#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_1 // PA4, 5, 6, 7
|
||||
|
@ -81,9 +81,9 @@
|
|||
|
||||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PB2
|
||||
#define VBAT_SCALE_DEFAULT 77
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PB2
|
||||
#define VBAT_SCALE_DEFAULT 77
|
||||
|
||||
#define LED_STRIP
|
||||
|
||||
|
@ -103,17 +103,17 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA15
|
||||
#define BIND_PIN PA15
|
||||
#define BIND_PIN PA15
|
||||
|
||||
#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(16) |TIM_N(17))
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17))
|
||||
|
||||
|
|
|
@ -19,14 +19,14 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SIRF"
|
||||
|
||||
#define LED0 PB2
|
||||
#define BEEPER PA1
|
||||
#define LED0 PB2
|
||||
#define BEEPER PA1
|
||||
|
||||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PA8
|
||||
#define MPU_INT_EXTI PA8
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define GYRO
|
||||
|
@ -40,18 +40,18 @@
|
|||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
// MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
// MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW90_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||
#define ACC_MPU6500_ALIGN CW90_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USB_IO
|
||||
|
||||
|
@ -59,16 +59,16 @@
|
|||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#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 PA2 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA3 // PA15
|
||||
#define UART2_TX_PIN PA2 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA3 // 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)
|
||||
|
||||
#undef USE_I2C
|
||||
|
||||
|
@ -93,17 +93,17 @@
|
|||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN PA15
|
||||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN PA15
|
||||
|
||||
#define MAX7456_DMA_CHANNEL_TX DMA2_Channel2
|
||||
#define MAX7456_DMA_CHANNEL_RX DMA2_Channel1
|
||||
#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_CH1_HANDLER
|
||||
|
||||
#define USE_RTC6705
|
||||
#define RTC6705_SPIDATA_PIN PC15
|
||||
#define RTC6705_SPILE_PIN PC14
|
||||
#define RTC6705_SPICLK_PIN PC13
|
||||
#define RTC6705_SPIDATA_PIN PC15
|
||||
#define RTC6705_SPILE_PIN PC14
|
||||
#define RTC6705_SPICLK_PIN PC13
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI2
|
||||
|
@ -124,32 +124,33 @@
|
|||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PA0
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PA0
|
||||
|
||||
//#define USE_QUAD_MIXER_ONLY
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define OSD
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define USE_SERVOS
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||
#define USED_TIMERS (TIM_N(3) | TIM_N(4))
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB)
|
||||
#define USED_TIMERS (TIM_N(3) | TIM_N(4))
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB)
|
||||
|
||||
|
|
|
@ -21,30 +21,28 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4
|
||||
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4
|
||||
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||
|
||||
#define BEEPER PA1
|
||||
#define BEEPER PA1
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
// 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
|
||||
|
||||
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
|
||||
#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_MS5611
|
||||
|
@ -53,22 +51,22 @@
|
|||
#define MAG
|
||||
#define USE_MAG_AK8975
|
||||
|
||||
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
||||
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1 // Conn 1 - TX (PB6) RX PB7 (AF7)
|
||||
#define USE_UART2 // Input - RX (PA3)
|
||||
#define USE_UART3 // Servo out - 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 - Clashes with PWM6 input.
|
||||
#define UART2_RX_PIN PA3 // PA3
|
||||
#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input.
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#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)
|
||||
|
||||
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP?
|
||||
|
||||
|
@ -76,11 +74,11 @@
|
|||
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA7
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA7
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
|
@ -115,21 +113,19 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PIN PA3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
//#define SONAR
|
||||
//#define SONAR_ECHO_PIN PB1
|
||||
//#define SONAR_TRIGGER_PIN PA2
|
||||
//#define SONAR_ECHO_PIN PB1
|
||||
//#define SONAR_TRIGGER_PIN PA2
|
||||
|
||||
// available IO pins (from schematics)
|
||||
//#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
//#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9))
|
||||
// !!TODO - check following lines are correct
|
||||
#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
|
||||
#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 TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
|
||||
#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))
|
||||
|
||||
|
|
|
@ -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 17
|
||||
|
@ -37,11 +37,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_MS5611
|
||||
|
@ -51,37 +51,37 @@
|
|||
#define MAG
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define MAG_HMC5883_ALIGN CW270_DEG
|
||||
#define MAG_HMC5883_ALIGN CW270_DEG
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
#define MAG_INT_EXTI PC14
|
||||
#define MAG_INT_EXTI PC14
|
||||
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#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_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#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 / 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 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
|
||||
|
@ -97,12 +97,12 @@
|
|||
#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 LED_STRIP
|
||||
|
||||
|
@ -121,16 +121,15 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#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)|BIT(3)|BIT(4))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
|
||||
|
|
|
@ -21,9 +21,9 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define LED0 PB8
|
||||
#define LED0 PB8
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
|
||||
|
@ -31,7 +31,7 @@
|
|||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
@ -47,8 +47,8 @@
|
|||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
@ -68,19 +68,19 @@
|
|||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#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
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
|
||||
|
@ -117,13 +117,12 @@
|
|||
#define MPU6500_CS_PIN PB9
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#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 LED_STRIP
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
|
@ -149,21 +148,20 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#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)|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(8) | TIM_N(15))
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))
|
||||
|
||||
|
|
|
@ -24,9 +24,9 @@
|
|||
// early prototype had slightly different pin mappings.
|
||||
//#define SPRACINGF3MINI_MKII_REVA
|
||||
|
||||
#define LED0 PB3
|
||||
#define LED0 PB3
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
|
||||
|
@ -34,24 +34,22 @@
|
|||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
|
||||
|
||||
#define GYRO
|
||||
//#define USE_FAKE_GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define ACC
|
||||
//#define USE_FAKE_ACC
|
||||
#define USE_ACC_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
@ -60,40 +58,39 @@
|
|||
#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883 // External
|
||||
|
||||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||
#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
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#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 / 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 SOFTSERIAL_1_TIMER TIM2
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
|
||||
|
||||
#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
|
||||
|
@ -124,10 +121,8 @@
|
|||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
|
@ -141,7 +136,6 @@
|
|||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
|
||||
#define TRANSPONDER
|
||||
#define TRANSPONDER_GPIO GPIOA
|
||||
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
@ -158,27 +152,29 @@
|
|||
#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_BLACKBOX
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||
|
||||
#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) | 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))
|
||||
|
|
|
@ -31,12 +31,12 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
||||
#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 USE_SPI
|
||||
|
@ -50,9 +50,9 @@
|
|||
|
||||
//#define USE_SD_CARD
|
||||
//
|
||||
//#define SD_DETECT_PIN PC14
|
||||
//#define SD_CS_PIN PB12
|
||||
//#define SD_SPI_INSTANCE SPI2
|
||||
//#define SD_DETECT_PIN PC14
|
||||
//#define SD_CS_PIN PB12
|
||||
//#define SD_SPI_INSTANCE SPI2
|
||||
|
||||
//#define USE_FLASHFS
|
||||
//#define USE_FLASH_M25P16
|
||||
|
@ -74,9 +74,9 @@
|
|||
|
||||
#define GYRO
|
||||
#define USE_GYRO_L3GD20
|
||||
#define L3GD20_SPI SPI1
|
||||
#define L3GD20_CS_PIN PE3
|
||||
#define GYRO_L3GD20_ALIGN CW270_DEG
|
||||
#define L3GD20_SPI SPI1
|
||||
#define L3GD20_CS_PIN PE3
|
||||
#define GYRO_L3GD20_ALIGN CW270_DEG
|
||||
|
||||
// Support the GY-91 MPU9250 dev board
|
||||
#define USE_GYRO_MPU6500
|
||||
|
@ -92,21 +92,21 @@
|
|||
#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
|
||||
|
||||
//#define BARO
|
||||
//#define BMP280_CS_PIN PB12
|
||||
//#define BMP280_SPI_INSTANCE SPI2
|
||||
//#define BMP280_CS_PIN PB12
|
||||
//#define BMP280_SPI_INSTANCE SPI2
|
||||
//#define USE_BARO_BMP280
|
||||
//#define USE_BARO_SPI_BMP280
|
||||
|
||||
#define OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI2
|
||||
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define MAX7456_SPI_INSTANCE SPI2
|
||||
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
//#define USE_SDCARD
|
||||
//#define USE_SDCARD_SPI2
|
||||
//
|
||||
//#define SDCARD_SPI_INSTANCE SPI2
|
||||
//#define SDCARD_SPI_CS_PIN PB12
|
||||
//#define SDCARD_SPI_INSTANCE SPI2
|
||||
//#define SDCARD_SPI_CS_PIN PB12
|
||||
//// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
//#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
//// Divide to under 25MHz for normal operation:
|
||||
|
@ -125,7 +125,7 @@
|
|||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
// uart2 gpio for shared serial rx/ppm
|
||||
//#define UART2_TX_PIN GPIO_Pin_5 // PD5
|
||||
|
@ -139,11 +139,11 @@
|
|||
#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
|
||||
|
||||
#define LED_STRIP
|
||||
#define WS2811_PIN PB8 // TIM16_CH1
|
||||
|
@ -153,19 +153,18 @@
|
|||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// IO - 303 in 100pin package
|
||||
#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_PORTF 0x00ff
|
||||
#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_PORTF 0x00ff
|
||||
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | 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(16) | TIM_N(17))
|
||||
|
||||
|
|
|
@ -22,33 +22,31 @@
|
|||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
|
||||
#define LED0 PC14
|
||||
#define BEEPER PC15
|
||||
#define LED0 PC14
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
||||
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
|
||||
#define MPU6000_CS_PIN PA15
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
#define MPU6000_CS_PIN PA15
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define USE_EXTI
|
||||
|
||||
|
||||
|
@ -60,27 +58,27 @@
|
|||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#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 PA2 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA3 // PA15
|
||||
#define UART2_TX_PIN PA2 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#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 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_1) // PB6/SCL, PB7/SDA
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
@ -100,12 +98,12 @@
|
|||
#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 LED_STRIP
|
||||
|
||||
|
@ -119,21 +117,20 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_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 SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#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)|BIT(3)|BIT(4))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
|
||||
|
|
|
@ -21,32 +21,30 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define LED0 PB8
|
||||
#define LED0 PB8
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
@ -54,17 +52,17 @@
|
|||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
|
||||
#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
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
|
||||
|
@ -84,25 +82,25 @@
|
|||
#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 DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue