mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
AlienFlight F4 support
This commit is contained in:
parent
3b474954ed
commit
34888ca335
15 changed files with 784 additions and 28 deletions
1
Makefile
1
Makefile
|
@ -496,6 +496,7 @@ COMMON_SRC = \
|
|||
drivers/rx_nrf24l01.c \
|
||||
drivers/rx_spi.c \
|
||||
drivers/rx_xn297.c \
|
||||
drivers/pwm_esc_detect.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rx.c \
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
|
||||
|
||||
AlienWii is now AlienFlight. This designs are released for public and some for non comercial use at:
|
||||
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
|
||||
|
||||
AlienFlightNG (Next Generation) designs are released for non comercial use can be found here:
|
||||
|
||||
http://www.alienflightng.com
|
||||
|
||||
AlienFlight F3 Eagle files are available at:
|
||||
|
||||
https://github.com/MJ666/Flight-Controllers
|
||||
|
||||
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 this designs.
|
||||
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:
|
||||
|
||||
|
@ -37,7 +37,7 @@ Here are the general hardware specifications for this boards:
|
|||
- 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 Lipoly battery for brushed versions
|
||||
- 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)
|
||||
|
@ -45,24 +45,30 @@ Here are the general hardware specifications for this boards:
|
|||
- 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)
|
||||
- (**) 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 receiver (10bit, 22ms) only the bind process will be different.
|
||||
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 ALIENFLIGHTF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENFLIGHTF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). 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 pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). 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 eanbled by default if present on the board.
|
||||
(**) 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
|
||||
|
|
58
src/main/drivers/pwm_esc_detect.c
Normal file
58
src/main/drivers/pwm_esc_detect.c
Normal file
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
* 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 "time.h"
|
||||
#include "system.h"
|
||||
#include "io.h"
|
||||
#include "pwm_esc_detect.h"
|
||||
#include "pwm_mapping.h"
|
||||
#include "timer.h"
|
||||
|
||||
#ifdef BRUSHED_ESC_AUTODETECT
|
||||
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
||||
|
||||
void detectBrushedESC(void)
|
||||
{
|
||||
int i = 0;
|
||||
const uint16_t *setup = multiPPM;
|
||||
while ((!(setup[i] & 0xFF00) >> 8 == MAP_TO_MOTOR_OUTPUT) && i < USABLE_TIMER_CHANNEL_COUNT) {
|
||||
i++;
|
||||
}
|
||||
|
||||
IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
|
||||
IOInit(MotorDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
||||
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
|
||||
// Check presence of brushed ESC's
|
||||
if (IORead(MotorDetectPin)) {
|
||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
||||
} else {
|
||||
hardwareMotorType = MOTOR_BRUSHED;
|
||||
}
|
||||
}
|
||||
#endif
|
29
src/main/drivers/pwm_esc_detect.h
Normal file
29
src/main/drivers/pwm_esc_detect.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
#ifdef BRUSHED_ESC_AUTODETECT
|
||||
typedef enum {
|
||||
MOTOR_UNKNOWN = 0,
|
||||
MOTOR_BRUSHED,
|
||||
MOTOR_BRUSHLESS
|
||||
} HardwareMotorTypes_e;
|
||||
|
||||
extern uint8_t hardwareMotorType;
|
||||
|
||||
void detectBrushedESC(void);
|
||||
#endif
|
|
@ -52,6 +52,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
@ -168,30 +169,34 @@ void init(void)
|
|||
|
||||
printfSupportInit();
|
||||
|
||||
systemInit();
|
||||
|
||||
// initialize IO (needed for all IO operations)
|
||||
IOInitGlobal();
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
detectHardwareRevision();
|
||||
#endif
|
||||
|
||||
#ifdef BRUSHED_ESC_AUTODETECT
|
||||
detectBrushedESC();
|
||||
#endif
|
||||
|
||||
initEEPROM();
|
||||
|
||||
ensureEEPROMContainsValidData();
|
||||
readEEPROM();
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_CONFIG_LOADED, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||
|
||||
debugMode = systemConfig()->debug_mode;
|
||||
|
||||
systemInit();
|
||||
|
||||
i2cSetOverclock(systemConfig()->i2c_overclock);
|
||||
|
||||
// initialize IO (needed for all IO operations)
|
||||
IOInitGlobal();
|
||||
|
||||
#ifdef USE_HARDWARE_PREBOOT_SETUP
|
||||
initialisePreBootHardware();
|
||||
#endif
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
detectHardwareRevision();
|
||||
#endif
|
||||
addBootlogEvent2(BOOT_EVENT_CONFIG_LOADED, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||
|
||||
debugMode = systemConfig()->debug_mode;
|
||||
|
||||
// Latch active features to be used for feature() in the remainder of init().
|
||||
latchActiveFeatures();
|
||||
|
|
74
src/main/target/ALIENFLIGHTF3/AlienFlight.md
Normal file
74
src/main/target/ALIENFLIGHTF3/AlienFlight.md
Normal file
|
@ -0,0 +1,74 @@
|
|||
# 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:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
|
||||
- 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 F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). 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
|
|
@ -15,12 +15,16 @@
|
|||
* 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_output.h"
|
||||
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
|
@ -34,6 +38,12 @@
|
|||
|
||||
#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)
|
||||
{
|
||||
|
@ -41,9 +51,14 @@ void targetConfiguration(void)
|
|||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
batteryConfigMutable()->vbatscale = 20;
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
motorConfigMutable()->minthrottle = 1000;
|
||||
motorConfigMutable()->maxthrottle = 2000;
|
||||
motorConfigMutable()->motorPwmRate = 32000;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||
motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1000;
|
||||
}
|
||||
|
||||
pidProfileMutable()->bank_mc.pid[ROLL].P = 36;
|
||||
pidProfileMutable()->bank_mc.pid[PITCH].P = 36;
|
||||
failsafeConfigMutable()->failsafe_delay = 2;
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
#define HW_PIN PB2
|
||||
#define BRUSHED_ESC_AUTODETECT
|
||||
|
||||
// LED's V1
|
||||
#define LED0 PB4
|
||||
|
@ -80,6 +81,7 @@
|
|||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_PULLUP
|
||||
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||
|
||||
#define I2C2_SCL PA9
|
||||
|
@ -108,7 +110,6 @@
|
|||
#define BINDPLUG_PIN PB12
|
||||
|
||||
|
||||
#define BRUSHED_MOTORS
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
|
@ -118,6 +119,8 @@
|
|||
// 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
|
||||
|
|
74
src/main/target/ALIENFLIGHTF4/AlienFlight.md
Normal file
74
src/main/target/ALIENFLIGHTF4/AlienFlight.md
Normal file
|
@ -0,0 +1,74 @@
|
|||
# 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:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
|
||||
- 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 F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). 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
|
96
src/main/target/ALIENFLIGHTF4/config.c
Normal file
96
src/main/target/ALIENFLIGHTF4/config.c
Normal file
|
@ -0,0 +1,96 @@
|
|||
/*
|
||||
* 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 "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#define CURRENTOFFSET 2500 // ACS712/714-30A - 0A = 2.5V
|
||||
#define CURRENTSCALE -667 // ACS712/714-30A - 66.666 mV/A inverted mode
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
|
||||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
batteryConfigMutable()->currentMeterOffset = CURRENTOFFSET;
|
||||
batteryConfigMutable()->currentMeterScale = CURRENTSCALE;
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||
motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1000;
|
||||
}
|
||||
if (hardwareRevision == AFF4_REV_1) {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048;
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureConfigMutable()->enabledFeatures |= (FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
pidProfileMutable()->bank_mc.pid[ROLL].P = 53;
|
||||
pidProfileMutable()->bank_mc.pid[ROLL].I = 45;
|
||||
pidProfileMutable()->bank_mc.pid[ROLL].D = 52;
|
||||
pidProfileMutable()->bank_mc.pid[PITCH].P = 53;
|
||||
pidProfileMutable()->bank_mc.pid[PITCH].I = 45;
|
||||
pidProfileMutable()->bank_mc.pid[PITCH].D = 52;
|
||||
pidProfileMutable()->bank_mc.pid[YAW].P = 64;
|
||||
pidProfileMutable()->bank_mc.pid[YAW].D = 18;
|
||||
|
||||
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
*customMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
|
||||
*customMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
|
||||
*customMotorMixerMutable(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
|
||||
*customMotorMixerMutable(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
|
||||
*customMotorMixerMutable(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
|
||||
*customMotorMixerMutable(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L
|
||||
}
|
53
src/main/target/ALIENFLIGHTF4/hardware_revision.c
Normal file
53
src/main/target/ALIENFLIGHTF4/hardware_revision.c
Normal file
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* 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/system.h"
|
||||
#include "drivers/io.h"
|
||||
#include "hardware_revision.h"
|
||||
|
||||
uint8_t hardwareRevision = AFF4_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);
|
||||
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
|
||||
// Check hardware revision
|
||||
if (IORead(HWDetectPin)) {
|
||||
hardwareRevision = AFF4_REV_1;
|
||||
} else {
|
||||
hardwareRevision = AFF4_REV_2;
|
||||
}
|
||||
}
|
||||
|
||||
void updateHardwareRevision(void)
|
||||
{
|
||||
}
|
28
src/main/target/ALIENFLIGHTF4/hardware_revision.h
Normal file
28
src/main/target/ALIENFLIGHTF4/hardware_revision.h
Normal file
|
@ -0,0 +1,28 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
typedef enum awf4HardwareRevision_t {
|
||||
AFF4_UNKNOWN = 0,
|
||||
AFF4_REV_1, // MPU6500 / MPU9250 (SPI), (V1.1 Current Sensor (ACS712), SDCard Reader)
|
||||
AFF4_REV_2 // ICM-20602 (SPI), OpenSky RX (CC2510), Current Sensor (ACS712), SDCard Reader
|
||||
} awf4HardwareRevision_e;
|
||||
|
||||
extern uint8_t hardwareRevision;
|
||||
|
||||
void updateHardwareRevision(void);
|
||||
void detectHardwareRevision(void);
|
107
src/main/target/ALIENFLIGHTF4/target.c
Normal file
107
src/main/target/ALIENFLIGHTF4/target.c
Normal file
|
@ -0,0 +1,107 @@
|
|||
/*
|
||||
* 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"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // servo #7
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #9
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM3 }, // PWM2 - PB0 RC2
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM3 }, // PWM3 - PB1 RC3
|
||||
{ TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM1 }, // PWM4 - PA14 RC4
|
||||
{ TIM1, IO_TAG(PB15), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM1 }, // PWM5 - PA15 RC5
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM10 - PC6 OUT5
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM11 - PC7 OUT6
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM13 - PC8 OUT7
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM13 - PC9 OUT8
|
||||
};
|
195
src/main/target/ALIENFLIGHTF4/target.h
Normal file
195
src/main/target/ALIENFLIGHTF4/target.h
Normal file
|
@ -0,0 +1,195 @@
|
|||
/*
|
||||
* 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 "AFF4"
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
#define HW_PIN PC13
|
||||
#define BRUSHED_ESC_AUTODETECT
|
||||
|
||||
#define USBD_PRODUCT_STRING "AlienFlight F4"
|
||||
|
||||
#define LED0 PC12
|
||||
#define LED1 PD2
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_USART2 PC15
|
||||
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC14
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8963
|
||||
|
||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||
#define MAG_AK8963_ALIGN CW270_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_MS56XX
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
//#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PB11
|
||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
|
||||
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10
|
||||
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
|
||||
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB10
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
//#define M25P16_CS_PIN SPI2_NSS_PIN
|
||||
//#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
//#define USE_FLASHFS
|
||||
//#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2 //inverter
|
||||
|
||||
//#define USE_UART3
|
||||
//#define UART3_RX_PIN PB11
|
||||
//#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC11
|
||||
#define UART4_TX_PIN PC10
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PC2
|
||||
#define SPI2_MOSI_PIN PC3
|
||||
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_PULLUP
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
//#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
#define EXTERNAL1_ADC_GPIO_PIN PC5
|
||||
|
||||
// LED strip configuration using RC1 pin.
|
||||
#define LED_STRIP
|
||||
// LED Strip can run off Pin 41 (PA8) of the ESC outputs.
|
||||
#define WS2811_PIN PA8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA2_ST1_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA2_Stream1
|
||||
#define WS2811_DMA_IT DMA_IT_TCIF1
|
||||
#define WS2811_DMA_CHANNEL DMA_Channel_6
|
||||
#define WS2811_TIMER_CHANNEL TIM_Channel_1
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PIN UART2_RX_PIN
|
||||
|
||||
#define HARDWARE_BIND_PLUG
|
||||
// Hardware bind plug at PB2 (Pin 28)
|
||||
#define BINDPLUG_PIN PB2
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_USART1
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// Number of available PWM outputs
|
||||
#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 (BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 13
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )
|
||||
|
12
src/main/target/ALIENFLIGHTF4/target.mk
Normal file
12
src/main/target/ALIENFLIGHTF4/target.mk
Normal file
|
@ -0,0 +1,12 @@
|
|||
F405_TARGETS += $(TARGET)
|
||||
FEATURES += SDCARD VCP
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_ak8963.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
Loading…
Add table
Add a link
Reference in a new issue