OmniNXT F4/F7 support

This commit is contained in:
jflyper 2018-04-26 10:31:24 +09:00
parent 7ee764b569
commit ac13e87c86
9 changed files with 652 additions and 1 deletions

View File

@ -1,5 +1,5 @@
OFFICIAL_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 FURYF4 REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3NEO SPRACINGF4EVO SPRACINGF7DUAL STM32F3DISCOVERY
SKIP_TARGETS := ALIENWHOOP MOTOLABF4
SKIP_TARGETS := ALIENWHOOP MOTOLABF4 OMNINXT
ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
OSD_SLAVE_TARGETS = SPRACINGF3OSD
@ -99,6 +99,8 @@ GROUP_3_TARGETS := \
OMNIBUSF4SD \
OMNIBUSF7 \
OMNIBUSF7V2 \
OMNINXT4 \
OMNINXT7 \
PLUMF4 \
PODIUMF4 \
RACEBASE \

View File

View File

View File

@ -0,0 +1,34 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#ifdef USE_TARGET_CONFIG
#include "io/serial.h"
#include "pg/pg.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[SERIAL_PORT_USART1].functionMask = FUNCTION_RX_SERIAL;
serialConfigMutable()->portConfigs[SERIAL_PORT_UART5].functionMask = FUNCTION_ESC_SENSOR;
}
#endif

View File

@ -0,0 +1,300 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "build/debug.h"
#include "drivers/adc_impl.h"
#include "drivers/io_types.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/rcc.h"
#include "drivers/time.h"
#include "hardware_revision.h"
#undef DEBUG_HARDWARE_REVISION_ADC
#undef DEBUG_HARDWARE_REVISION_TABLE
uint8_t hardwareRevision = 0;
// Do ADC on IDDetectPin and determine revision
// If VREFINT is used, we can (probably) get a pretty good precision
// that we can distinguish tens of different voltages.
#define ADC_ID_DETECT_PIN PC2
typedef struct idDetect_s {
uint32_t ratio;
uint8_t revision;
} idDetect_t;
// To deploy the analog ID detection in production:
// - Need some theoretical evaluation and experimentation to determine
// IDDET_ERROR value (ADC with VREFINT compensation is quite accurate).
// - Do some planning on revision numbering scheme.
// - Divider value planning for the scheme (separation).
#define IDDET_RATIO(highside, lowside) ((lowside) * 1000 / ((lowside) + (highside)))
#define IDDET_ERROR 12
static idDetect_t idDetectTable[] = {
#ifdef OMNINXT7
{ IDDET_RATIO(10000, 10000), 1 },
#endif
#ifdef OMNINXT4
{ IDDET_RATIO(10000, 10000), 1 },
#endif
};
ioTag_t idDetectTag;
#if defined(OMNINXT4)
#define VREFINT_CAL_ADDR 0x1FFF7A2A
static void adcIDDetectInit(void)
{
idDetectTag = IO_TAG(ADC_ID_DETECT_PIN);
IOConfigGPIO(IOGetByTag(idDetectTag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
RCC_ClockCmd(RCC_APB2(ADC1), ENABLE);
ADC_CommonInitTypeDef ADC_CommonInitStructure;
ADC_CommonStructInit(&ADC_CommonInitStructure);
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
ADC_CommonInit(&ADC_CommonInitStructure);
ADC_InitTypeDef ADC_InitStructure;
ADC_StructInit(&ADC_InitStructure);
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = 2; // Not used
ADC_InitStructure.ADC_ScanConvMode = ENABLE;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_Cmd(ADC1, ENABLE);
ADC_TempSensorVrefintCmd(ENABLE);
delayMicroseconds(10); // Maximum startup time for internal sensors (DM00037051 5.3.22 & 24)
uint32_t channel = adcChannelByTag(idDetectTag);
ADC_InjectedDiscModeCmd(ADC1, DISABLE);
ADC_InjectedSequencerLengthConfig(ADC1, 2);
ADC_InjectedChannelConfig(ADC1, channel, 1, ADC_SampleTime_480Cycles);
ADC_InjectedChannelConfig(ADC1, ADC_Channel_Vrefint, 2, ADC_SampleTime_480Cycles);
}
static void adcIDDetectDeinit(void)
{
ADC_Cmd(ADC1, DISABLE);
ADC_DeInit();
IOConfigGPIO(IOGetByTag(idDetectTag), IOCFG_IPU);
}
static void adcIDDetectStart(void)
{
ADC_ClearFlag(ADC1, ADC_FLAG_JEOC);
ADC_SoftwareStartInjectedConv(ADC1);
}
static void adcIDDetectWait(void)
{
while (ADC_GetFlagStatus(ADC1, ADC_FLAG_JEOC) == RESET) {
// Empty
}
}
static uint16_t adcIDDetectReadIDDet(void)
{
return ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
}
static uint16_t adcIDDetectReadVrefint(void)
{
return ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_2);
}
#endif
#if defined(OMNINXT7)
#define VREFINT_CAL_ADDR 0x1FF07A2A
#include "drivers/adc_impl.h"
static adcDevice_t adcIDDetHardware =
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = ADC1_DMA_STREAM, .channel = DMA_CHANNEL_0 };
// XXX adcIDDetectInitDevice is an exact copy of adcInitDevice() from adc_stm32f7xx.c. Export and use?
static void adcIDDetectInitDevice(adcDevice_t *adcdev, int channelCount)
{
adcdev->ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8;
adcdev->ADCHandle.Init.ContinuousConvMode = ENABLE;
adcdev->ADCHandle.Init.Resolution = ADC_RESOLUTION_12B;
adcdev->ADCHandle.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T1_CC1;
adcdev->ADCHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
adcdev->ADCHandle.Init.DataAlign = ADC_DATAALIGN_RIGHT;
adcdev->ADCHandle.Init.NbrOfConversion = channelCount;
#ifdef USE_ADC_INTERNAL
// Multiple injected channel seems to require scan conversion mode to be
// enabled even if main (non-injected) channel count is 1.
adcdev->ADCHandle.Init.ScanConvMode = ENABLE;
#else
adcdev->ADCHandle.Init.ScanConvMode = channelCount > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
#endif
adcdev->ADCHandle.Init.DiscontinuousConvMode = DISABLE;
adcdev->ADCHandle.Init.NbrOfDiscConversion = 0;
adcdev->ADCHandle.Init.DMAContinuousRequests = ENABLE;
adcdev->ADCHandle.Init.EOCSelection = DISABLE;
adcdev->ADCHandle.Instance = adcdev->ADCx;
if (HAL_ADC_Init(&adcdev->ADCHandle) != HAL_OK)
{
/* Initialization Error */
}
}
static void adcIDDetectInit(void)
{
idDetectTag = IO_TAG(ADC_ID_DETECT_PIN);
IOConfigGPIO(IOGetByTag(idDetectTag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL));
adcIDDetectInitDevice(&adcIDDetHardware, 2);
ADC_InjectionConfTypeDef iConfig;
iConfig.InjectedSamplingTime = ADC_SAMPLETIME_480CYCLES;
iConfig.InjectedOffset = 0;
iConfig.InjectedNbrOfConversion = 2;
iConfig.InjectedDiscontinuousConvMode = DISABLE;
iConfig.AutoInjectedConv = DISABLE;
iConfig.ExternalTrigInjecConv = 0; // Don't care
iConfig.ExternalTrigInjecConvEdge = 0; // Don't care
iConfig.InjectedChannel = ADC_CHANNEL_VREFINT;
iConfig.InjectedRank = 1;
if (HAL_ADCEx_InjectedConfigChannel(&adcIDDetHardware.ADCHandle, &iConfig) != HAL_OK) {
/* Channel Configuration Error */
}
iConfig.InjectedChannel = adcChannelByTag(idDetectTag);
iConfig.InjectedRank = 2;
if (HAL_ADCEx_InjectedConfigChannel(&adcIDDetHardware.ADCHandle, &iConfig) != HAL_OK) {
/* Channel Configuration Error */
}
}
static void adcIDDetectDeinit(void)
{
HAL_ADC_DeInit(&adcIDDetHardware.ADCHandle);
IOConfigGPIO(IOGetByTag(idDetectTag), IOCFG_IPU);
}
static void adcIDDetectStart(void)
{
HAL_ADCEx_InjectedStart(&adcIDDetHardware.ADCHandle);
}
static void adcIDDetectWait(void)
{
while (HAL_ADCEx_InjectedPollForConversion(&adcIDDetHardware.ADCHandle, 0) != HAL_OK) {
// Empty
}
}
static uint16_t adcIDDetectReadVrefint(void)
{
return HAL_ADCEx_InjectedGetValue(&adcIDDetHardware.ADCHandle, ADC_INJECTED_RANK_1);
}
static uint16_t adcIDDetectReadIDDet(void)
{
return HAL_ADCEx_InjectedGetValue(&adcIDDetHardware.ADCHandle, ADC_INJECTED_RANK_2);
}
#endif
void detectHardwareRevision(void)
{
adcIDDetectInit();
uint32_t vrefintValue = 0;
uint32_t iddetValue = 0;
for (int i = 0 ; i < 16 ; i++) {
adcIDDetectStart();
adcIDDetectWait();
iddetValue += adcIDDetectReadIDDet();
vrefintValue += adcIDDetectReadVrefint();
}
vrefintValue /= 16;
iddetValue /= 16;
uint32_t iddetRatio = (iddetValue * vrefintValue) / *(uint16_t *)VREFINT_CAL_ADDR;
iddetRatio = iddetRatio * 1000 / 4096;
#ifdef DEBUG_HARDWARE_REVISION_ADC
debug[0] = *(uint16_t *)VREFINT_CAL_ADDR;
debug[1] = vrefintValue;
debug[2] = iddetValue;
debug[3] = iddetRatio;
#endif
for (size_t entry = 0; entry < ARRAYLEN(idDetectTable); entry++) {
#ifdef DEBUG_HARDWARE_REVISION_TABLE
debug[0] = iddetRatio;
debug[1] = idDetectTable[entry].ratio - IDDET_ERROR;
debug[2] = idDetectTable[entry].ratio + IDDET_ERROR;
#endif
if (idDetectTable[entry].ratio - IDDET_ERROR < iddetRatio && iddetRatio < idDetectTable[entry].ratio + IDDET_ERROR) {
hardwareRevision = idDetectTable[entry].revision;
break;
}
}
adcIDDetectDeinit();
}
void updateHardwareRevision(void)
{
// Empty
}
ioTag_t selectMPUIntExtiConfigByHardwareRevision(void)
{
return IO_TAG_NONE;
}
#endif

View File

@ -0,0 +1,23 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
extern uint8_t hardwareRevision;
void updateHardwareRevision(void);
void detectHardwareRevision(void);
ioTag_t selectMPUIntExtiConfigByHardwareRevision(void);

View File

@ -0,0 +1,66 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// Main motors
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // M1
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // M2
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // M3
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // M4
// Additional motors/servos
DEF_TIM(TIM8, CH4, PC9, TIM_USE_NONE, 0, 0), // MST5 Collision with TX/RX6 (useful for OCTO)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_NONE, 0, 0), // MST6 Collision with TX/RX6 (useful for OCTO)
DEF_TIM(TIM11, CH1, PB9, TIM_USE_NONE, 0, 0), // I2C1_SDA, MST7
DEF_TIM(TIM10, CH1, PB8, TIM_USE_NONE, 0, 0), // I2C1_SCL, MST8
// PPM
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // Overloaded with UART1_RX
// LED strip
DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0),
// CAMCTL
DEF_TIM(TIM12, CH2, PB15, TIM_USE_NONE, 0, 0),
// Backdoor timers on UARTs
DEF_TIM(TIM4, CH1, PB6, TIM_USE_NONE, 0, 0), // UART1_TX Collision with PPM
DEF_TIM(TIM9, CH1, PA2, TIM_USE_NONE, 0, 0), // UART2_TX
DEF_TIM(TIM9, CH2, PA3, TIM_USE_NONE, 0, 0), // UART2_RX
DEF_TIM(TIM2, CH3, PB10, TIM_USE_NONE, 0, 0), // UART3_TX
DEF_TIM(TIM2, CH4, PB11, TIM_USE_NONE, 0, 0), // UART3_RX
DEF_TIM(TIM5, CH1, PA0, TIM_USE_NONE, 0, 0), // UART4_TX
DEF_TIM(TIM5, CH2, PA1, TIM_USE_NONE, 0, 0), // UART4_RX
DEF_TIM(TIM8, CH1, PC6, TIM_USE_NONE, 0, 0), // UART6_TX Collision with MS1&2 (useful for OCTO)
DEF_TIM(TIM8, CH2, PC7, TIM_USE_NONE, 0, 0), // UART6_RX Collision with MS1&2 (useful for OCTO)
// Others
DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE, 0, 0), // CS_ExtIMU, Collision with LED_STRIP
};

View File

@ -0,0 +1,200 @@
/*
* This 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.
*
* This software 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 this software. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define USE_TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#ifdef OMNINXT4
#define TARGET_BOARD_IDENTIFIER "ONX4"
#define USBD_PRODUCT_STRING "OmniNXT4"
#else
#define TARGET_BOARD_IDENTIFIER "ONX7"
#define USBD_PRODUCT_STRING "OmniNXT7"
#endif
#define LED0_PIN PB2
#define USE_BEEPER
#define BEEPER_PIN PC13
#define BEEPER_INVERTED
#define USE_DSHOT_DMAR
#define ENABLE_DSHOT_DMAR true
#ifdef OMNINXT4
#define USE_INVERTER
#define INVERTER_PIN_UART2 PC5
#endif
#define USE_ACC
#define USE_GYRO
// For debugging with NUC405RG
#define USE_FAKE_ACC
#define USE_FAKE_GYRO
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
#define USE_DUAL_GYRO
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_CS_PIN PB12 // Onboard IMU
#define GYRO_1_ALIGN CW0_DEG
#define ACC_1_ALIGN CW0_DEG
#define GYRO_2_SPI_INSTANCE SPI1
#define GYRO_2_CS_PIN PA8 // External IMU
#define GYRO_2_ALIGN CW0_DEG
#define ACC_2_ALIGN CW0_DEG
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
// MPU interrupts
//#define USE_EXTI
//#define MPU_INT_EXTI PC4
//#define USE_MPU_DATA_READY_SIGNAL
#define USE_MAG
#define MAG_I2C_INSTANCE (I2CDEV_1)
#define USE_MAG_HMC5883
#define USE_BARO
#define USE_BARO_SPI_LPS
#define LPS_SPI_INSTANCE SPI2
#define LPS_CS_PIN PA10
#define DEFAULT_BARO_SPI_LPS
#define BARO_I2C_INSTANCE (I2CDEV_1)
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PA15
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_SPI_INSTANCE SPI2
#define M25P16_CS_PIN PC14
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_VCP
#define VBUS_SENSING_PIN PC15
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11 // PB11, shared with I2C2
#define UART3_TX_PIN PB10 // PB10, shared with I2C2
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN NONE // PC12, alt SPI3_MOSI
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 9 // VCP, UART x 6, SOFTSERIAL x 2
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_PIN PB7
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PC3
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10 // PC10, alt UART3_TX, UART4_TX
#define SPI3_MISO_PIN PC11 // PC11, alt UART3_RX, UART4_RX
#define SPI3_MOSI_PIN PC12 // PC12, alt UART5_TX
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8 // PB8, alt MST8
#define I2C1_SDA PB9 // PB9, alt MST7
#define USE_I2C_DEVICE_2
#define I2C2_SCL NONE // PB10 alt UART3TX
#define I2C2_SDA NONE // PB11 alt UART3RX
#define USE_I2C_DEVICE_3
#define I2C3_SCL NONE
#define I2C3_SDA NONE
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0 // 11:1 (10K + 1K) divider
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC4
#define EXTERNAL1_ADC_PIN PA4
#define CAMERA_CONTROL_PIN PB15
#define USE_TRANSPONDER
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04
#define USE_RANGEFINDER_TF
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_LED_STRIP)
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) // Less SWC and SWD
#define TARGET_IO_PORTB (0xffff)
#define TARGET_IO_PORTC (0xffff)
#define TARGET_IO_PORTD BIT(2)
#define USABLE_TIMER_CHANNEL_COUNT 22
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12))

View File

@ -0,0 +1,26 @@
ifeq ($(TARGET), OMNINXT4)
F405_TARGETS += $(TARGET)
else
ifeq ($(TARGET), OMNINXT7)
F7X2RE_TARGETS += $(TARGET)
else
# Nothing to do for generic target
endif
endif
FEATURES += VCP ONBOARDFLASH
# XXX Remove fake drivers for final production
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu9250.c \
drivers/barometer/barometer_lps.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/max7456.c