diff --git a/src/main/target/FURYF4/config.c b/src/main/target/FURYF4/config.c new file mode 100644 index 000000000..0a12258f2 --- /dev/null +++ b/src/main/target/FURYF4/config.c @@ -0,0 +1,86 @@ +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for FURYF4 targets +void targetConfiguration(void) { + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + masterConfig.gyro_sync_denom = 1; + masterConfig.pid_process_denom = 1; +} diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 8f6937859..4006d9d66 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -18,6 +18,8 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "FYF4" +#define TARGET_CONFIG + #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) #define USBD_PRODUCT_STRING "FuryF4" @@ -36,6 +38,7 @@ #define MPU_INT_EXTI PC4 #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) #define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 @@ -43,15 +46,18 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 +#define GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG + #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG @@ -68,17 +74,6 @@ #define SDCARD_SPI_INSTANCE SPI2 #define SDCARD_SPI_CS_PIN PB12 -/* -#define SDCARD_DETECT_PIN PD2 -#define SDCARD_DETECT_EXTI_LINE EXTI_Line2 -#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2 -#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD -#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn - -#define SDCARD_SPI_INSTANCE SPI3 -#define SDCARD_SPI_CS_PIN PB3 -*/ - // 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 // Divide to under 25MHz for normal operation: @@ -95,7 +90,6 @@ #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CHANNEL DMA_Channel_0 - #define USE_FLASHFS #define USE_FLASH_M25P16 #define M25P16_CS_PIN PB3 @@ -110,7 +104,6 @@ #define USE_UART1 #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