1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 11:29:56 +03:00

Delete F3 targets

This commit is contained in:
Pawel Spychalski (DzikuVx) 2022-05-26 19:27:42 +02:00
parent 8d70c7a186
commit 2c8a25d67a
66 changed files with 0 additions and 3506 deletions

View file

@ -1,2 +0,0 @@
target_stm32f303xc(AIRHEROF3 HSE_MHZ 12 SKIP_RELEASES)
target_stm32f303xc(AIRHEROF3_QUAD HSE_MHZ 12 SKIP_RELEASES)

View file

@ -1,10 +0,0 @@
# AIRHEROF3
* This is the AIR3 PARIS Sirius AirHERO 32 F3 board from MultiWiiCopter
* Source: http://www.multiwiicopter.com/products/inav-air3-fixed-wing
## HW info
* STM32F303RCT6
* MPU6500 SPI
* BMP280 baro SPI

View file

@ -1,53 +0,0 @@
/*
* 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>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM, 0),
DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM | TIM_USE_ANY, 0),
DEF_TIM(TIM3, CH2, PA7, TIM_USE_PWM, 0),
#if 1
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // DMA1_CH2
DEF_TIM(TIM1, CH4, PA11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // DMA1_CH4
DEF_TIM(TIM8, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA2_CH3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // DMA1_CH4 - conflict with TIM1_CH4
#else
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // DMA1_CH2
DEF_TIM(TIM4, CH1, PA11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA1_CH1
DEF_TIM(TIM8, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA2_CH3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA1_CH4
#endif
#if !defined(AIRHEROF3_QUAD)
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA2_CH5
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // DMA2_CH1
#endif
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,125 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "AIR3"
#define LED0 PB3
#define LED1 PB4
#define BEEPER PA12
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC13
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU INT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SPI
#define USE_SPI_DEVICE_2
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW0_DEG
#define MPU6500_SPI_BUS BUS_SPI2
#define MPU6500_CS_PIN PB12
#define BMP280_SPI_BUS BUS_SPI2
#define BMP280_CS_PIN PB5
#define USE_BARO
#define USE_BARO_BMP280
#define USE_PITOT_ADC
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_RX_PIN PA6
#define SOFTSERIAL_1_TX_PIN PA7
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#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 BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_1_INSTANCE ADC2
#define ADC_CHANNEL_2_PIN PA1
#define ADC_CHANNEL_2_INSTANCE ADC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define AIRSPEED_ADC_CHANNEL ADC_CHN_2
/*
#define USE_LED_STRIP
#define WS2811_PIN PA6
*/
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_SOFTSERIAL)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER
#ifdef AIRHEROF3_QUAD
#define USE_I2C
#define USE_I2C_DEVICE_1 // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9
// MAG is I2C, so it is only useful when I2C is available
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_LIS3MDL
#define MAX_PWM_OUTPUT_PORTS 8
#define TARGET_MOTOR_COUNT 4
#else
#define MAX_PWM_OUTPUT_PORTS 10
#define TARGET_MOTOR_COUNT 6
#endif
#define USE_SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))

View file

@ -1,73 +0,0 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
http://www.alienflight.com
AlienFlight F3 Eagle files are available at:
https://github.com/MJ666/Flight-Controllers
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
http://www.alienflightng.com
This targets supports various variants of brushed and brushless flight controllers. All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users and in some cases RC vendors to build them.
Some variants of the AlienFlight controllers will be available for purchase from:
http://www.microfpv.eu
https://micro-motor-warehouse.com
Here are the general hardware specifications for this boards:
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
- STM32F711RET6 MCU (ALIENFLIGHTNGF7)
- MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all published designs and enabled in the firmware
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
- some new F4 boards using a 4-layer PCB for better power distribution
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
- CPPM input
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- small footprint
- direct operation from a single cell LIPO battery for brushed versions
- 3.3V LDO power regulator (older prototypes)
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 4S operation and also have an 5V power output
- battery monitoring with an LED or buzzer output (for some variants only)
- current monitoring (F4/F7 V1.1 versions)
- SDCard Reader for black box monitoring (F4/F7 V1.1 versions)
- (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions)
- hardware detection of brushed and brushless versions with individual defaults
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
## Flashing the firmware
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.
The firmware for the OpenSky receiver can be updated via serial pass-through and the embedded boot loader. The initial flashing need to be done with the ISP programming pins. The target for the embedded AlienFlight OpenSky receiver is "AFF4RX". Please refer to the OpenSky project for more details.
https://github.com/fishpepper/OpenSky/blob/master/README.md

View file

@ -1 +0,0 @@
target_stm32f303xc(ALIENFLIGHTF3 SKIP_RELEASES)

View file

@ -1,76 +0,0 @@
/*
* 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>
#include "common/axis.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_output.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/battery.h"
#ifdef BRUSHED_MOTORS_PWM_RATE
#undef BRUSHED_MOTORS_PWM_RATE
#endif
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
// alternative defaults settings for BlueJayF4 targets
void targetConfiguration(void)
{
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
batteryMetersConfigMutable()->voltage.scale = 200;
rxConfigMutable()->spektrum_sat_bind = 5;
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
}
pidProfileMutable()->bank_mc.pid[ROLL].P = 36;
pidProfileMutable()->bank_mc.pid[PITCH].P = 36;
failsafeConfigMutable()->failsafe_delay = 2;
failsafeConfigMutable()->failsafe_off_delay = 0;
parseRcChannels("TAER1234");
*primaryMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
*primaryMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
*primaryMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
*primaryMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
*primaryMotorMixerMutable(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
*primaryMotorMixerMutable(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
*primaryMotorMixerMutable(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
*primaryMotorMixerMutable(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L
}

View file

@ -1,72 +0,0 @@
/*
* 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"
#include "build/build_config.h"
#include "drivers/time.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "hardware_revision.h"
uint8_t hardwareRevision = AFF3_UNKNOWN;
static IO_t HWDetectPin = IO_NONE;
void detectHardwareRevision(void)
{
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0);
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
// Check hardware revision
delayMicroseconds(40); // allow configuration to settle
if (IORead(HWDetectPin)) {
hardwareRevision = AFF3_REV_1;
} else {
hardwareRevision = AFF3_REV_2;
}
}
void updateHardwareRevision(void)
{
}
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
// MPU_INT output on V1 PA15
static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = {
.tag = IO_TAG(PA15)
};
// MPU_INT output on V2 PB13
static const extiConfig_t alienFlightF3V2MPUIntExtiConfig = {
.tag = IO_TAG(PB13)
};
if (hardwareRevision == AFF3_REV_1) {
return &alienFlightF3V1MPUIntExtiConfig;
}
else {
return &alienFlightF3V2MPUIntExtiConfig;
}
}

View file

@ -1,32 +0,0 @@
/*
* 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
#include "drivers/exti.h"
typedef enum awf3HardwareRevision_t {
AFF3_UNKNOWN = 0,
AFF3_REV_1, // MPU6050 / MPU9150 (I2C)
AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
} awf3HardwareRevision_e;
extern uint8_t hardwareRevision;
void updateHardwareRevision(void);
void detectHardwareRevision(void);
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -1,41 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// up to 10 Motor Outputs
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PB15 - NONE
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PB14 - DMA1_CH5
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA8 - DMA1_CH2
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB0 - DMA2_CH5
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PA6 - DMA1_CH3
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6 - PA2 - DMA1_CH1
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM7 - PB1 - DMA2_CH1
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_ANY, 0), // PWM8 - PA7 - DMA1_CH7
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM9 - PA4 - DMA_NONE
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM10 - PA1 - DMA1_CH7
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0), // PPM - PA3 - DMA1_CH7
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,133 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "AFF3" // ALIENFLIGHT F3
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2
#define USE_BRUSHED_ESC_AUTODETECT
// LED's V1
#define LED0 PB4
#define LED1 PB5
// LED's V2
#define LED0_A PB8
#define LED1_A PB9
#define BEEPER PA5
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// Using MPU6050 for the moment.
#define USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW270_DEG
#define MPU6050_I2C_BUS BUS_I2C2
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW270_DEG
#define MPU6500_CS_PIN PA15
#define MPU6500_SPI_BUS BUS_SPI3
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW270_DEG
#define MPU9250_CS_PIN PA15
#define MPU9250_SPI_BUS BUS_SPI3
// No baro support.
//#define USE_BARO
//#define USE_BARO_MS5611
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_MPU9250
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_LIS3MDL
#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 UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define USE_I2C_PULLUP
#define USE_I2C_DEVICE_2 // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
// SPI3
// PA15 38 SPI3_NSS
// PB3 39 SPI3_SCK
// PB4 40 SPI3_MISO
// PB5 41 SPI3_MOSI
#define USE_SPI
#define USE_SPI_DEVICE_3
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define VBAT_SCALE_DEFAULT 20
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB12 (Pin 25)
#define BINDPLUG_PIN PB12
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define SERIALRX_UART SERIAL_PORT_USART3
#define RX_CHANNELS_TAER
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
#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))

View file

@ -1 +0,0 @@
target_stm32f303xc(BETAFLIGHTF3 COMPILE_DEFINITIONS "SPRACINGF3" SKIP_RELEASES)

View file

@ -1,26 +0,0 @@
/*
* 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>
#include "sensors/battery.h"
void targetConfiguration(void)
{
batteryMetersConfigMutable()->current.scale = 20;
}

View file

@ -1,13 +0,0 @@
==BETAFLIGHTF3==
Owner: BorisB
Board information:
- CPU - STM32F303CCT6
- MPU-6000
- SD Card Slot
- Build in 5V BEC + LC filter - board can be powered from main battery
- Built in current meter, PDB
More info to come

View file

@ -1,47 +0,0 @@
/*
* 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/>.
*/
//Target code By BorisB and Hector "Hectech FPV" Hind
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/timer.h"
#include "drivers/pwm_mapping.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0), // PPM DMA(1,4)
// Motors 1-4
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 UP(1,6)
DEF_TIM(TIM8, CH1N, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 UP(2,1)
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 UP(2,1)
DEF_TIM(TIM17, CH1, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 UP(1,7)
// Motors 5-6 or SoftSerial
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6
// Motors 7-8 or UART2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM7/UART2_RX
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM8/UART2_TX
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // LED DMA(1,2)
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,123 +0,0 @@
/*
* 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/>.
*/
//Target code By BorisB and Hector "Hectech FPV" Hind
#pragma once
#define TARGET_BOARD_IDENTIFIER "BFF3"
#define BEEPER PC15
#define BEEPER_INVERTED
#define MPU6000_CS_PIN PA15
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 1
#define GYRO_INT_EXTI PC13
#define USE_EXTI
//#define USE_ESC_SENSOR // XXX
//#define REMAP_TIM16_DMA // XXX
//#define REMAP_TIM17_DMA // XXX
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
//#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
//#define USE_ESCSERIAL // XXX
//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1 XXX
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define SOFTSERIAL_1_RX_PIN PB0 // PWM 5
#define SOFTSERIAL_1_TX_PIN PB1 // PWM 6
#undef USE_I2C
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI1_NSS_PIN PA15
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI1
#define MAX7456_CS_PIN PA1
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_BUS BUS_SPI2
#define SDCARD_CS_PIN SPI2_NSS_PIN
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PA5
#define ADC_CHANNEL_3_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
//#define USE_LED_STRIP
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
//#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1 // XXX
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_CURRENT_METER | FEATURE_TELEMETRY ) // XXX
//#define USE_SPEKTRUM_BIND
//#define BIND_PIN UART2_RX_PIN
#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 MAX_PWM_OUTPUT_PORTS 8

View file

@ -1 +0,0 @@
target_stm32f303xc(COLIBRI_RACE SKIP_RELEASES)

View file

@ -1,49 +0,0 @@
/*
* 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 "config/feature.h"
#include "fc/config.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/gyro.h"
void targetConfiguration(void)
{
gyroConfigMutable()->looptime = 1000;
rxConfigMutable()->rcmap[0] = 1;
rxConfigMutable()->rcmap[1] = 2;
rxConfigMutable()->rcmap[2] = 3;
rxConfigMutable()->rcmap[3] = 0;
featureSet(FEATURE_VBAT);
featureSet(FEATURE_LED_STRIP);
serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP;
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
}
}

View file

@ -1,40 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PC6
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PC7
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PMW4 - PC8
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PC9
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR, 0), // PWM6 - PA0
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR, 0), // PWM7 - PA1
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR, 0), // PWM8 - PA2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR, 0), // PWM9 - PA3
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR, 0), // PWM10 - PB14
DEF_TIM(TIM15, CH2, PB15, TIM_USE_MC_MOTOR, 0), // PWM11 - PB15
DEF_TIM(TIM16, CH1, PA6, TIM_USE_LED, 0), // PWM11 - PB15
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,127 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "CLBR"
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define BEEPER_INVERTED
#define USE_DSHOT
#define USE_ESC_SENSOR
// MPU6500 interrupt
#define USE_EXTI
#define GYRO_INT_EXTI PA5
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI1_NSS_PIN PA4
#define MPU6500_CS_PIN SPI1_NSS_PIN
#define MPU6500_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN SPI1_NSS_PIN
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW270_DEG
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW270_DEG
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_MAG9250
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC2
#define ADC_CHANNEL_4_PIN PC3
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA6
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// 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 BNO055_I2C_BUS BUS_I2C2

View file

@ -1 +0,0 @@
target_stm32f303xc(FALCORE HSE_MHZ 12 SKIP_RELEASES)

View file

@ -1,5 +0,0 @@
# CONNEX FALCORE
* The ready-to-flight HD racing drone equipped with sonar for easy beginner mode
* Source: http://www.amimon.com/fpv-market/falcore-product-page/
* INAV teaser: https://youtu.be/6JwmDqYqmUs

View file

@ -1,195 +0,0 @@
/*
* 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 "config/feature.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_mapping.h"
#include "blackbox/blackbox.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/boardalignment.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "navigation/navigation.h"
void targetConfiguration(void)
{
mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR;
featureSet(FEATURE_VBAT);
featureSet(FEATURE_GPS);
featureSet(FEATURE_TELEMETRY);
featureSet(FEATURE_LED_STRIP);
featureSet(FEATURE_BLACKBOX);
serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP; // VCP
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_GPS; // UART1
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; // UART2
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_NONE; // UART4
serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_TELEMETRY_MAVLINK; // UART5
gyroConfigMutable()->looptime = 1000;
gyroConfigMutable()->gyro_lpf = 0; // 256 Hz
gyroConfigMutable()->gyro_main_lpf_hz = 90;
accelerometerConfigMutable()->acc_hardware = ACC_MPU6500;
accelerometerConfigMutable()->acc_lpf_hz = 15;
compassConfigMutable()->mag_hardware = MAG_HMC5883;
compassConfigMutable()->mag_align = CW270_DEG_FLIP;
barometerConfigMutable()->baro_hardware = BARO_MS5607;
barometerConfigMutable()->use_median_filtering = 1;
rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
rxConfigMutable()->serialrx_provider = SERIALRX_IBUS;
rxConfigMutable()->mincheck = 1100;
rxConfigMutable()->maxcheck = 1900;
blackboxConfigMutable()->rate_num = 1;
blackboxConfigMutable()->rate_denom = 4;
motorConfigMutable()->maxthrottle = 2000;
motorConfigMutable()->mincommand = 980;
motorConfigMutable()->motorPwmRate = 2000;
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_ONESHOT125;
failsafeConfigMutable()->failsafe_delay = 5;
failsafeConfigMutable()->failsafe_recovery_delay = 5;
failsafeConfigMutable()->failsafe_off_delay = 200;
currentBatteryProfile->failsafe_throttle = 1200;
failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH;
boardAlignmentMutable()->rollDeciDegrees = 0;
boardAlignmentMutable()->pitchDeciDegrees = 165;
boardAlignmentMutable()->yawDeciDegrees = 0;
imuConfigMutable()->small_angle = 30;
gpsConfigMutable()->provider = GPS_UBLOX;
gpsConfigMutable()->sbasMode = SBAS_NONE;
gpsConfigMutable()->dynModel = GPS_DYNMODEL_AIR_1G;
gpsConfigMutable()->autoConfig = 1;
gpsConfigMutable()->autoBaud = 1;
gpsConfigMutable()->gpsMinSats = 7;
rcControlsConfigMutable()->deadband = 10;
rcControlsConfigMutable()->yaw_deadband = 15;
navConfigMutable()->general.flags.disarm_on_landing = 1;
navConfigMutable()->general.flags.use_thr_mid_for_althold = 1;
navConfigMutable()->general.flags.extra_arming_safety = 1;
navConfigMutable()->general.flags.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS;
navConfigMutable()->general.max_auto_speed = 500;
navConfigMutable()->general.max_auto_climb_rate = 200;
navConfigMutable()->general.max_manual_speed = 500;
navConfigMutable()->general.max_manual_climb_rate = 200;
navConfigMutable()->general.rth_altitude = 1000;
navConfigMutable()->mc.max_bank_angle = 30;
currentBatteryProfile->nav.mc.hover_throttle = 1500;
navConfigMutable()->mc.auto_disarm_delay = 2000;
/*
aux 0 0 0 1150 2100
aux 1 2 0 1300 1700
aux 2 20 0 1150 2100
aux 3 3 3 1300 1700
aux 4 9 3 1300 1700
aux 5 8 3 1700 2100
aux 6 19 1 1375 2100
*/
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
modeActivationConditionsMutable(index)->modeId = 0;
modeActivationConditionsMutable(index)->auxChannelIndex = 0;
modeActivationConditionsMutable(index)->range.startStep = 0;
modeActivationConditionsMutable(index)->range.endStep = 0;
}
configureModeActivationCondition(0, BOXARM, 0, 1150, 2100);
configureModeActivationCondition(1, BOXANGLE, 0, 1300, 1700);
configureModeActivationCondition(2, BOXNAVALTHOLD, 3, 1300, 1700);
configureModeActivationCondition(3, BOXNAVPOSHOLD, 3, 1300, 1700);
configureModeActivationCondition(4, BOXNAVRTH, 3, 1700, 2100);
configureModeActivationCondition(5, BOXANGLE, 3, 1700, 2100);
// Rates and PIDs
setConfigProfile(0);
pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 65;
pidProfileMutable()->bank_mc.pid[PID_PITCH].I = 50;
pidProfileMutable()->bank_mc.pid[PID_PITCH].D = 28;
pidProfileMutable()->bank_mc.pid[PID_ROLL].P = 45;
pidProfileMutable()->bank_mc.pid[PID_ROLL].I = 40;
pidProfileMutable()->bank_mc.pid[PID_ROLL].D = 25;
pidProfileMutable()->bank_mc.pid[PID_YAW].P = 90;
pidProfileMutable()->bank_mc.pid[PID_YAW].I = 45;
pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
pidProfileMutable()->max_angle_inclination[FD_ROLL] = 300;
pidProfileMutable()->max_angle_inclination[FD_PITCH] = 300;
pidProfileMutable()->dterm_lpf_hz = 70;
pidProfileMutable()->yaw_lpf_hz = 35;
pidProfileMutable()->pidSumLimit = 500;
pidProfileMutable()->axisAccelerationLimitRollPitch = 0;
pidProfileMutable()->axisAccelerationLimitYaw = 10000;
pidProfileMutable()->bank_mc.pid[PID_POS_Z].P = 50;
pidProfileMutable()->bank_mc.pid[PID_POS_Z].I = 0;
pidProfileMutable()->bank_mc.pid[PID_POS_Z].D = 0;
pidProfileMutable()->bank_mc.pid[PID_VEL_Z].P = 100;
pidProfileMutable()->bank_mc.pid[PID_VEL_Z].I = 50;
pidProfileMutable()->bank_mc.pid[PID_VEL_Z].D = 10;
pidProfileMutable()->bank_mc.pid[PID_POS_XY].P = 50;
pidProfileMutable()->bank_mc.pid[PID_POS_XY].I = 100;
pidProfileMutable()->bank_mc.pid[PID_POS_XY].D = 10;
pidProfileMutable()->bank_mc.pid[PID_VEL_XY].P = 150;
pidProfileMutable()->bank_mc.pid[PID_VEL_XY].I = 20;
pidProfileMutable()->bank_mc.pid[PID_VEL_XY].D = 70;
((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcExpo8 = 60;
((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcYawExpo8 = 35;
((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_ROLL] = 54;
((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_PITCH] = 54;
((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_YAW] = 36;
((controlRateConfig_t*)currentControlRateProfile)->throttle.rcMid8 = 50;
((controlRateConfig_t*)currentControlRateProfile)->throttle.rcExpo8 = 0;
((controlRateConfig_t*)currentControlRateProfile)->throttle.dynPID = 10;
((controlRateConfig_t*)currentControlRateProfile)->throttle.pa_breakpoint = 1600;
beeperConfigMutable()->pwmMode = true;
}

View file

@ -1,42 +0,0 @@
/*
* 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"
#include "build/build_config.h"
#include "drivers/system.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
void initialisePreBootHardware(void)
{
// AUX_BUFF_EN
IOInit(DEFIO_IO(PB2), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PB2), IOCFG_OUT_OD);
IOLo(DEFIO_IO(PB2));
// VIS_SYS_BUFF_EN
IOInit(DEFIO_IO(PC3), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PC3), IOCFG_OUT_OD);
IOLo(DEFIO_IO(PC3));
}

View file

@ -1,46 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// MOTOR outputs
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR, 1),
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR, 1),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 1),
// Additional servo outputs
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_SERVO, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO, 0),
// PPM PORT - Also USART2 RX (AF5)
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0),
// LED_STRIP
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0),
// PWM_BUZZER
DEF_TIM(TIM16, CH1, PB4, TIM_USE_BEEPER, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,133 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "FLCR" // FaLCoRre
#define LED0 PC2
#define LED1 PB11
#define USE_HARDWARE_PREBOOT_SETUP // FALCORE board requires some hardware to be set up before booting and detecting sensors
#define BEEPER PB4
#define BEEPER_PWM_FREQUENCY 2700
#define MPU6500_CS_PIN PC0
#define MPU6500_SPI_BUS BUS_SPI1
#define USE_EXTI
#define GYRO_INT_EXTI PB0
#define USE_MPU_DATA_READY_SIGNAL
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW0_DEG
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5607
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART4
#define USE_UART5
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input.
#define UART2_RX_PIN PA3
#define UART4_TX_PIN PC10
#define UART4_RX_PIN PC11
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PB5
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define VBAT_SCALE_DEFAULT 78
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PF4
#define ADC_CHANNEL_2_PIN PA1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PC1
#define M25P16_SPI_BUS BUS_SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#define USE_RANGEFINDER
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_GPS | FEATURE_TELEMETRY | FEATURE_LED_STRIP)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6
// available IO pins (from schematics)
#define TARGET_IO_PORTA 0xFFFF
#define TARGET_IO_PORTB 0xFFFF
#define TARGET_IO_PORTC 0xFFFF
#define TARGET_IO_PORTD 0xFFFF
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define BNO055_I2C_BUS BUS_I2C2

View file

@ -1 +0,0 @@
target_stm32f303xc(FRSKYF3 SKIP_RELEASES)

View file

@ -1,29 +0,0 @@
/*
* 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 "rx/rx.h"
#include "io/serial.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
rxConfigMutable()->rssi_channel = 8;
}

View file

@ -1,38 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // LED
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,113 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "FRF3"
#define LED0_PIN PB3
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_ADDRESS 0x69
#define MPU6050_I2C_BUS BUS_I2C1
#define USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW270_DEG
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
// #define USE_SOFTSERIAL1
// #define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_SPI
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB4
#define USE_SPI
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_1
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define SPI1_NSS_PIN PC14
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB5
#define SDCARD_SPI_BUS BUS_SPI1
#define SDCARD_CS_PIN SPI1_NSS_PIN
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
//INAV is not using transponder, feature disabled
// #define TRANSPONDER
// #define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD)
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_USART3
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define MAX_PWM_OUTPUT_PORTS 8
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View file

@ -1,2 +0,0 @@
target_stm32f303xc(FURYF3 SKIP_RELEASES)
target_stm32f303xc(FURYF3_SPIFLASH SKIP_RELEASES)

View file

@ -1,24 +0,0 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH2, PB3, TIM_USE_PPM, 0), // PPM IN
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM17, CH1, PB5, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM16, CH1, PB4, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,149 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "FYF3"
#define LED0 PC14
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG // changedkb 270
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW90_DEG // changedkb 270
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_BUS BUS_SPI1
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW90_DEG // changedkb 270
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_BUS BUS_SPI1
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MPU9250
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define USE_BARO_BMP280
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#ifdef FURYF3_SPIFLASH
#define USE_FLASHFS
#undef BEEPER_INVERTED
#else
#define USE_SDCARD
#endif
#ifdef USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB12
#define M25P16_SPI_BUS BUS_SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#endif
#ifdef USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB2
#define SDCARD_SPI_BUS BUS_SPI2
#define SDCARD_CS_PIN SPI2_NSS_PIN
#endif
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define SOFTSERIAL_1_RX_PIN PB0
#define SOFTSERIAL_1_TX_PIN PB1
#define USE_I2C
#define USE_I2C_DEVICE_1 // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PA0
#define ADC_CHANNEL_2_PIN PA1
#define ADC_CHANNEL_3_PIN PA2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define USE_RANGEFINDER
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define USE_SPEKTRUM_BIND
// UART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))

View file

@ -1 +0,0 @@
target_stm32f303xc(KISSFC SKIP_RELEASES)

View file

@ -1,33 +0,0 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "fc/config.h"
#include "sensors/boardalignment.h"
void targetConfiguration(void)
{
}

View file

@ -1,44 +0,0 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM15, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM3, CH2, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM4, CH3, PA13, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_PPM, 0),
DEF_TIM(TIM8, CH1, PA15, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,83 +0,0 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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 SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
#define TARGET_BOARD_IDENTIFIER "KISSFC"
#define LED0 PB1
#define BEEPER PB13
#define BEEPER_INVERTED
#define USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW180_DEG
#define MPU6050_I2C_BUS BUS_I2C1
#define USE_EXTI
#define MPU_INT_EXTI PB2
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
//#define USE_SOFTSERIAL1
//#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
//#define SOFTSERIAL1_TX_PIN PA13 // AUX1
//#define SOFTSERIAL2_TX_PIN PA15 // ROLL
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ADC
#define VBAT_SCALE_DEFAULT 160
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
#define CURRENT_METER_ADC_PIN PA2
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define MAX_PWM_OUTPUT_PORTS 12
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))

View file

@ -1 +0,0 @@
target_stm32f303xc(LUX_RACE SKIP_RELEASES)

View file

@ -1,43 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PC6
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PC7
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PMW4 - PC8
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PC9
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR, 0), // PWM6 - PA0
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR, 0), // PWM7 - PA1
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR, 0), // PWM8 - PA2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR, 0), // PWM9 - PA3
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR, 0), // PWM10 - PB14
DEF_TIM(TIM15, CH2, PB15, TIM_USE_MC_MOTOR, 0), // PWM11 - PB15
DEF_TIM(TIM16, CH1, PA6, TIM_USE_LED, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,108 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "LUX"
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define BEEPER PB13
#define BEEPER_INVERTED
// MPU6500 interrupt
#define USE_EXTI
#define GYRO_INT_EXTI PA5
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI1_NSS_PIN PA4
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW270_DEG
#define MPU6500_CS_PIN SPI1_NSS_PIN
#define MPU6500_SPI_BUS BUS_SPI1
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW270_DEG
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define USE_I2C_DEVICE_2
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC2
#define ADC_CHANNEL_4_PIN PC3
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_DMA_STREAM DMA1_Channel3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define USE_SPEKTRUM_BIND
// USART1, PC5
#define BIND_PIN PC5
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// 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))

View file

@ -1 +0,0 @@
target_stm32f303xc(MOTOLAB SKIP_RELEASES)

View file

@ -1,38 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PA4 - *TIM3_CH2
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), // LED - PB8 - *TIM16_CH1, TIM4_CH3, TIM8_CH2
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,123 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab
#define LED0 PB5 // Blue LEDs - PB5
#define LED1 PB9 // Green LEDs - PB9
#define BEEPER PA0
#define BEEPER_INVERTED
// MPU6050 interrupts
#define USE_EXTI
#define GYRO_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#define USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW180_DEG
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG
#define MPU6050_I2C_BUS BUS_I2C2
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI2
//#define USE_BARO
//#define USE_BARO_MS5611
//#define USE_MAG
//#define USE_MAG_HMC5883
//#define USE_MAG_QMC5883
//#define USE_MAG_IST8310
//#define USE_MAG_IST8308
//#define USE_MAG_MAG3110
//#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_SPI
#define USE_SPI_DEVICE_2
#define M25P16_CS_PIN PB12
#define M25P16_SPI_BUS BUS_SPI2
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA5
#define ADC_CHANNEL_2_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PB8 // TIM16_CH1
#define USE_SPEKTRUM_BIND
// USART2, PB4
#define BIND_PIN PB4
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
//#undef USE_GPS
#undef USE_GPS_PROTO_NMEA
//#undef USE_GPS_PROTO_UBLOX
#undef USE_GPS_PROTO_I2C_NAV
#undef USE_GPS_PROTO_NAZA
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 8
// 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))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define BNO055_I2C_BUS BUS_I2C2

View file

@ -1 +0,0 @@
target_stm32f303xc(OMNIBUS SKIP_RELEASES)

View file

@ -1,45 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// PWM1 PPM Pad
DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0), // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
// PWM2-PWM5
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0), // PWM1 - PB8
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PB9
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA3
DEF_TIM(TIM15, CH1, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PA2
// For iNav, PWM6&7 (PWM pins 5&6) are shared with UART3
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PA2
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PA2
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,150 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#undef USE_VTX_SMARTAUDIO // Disabled due to flash size
#define USE_EXTI
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW90_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PA4
#define GYRO_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI1
#define BMP280_CS_PIN PA13
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
// #define USE_MAG_MAG3110
// #define USE_MAG_LIS3MDL
// #define USE_MAG_AK8975
// Disable certain features to save flash space
#undef USE_GPS_PROTO_MTK
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN PB5
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#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)
// Enable I2C instead of PWM7&8 for iNav
#define USE_I2C
#define USE_I2C_DEVICE_1 // PB6/SCL(PWM8), PB7/SDA(PWM7)
#define USE_I2C_PULLUP
#define PITOT_I2C_BUS BUS_I2C1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define RX_SPI_INSTANCE SPI2
#define RX_NSS_PIN PB3
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_BUS BUS_SPI2
#define SDCARD_CS_PIN SPI2_NSS_PIN
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI1
#define MAX7456_CS_PIN PB1
#define USE_ADC
#define ADC_INSTANCE ADC1
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_CHANNEL_1_PIN PA0
#define ADC_CHANNEL_2_PIN PA1
#define ADC_CHANNEL_3_PIN PB2
#define ADC_CHANNEL_3_INSTANCE ADC2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
//#define USE_LED_STRIP
//#define WS2811_PIN PA8
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_OSD)
#define BUTTONS
#define BUTTON_A_PORT GPIOB // Non-existent (PB1 used for RSSI/MAXCS)
#define BUTTON_A_PIN Pin_1
#define BUTTON_B_PORT GPIOB // TRIG button, used for BINDPLUG_PIN
#define BUTTON_B_PIN Pin_0
#define USE_SPEKTRUM_BIND
// USART3
#define BIND_PIN PB11
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PIN PB0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View file

@ -1 +0,0 @@
target_stm32f303xc(PIKOBLX SKIP_RELEASES)

View file

@ -1,38 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0),
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,96 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV Piko BLX
#define CONFIG_FASTLOOP_PREFERRED_ACC IMU_DEFAULT
#define LED0 PB9
#define LED1 PB5
#define BEEPER PA0
#define BEEPER_INVERTED
// MPU6000 interrupts
#define USE_EXTI
#define GYRO_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI2
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_SPI
#define USE_SPI_DEVICE_2
#define SENSORS_SET (SENSOR_ACC)
#define USE_TELEMETRY
#define USE_BLACKBOX
#define USE_SERIAL_RX
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
//#define ADC_CHANNEL_1_PIN PA2 <-- conflict with pwm output 6, and the board does not have current sensor
#define ADC_CHANNEL_2_PIN PA5
//#define ADC_CHANNEL_3_PIN PB2 <-- the board does not have a rssi pad
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
//#define USE_LED_STRIP
//#define WS2811_PIN PB8 // TIM16_CH1
// #define USE_TRANSPONDER
// #define TRANSPONDER_PIN PA8
#define USE_SPEKTRUM_BIND
// USART3, PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
// sn dec06.16 added MAX_PWM_OUTPUT_PORTS: number of available PWM outputs
// porting inav to PIKO BLX by using betaflight target files from before inav changes to timer.h/timer_def.h
// review of target.c shows definitions for PWB1-PWM9. PWM9 is for PPM input
#define MAX_PWM_OUTPUT_PORTS 6

View file

@ -1 +0,0 @@
target_stm32f303xc(RCEXPLORERF3 SKIP_RELEASES)

View file

@ -1,36 +0,0 @@
/*
* 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>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA8
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0), // PWM2 - PA7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB0
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PA4
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PB1
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM, 0), // PWM6 - PPM
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,112 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "REF3"
#define LED0 PB4
#define LED1 PB5
#define BEEPER PA0
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI2
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#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 USE_I2C
#define USE_I2C_DEVICE_2 // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA5
#define ADC_CHANNEL_2_PIN PB2
#define ADC_CHANNEL_3_PIN PA6
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP // LED strip configuration using PWM motor output pin 5.
#define WS2811_PIN PB8 // TIM16_CH1
#define USE_RANGEFINDER
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // USART3,
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View file

@ -1 +0,0 @@
target_stm32f303xc(SPARKY SKIP_RELEASES)

View file

@ -1,44 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// 6 3-pin headers
DEF_TIM(TIM15, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0), // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0), // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0), // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
// PWM7 - PMW10
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM9 - PA4 - *TIM3_CH2
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
// PPM PORT - Also USART2 RX (AF5)
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0), // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,107 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "SPKY" // SParKY
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5
#define BEEPER PA1
#define BEEPER_INVERTED
// MPU6050 interrupts
#define USE_EXTI
#define GYRO_INT_EXTI PA15
#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 USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW270_DEG
#define MPU6050_I2C_BUS BUS_I2C2
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define USE_BARO_BMP280
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#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 UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#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)
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP?
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PA7
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
// LED strip configuration using PWM motor output pin 5.
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PA6 // TIM16_CH1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
// #define USE_RANGEFINDER
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// 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))

View file

@ -1 +0,0 @@
target_stm32f303xc(SPRACINGF3 SKIP_RELEASES)

View file

@ -1,49 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2
DEF_TIM(TIM4, CH1, PA11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3
DEF_TIM(TIM4, CH2, PA12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6
DEF_TIM(TIM15, CH1, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM7
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // GPIO_TIMER / LED_STRIP
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PWM | TIM_USE_PPM, 0), // RC_CH1
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0), // RC_CH2
DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0), // RC_CH3
DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0), // RC_CH4
DEF_TIM(TIM3, CH1, PB4, TIM_USE_PWM | TIM_USE_MC_SERVO, 0), // RC_CH5
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM | TIM_USE_MC_SERVO, 0), // RC_CH6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM | TIM_USE_MC_SERVO, 0), // RC_CH7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM | TIM_USE_MC_SERVO, 0), // RC_CH8
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,118 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "SRF3"
#define LED0 PB3
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC13
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_IMU_MPU6050
#define IMU_MPU6050_ALIGN CW270_DEG
#define MPU6050_I2C_BUS BUS_I2C1
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#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 SOFTSERIAL_1_RX_PIN PB4
#define SOFTSERIAL_1_TX_PIN PB5
#define SOFTSERIAL_2_RX_PIN PB0
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define M25P16_CS_PIN PB12
#define M25P16_SPI_BUS BUS_SPI2
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PA5
#define ADC_CHANNEL_3_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 // UART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 12
// 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))

View file

@ -1,2 +0,0 @@
target_stm32f303xc(SPRACINGF3EVO SKIP_RELEASES)
target_stm32f303xc(SPRACINGF3EVO_1SS SKIP_RELEASES)

View file

@ -1,52 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// PPM / UART2 RX
DEF_TIM(TIM8, CH1, PA15, TIM_USE_PPM, 0), // PPM
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 [TIM2_CH1 (D1_CH5)]
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 [TIM2_CH2 (D1_CH7)] [TIM15_CH1N (D1_CH5)]
DEF_TIM(TIM15, CH1, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 [TIM2_CH3 (D1_CH1)] [TIM15_CH1 (D1_CH5)]
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 [TIM2_CH4 (D1_CH7)]
#ifdef SPRACINGF3EVO_1SS
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6
#else
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM5
DEF_TIM(TIM3, CH2, PA7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM6
#endif
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM8
// UART3 RX/TX
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
// IR / LED Strip Pad
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // LED_STRIP / TRANSPONDER
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,145 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "SPEV"
#define LED0 PB8
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define MPU6500_CS_PIN PB9
#define MPU6500_SPI_BUS BUS_SPI1
#define MPU9250_CS_PIN PB9
#define MPU9250_SPI_BUS BUS_SPI1
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW180_DEG
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW180_DEG
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MPU9250
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#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)
#ifdef SPRACINGF3EVO_1SS
#define SERIAL_PORT_COUNT 5
#define SOFTSERIAL_1_RX_PIN PB0
#define SOFTSERIAL_1_TX_PIN PB1
#else
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 6
#define SOFTSERIAL_1_RX_PIN PA6
#define SOFTSERIAL_1_TX_PIN PA7
#define SOFTSERIAL_2_RX_PIN PB0
#define SOFTSERIAL_2_TX_PIN PB1
#endif
#define USE_I2C
#define USE_I2C_DEVICE_1
#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 SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_BUS BUS_SPI2
#define SDCARD_CS_PIN SPI2_NSS_PIN
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PA5
#define ADC_CHANNEL_3_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER_SRF10
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY)
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 // UART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View file

@ -1 +0,0 @@
target_stm32f303xc(SPRACINGF3MINI SKIP_RELEASES)

View file

@ -1,53 +0,0 @@
/*
* 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/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
// PPM Pad
#ifdef SPRACINGF3MINI_MKII_REVA
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PPM, 0), // PPM - PB5
// PB4 / TIM3 CH1 is connected to USBPresent
#else
DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0), // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
#endif
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PA6
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PA7
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PB8
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB9
DEF_TIM(TIM15, CH1, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM5 - PA2
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM6 - PA3
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM7 - PA0
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM8 - PA1
// UART3 RX/TX
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
// LED Strip Pad
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // LED_STRIP / TRANSPONDER
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -1,155 +0,0 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "SRFM"
// early prototype had slightly different pin mappings.
//#define SPRACINGF3MINI_MKII_REVA
#define LED0 PB3
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define GYRO_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW180_DEG
#define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW180_DEG
#define MPU6500_I2C_BUS BUS_I2C1
#define MPU9250_I2C_BUS BUS_I2C1
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8963
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN PB5
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#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 SOFTSERIAL_1_RX_PIN PA0
#define SOFTSERIAL_1_TX_PIN PA1
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_BUS BUS_SPI2
#define SDCARD_CS_PIN SPI2_NSS_PIN
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_CHANNEL_1_PIN PA4
#define ADC_CHANNEL_2_PIN PA5
#define ADC_CHANNEL_3_PIN PB2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define TRANSPONDER
#define TRANSPONDER_GPIO GPIOA
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define TRANSPONDER_GPIO_AF GPIO_AF_6
#define TRANSPONDER_PIN GPIO_Pin_8
#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8
#define TRANSPONDER_TIMER TIM1
#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define BUTTONS
#define BUTTON_A_PORT GPIOB
#define BUTTON_A_PIN Pin_1
#define BUTTON_B_PORT GPIOB
#define BUTTON_B_PIN Pin_0
#define USE_SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PIN PB0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))