diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 2b9fb09e2..50061fb79 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -31,7 +31,7 @@ #include "pwm_rx.h" #include "pwm_mapping.h" -void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); +void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); @@ -327,7 +327,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { - pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); + pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM; } else { pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index a56e0eaa2..2212153cd 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -30,17 +30,14 @@ #error Invalid motor/servo/port configuration #endif - #define PULSE_1MS (1000) // 1ms pulse width - #define MAX_INPUTS 8 - #define PWM_TIMER_MHZ 1 #define PWM_BRUSHED_TIMER_MHZ 24 -#define MULTISHOT_TIMER_MHZ 72 -#define ONESHOT42_TIMER_MHZ 24 -#define ONESHOT125_TIMER_MHZ 8 +#define MULTISHOT_TIMER_MHZ 72 +#define ONESHOT42_TIMER_MHZ 24 +#define ONESHOT125_TIMER_MHZ 8 typedef struct sonarIOConfig_s { ioTag_t triggerTag; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 3aba0c097..b44594938 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -170,12 +170,11 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) uint8_t index; TIM_TypeDef *lastTimerPtr = NULL; - for(index = 0; index < motorCount; index++){ + for (index = 0; index < motorCount; index++) { // Force the timer to overflow if it's the first motor to output, or if we change timers - if(motors[index]->tim != lastTimerPtr){ + if (motors[index]->tim != lastTimerPtr) { lastTimerPtr = motors[index]->tim; - timerForceOverflow(motors[index]->tim); } @@ -185,10 +184,10 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) } } -void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse) +void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate) { uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; - motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse); + motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0); motors[motorIndex]->pwmWritePtr = pwmWriteBrushed; } diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index ca8028752..4bce8a70f 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -68,8 +68,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t tmp = (uint32_t) TIMx; tmp += CCMR_OFFSET; - if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) - { + if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) { tmp += (TIM_Channel>>1); /* Reset the OCxM bits in the CCMRx register */ @@ -77,9 +76,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t /* Configure the OCxM bits in the CCMRx register */ *(__IO uint32_t *) tmp |= TIM_OCMode; - } - else - { + } else { tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1; /* Reset the OCxM bits in the CCMRx register */ diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index eaabecb37..d7279327f 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -1904,7 +1904,7 @@ static void dumpValues(uint16_t valueSection) cliPrint("\r\n"); #ifdef STM32F4 - delayMicroseconds(1000); + delay(2); #endif } } @@ -2717,6 +2717,10 @@ static void cliSet(char *cmdline) cliPrintf("%s = ", valueTable[i].name); cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui cliPrint("\r\n"); + +#ifdef STM32F4 + delay(2); +#endif } } else if ((eqptr = strstr(cmdline, "=")) != NULL) { // has equals @@ -2891,14 +2895,14 @@ static void cliTasks(char *cmdline) subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f)); if (masterConfig.pid_process_denom > 1) { taskFrequency = subTaskFrequency / masterConfig.pid_process_denom; - cliPrintf("%d - (%s) ", taskId, taskInfo.taskName); + cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName); } else { taskFrequency = subTaskFrequency; - cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName); + cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName); } } else { taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f)); - cliPrintf("%d - (%s) ", taskId, taskInfo.taskName); + cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName); } cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency); @@ -2909,7 +2913,7 @@ static void cliTasks(char *cmdline) cliPrintf("%dms", taskTotalTime); } - if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency); + if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency); cliPrintf("\r\n", taskTotalTime); } } diff --git a/src/main/main.c b/src/main/main.c index 16c581c59..dba36d3f4 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -314,7 +314,7 @@ void init(void) } bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; - + // Configurator feature abused for enabling Fast PWM pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; @@ -324,6 +324,7 @@ void init(void) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) { + featureClear(FEATURE_3D); pwm_params.idlePulse = 0; // brushed motors use_unsyncedPwm = false; } @@ -336,9 +337,12 @@ void init(void) mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); +/* + // TODO is this needed here? enables at the end if (!feature(FEATURE_ONESHOT125)) motorControlEnable = true; +*/ systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef BEEPER diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 496f2e365..3bc3e20d2 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -19,11 +19,6 @@ #define TARGET_BOARD_IDENTIFIER "AFF4" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 -#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_MSP_PORT 1 -#define CONFIG_RX_SERIAL_PORT 2 #define USBD_PRODUCT_STRING "AlienFlight F4" @@ -48,12 +43,10 @@ #define ACC #define USE_ACC_SPI_MPU6500 - #define ACC_MPU6500_ALIGN CW270_DEG #define GYRO #define USE_GYRO_SPI_MPU6500 - #define GYRO_MPU6500_ALIGN CW270_DEG #define MAG diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 222cd71ce..7160da98f 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -19,19 +19,14 @@ #define TARGET_BOARD_IDENTIFIER "BJF4" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS -#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_FEATURE_ONESHOT125 -#define CONFIG_RX_SERIAL_PORT 3 #define USBD_PRODUCT_STRING "BlueJayF4" #define BOARD_HAS_VOLTAGE_DIVIDER #define USE_EXTI -#define INVERTER PB15 -#define INVERTER_USART USART6 +#define INVERTER PB15 +#define INVERTER_USART USART6 #define BEEPER PB7 #define BEEPER_INVERTED diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 50f5790a3..cda67742e 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -20,12 +20,6 @@ #define TARGET_BOARD_IDENTIFIER "REVO" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS -#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_FEATURE_ONESHOT125 -#define CONFIG_MSP_PORT 2 -#define CONFIG_RX_SERIAL_PORT 1 #define USBD_PRODUCT_STRING "Revolution" #ifdef OPBL diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index b3d1a4941..3c0287f2f 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -19,12 +19,6 @@ #define TARGET_BOARD_IDENTIFIER "REVN" #define CONFIG_START_FLASH_ADDRESS (0x08060000) //0x08060000 to 0x08080000 (FLASH_Sector_7) -#define CONFIG_SERIALRX_PROVIDER 2 -#define CONFIG_BLACKBOX_DEVICE 1 -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_FEATURE_ONESHOT125 -#define CONFIG_MSP_PORT 1 -#define CONFIG_RX_SERIAL_PORT 2 #define USBD_PRODUCT_STRING "Revo Nano" #ifdef OPBL diff --git a/src/main/target/SPRACINGF3/target.mk b/src/main/target/SPRACINGF3/target.mk index 00e15bd25..ed7391c7a 100644 --- a/src/main/target/SPRACINGF3/target.mk +++ b/src/main/target/SPRACINGF3/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH +FEATURES = ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_mpu.c \ diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c new file mode 100644 index 000000000..e3b40ee63 --- /dev/null +++ b/src/main/target/ZCOREF3/target.c @@ -0,0 +1,104 @@ + +#include +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP +}; + diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h new file mode 100644 index 000000000..c02b4d3ec --- /dev/null +++ b/src/main/target/ZCOREF3/target.h @@ -0,0 +1,126 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "ZCF3" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define LED0 PB8 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 + +#define USE_EXTI +#define MPU_INT_EXTI PC13 +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH + + +#define GYRO +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 + +#define ACC +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 + +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG + +#define BARO +#define USE_BARO_BMP280 + +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define SERIAL_PORT_COUNT 3 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK +#define UART2_RX_PIN GPIO_Pin_15 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource14 +#define UART2_RX_PINSOURCE GPIO_PinSource15 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard) + +#define SPI1_NSS_PIN PB9 +#define SPI1_SCK_PIN PB3 +#define SPI1_MISO_PIN PB4 +#define SPI1_MOSI_PIN PB5 + +#define MPU6500_CS_PIN PB9 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip + +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) + diff --git a/src/main/target/ZCOREF3/target.mk b/src/main/target/ZCOREF3/target.mk new file mode 100644 index 000000000..4b232a787 --- /dev/null +++ b/src/main/target/ZCOREF3/target.mk @@ -0,0 +1,11 @@ +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c +