Merge pull request #754 from martinbudden/bf_tidy_targets_adc
Whitespace and variable initialisation tidy
This commit is contained in:
commit
087aecff79
|
@ -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"
|
||||
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define RESOURCE_INDEX(x) x + 1
|
||||
#define RESOURCE_INDEX(x) (x + 1)
|
||||
|
||||
typedef enum {
|
||||
OWNER_FREE = 0,
|
||||
|
|
|
@ -28,11 +28,12 @@
|
|||
|
||||
#include "drivers/sensor.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
|
||||
|
|
|
@ -584,10 +584,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 +609,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 +626,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,22 @@
|
|||
//#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 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 +134,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 +155,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,8 +111,8 @@
|
|||
|
||||
#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
|
||||
|
||||
|
@ -128,8 +128,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) )
|
||||
|
|
|
@ -101,11 +101,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
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -97,10 +97,10 @@
|
|||
// #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
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -96,12 +96,12 @@
|
|||
#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
|
||||
|
|
|
@ -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) )
|
||||
|
|
|
@ -79,10 +79,10 @@
|
|||
#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
|
||||
|
|
|
@ -110,10 +110,10 @@
|
|||
// #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
|
||||
|
||||
|
|
|
@ -26,27 +26,27 @@
|
|||
#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
|
||||
|
@ -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) )
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
Loading…
Reference in New Issue