diff --git a/src/main/main.c b/src/main/main.c
index d542c15884..8cebbd6204 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -148,6 +148,15 @@ void init(void)
printfSupportInit();
+ systemInit();
+
+ // initialize IO (needed for all IO operations)
+ IOInitGlobal();
+
+#ifdef USE_HARDWARE_REVISION_DETECTION
+ detectHardwareRevision();
+#endif
+
initEEPROM();
ensureEEPROMContainsValidData();
@@ -155,19 +164,10 @@ void init(void)
systemState |= SYSTEM_STATE_CONFIG_LOADED;
- systemInit();
-
//i2cSetOverclock(masterConfig.i2c_overclock);
- // initialize IO (needed for all IO operations)
- IOInitGlobal();
-
debugMode = masterConfig.debug_mode;
-#ifdef USE_HARDWARE_REVISION_DETECTION
- detectHardwareRevision();
-#endif
-
// Latch active features to be used for feature() in the remainder of init().
latchActiveFeatures();
diff --git a/src/main/target/ALIENFLIGHTF1/AlienFlight.md b/src/main/target/ALIENFLIGHTF1/AlienFlight.md
index cb6e154bdb..cd97560aa7 100644
--- a/src/main/target/ALIENFLIGHTF1/AlienFlight.md
+++ b/src/main/target/ALIENFLIGHTF1/AlienFlight.md
@@ -2,13 +2,18 @@
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
-http://www.alienflight.com
+http://www.alienflightng.com
-All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
+The legacy designs are available at:
+
+https://github.com/MJ666/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.
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:
@@ -32,7 +37,9 @@ Here are the general hardware specifications for this boards:
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
-- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
+- battery monitoring with an LED or buzzer output (for some ALIENFLIGHTF3 and F4 variants only, F4 V2 has also current monitoring)
+- SDCard Reader for balk box monitoring (F4 V2 versions)
+- Integrated OpenSky (FRSky compatible) receiver with FRSky hub telemetry (F4 V2 versions)
(*) 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.
diff --git a/src/main/target/ALIENFLIGHTF1/config.c b/src/main/target/ALIENFLIGHTF1/config.c
index 0b93be5f5b..3f827c995b 100644
--- a/src/main/target/ALIENFLIGHTF1/config.c
+++ b/src/main/target/ALIENFLIGHTF1/config.c
@@ -38,8 +38,6 @@ void targetConfiguration(master_t *config)
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motorConfig.motorPwmRate = 32000;
- config->failsafeConfig.failsafe_delay = 2;
- config->failsafeConfig.failsafe_off_delay = 0;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
diff --git a/src/main/target/ALIENFLIGHTF3/AlienFlight.md b/src/main/target/ALIENFLIGHTF3/AlienFlight.md
index cb6e154bdb..cd97560aa7 100644
--- a/src/main/target/ALIENFLIGHTF3/AlienFlight.md
+++ b/src/main/target/ALIENFLIGHTF3/AlienFlight.md
@@ -2,13 +2,18 @@
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
-http://www.alienflight.com
+http://www.alienflightng.com
-All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
+The legacy designs are available at:
+
+https://github.com/MJ666/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.
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:
@@ -32,7 +37,9 @@ Here are the general hardware specifications for this boards:
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
-- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
+- battery monitoring with an LED or buzzer output (for some ALIENFLIGHTF3 and F4 variants only, F4 V2 has also current monitoring)
+- SDCard Reader for balk box monitoring (F4 V2 versions)
+- Integrated OpenSky (FRSky compatible) receiver with FRSky hub telemetry (F4 V2 versions)
(*) 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.
diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c
index 93a4fafaae..0df64d8533 100644
--- a/src/main/target/ALIENFLIGHTF3/config.c
+++ b/src/main/target/ALIENFLIGHTF3/config.c
@@ -47,8 +47,6 @@ void targetConfiguration(master_t *config)
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motorConfig.motorPwmRate = 32000;
- config->failsafeConfig.failsafe_delay = 2;
- config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 2;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 90;
diff --git a/src/main/target/ALIENFLIGHTF4/AlienFlight.md b/src/main/target/ALIENFLIGHTF4/AlienFlight.md
index cb6e154bdb..cd97560aa7 100644
--- a/src/main/target/ALIENFLIGHTF4/AlienFlight.md
+++ b/src/main/target/ALIENFLIGHTF4/AlienFlight.md
@@ -2,13 +2,18 @@
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
-http://www.alienflight.com
+http://www.alienflightng.com
-All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
+The legacy designs are available at:
+
+https://github.com/MJ666/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.
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:
@@ -32,7 +37,9 @@ Here are the general hardware specifications for this boards:
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
-- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
+- battery monitoring with an LED or buzzer output (for some ALIENFLIGHTF3 and F4 variants only, F4 V2 has also current monitoring)
+- SDCard Reader for balk box monitoring (F4 V2 versions)
+- Integrated OpenSky (FRSky compatible) receiver with FRSky hub telemetry (F4 V2 versions)
(*) 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.
diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c
index ee0165114a..be6e640c5b 100644
--- a/src/main/target/ALIENFLIGHTF4/config.c
+++ b/src/main/target/ALIENFLIGHTF4/config.c
@@ -24,6 +24,7 @@
#include "drivers/sensor.h"
#include "drivers/compass.h"
+#include "drivers/serial.h"
#include "fc/rc_controls.h"
@@ -33,30 +34,49 @@
#include "rx/rx.h"
+#include "io/serial.h"
+
+#include "telemetry/telemetry.h"
+
#include "sensors/sensors.h"
#include "sensors/compass.h"
#include "config/config_profile.h"
#include "config/config_master.h"
+#include "config/feature.h"
+#include "hardware_revision.h"
+
+void intFeatureSet(uint32_t mask, master_t *config);
// alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config)
{
config->mag_hardware = MAG_NONE; // disabled by default
- config->rxConfig.spektrum_sat_bind = 5;
- config->rxConfig.spektrum_sat_bind_autoreset = 1;
+ if (hardwareRevision == AFF4_REV_1) {
+ config->rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048;
+ config->rxConfig.spektrum_sat_bind = 5;
+ config->rxConfig.spektrum_sat_bind_autoreset = 1;
+ } else {
+ config->rxConfig.serialrx_provider = SERIALRX_SBUS;
+ config->rxConfig.sbus_inversion = 0;
+ config->serialConfig.portConfigs[SERIAL_PORT_USART2].functionMask = FUNCTION_TELEMETRY_FRSKY;
+ config->telemetryConfig.telemetry_inversion = 0;
+ intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, config);
+ config->batteryConfig.currentMeterOffset = 2500;
+ config->batteryConfig.currentMeterScale = -667;
+ }
config->motorConfig.motorPwmRate = 32000;
- config->failsafeConfig.failsafe_delay = 2;
- config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 1;
config->pid_process_denom = 1;
- config->profile[0].pidProfile.P8[ROLL] = 90;
- config->profile[0].pidProfile.I8[ROLL] = 44;
- config->profile[0].pidProfile.D8[ROLL] = 60;
- config->profile[0].pidProfile.P8[PITCH] = 90;
- config->profile[0].pidProfile.I8[PITCH] = 44;
- config->profile[0].pidProfile.D8[PITCH] = 60;
+ config->profile[0].pidProfile.P8[ROLL] = 53;
+ config->profile[0].pidProfile.I8[ROLL] = 45;
+ config->profile[0].pidProfile.D8[ROLL] = 52;
+ config->profile[0].pidProfile.P8[PITCH] = 53;
+ config->profile[0].pidProfile.I8[PITCH] = 45;
+ config->profile[0].pidProfile.D8[PITCH] = 52;
+ config->profile[0].pidProfile.P8[YAW] = 64;
+ config->profile[0].pidProfile.D8[YAW] = 18;
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
@@ -65,5 +85,5 @@ void targetConfiguration(master_t *config)
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
- config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
+ config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L
}
diff --git a/src/main/target/ALIENFLIGHTF4/hardware_revision.c b/src/main/target/ALIENFLIGHTF4/hardware_revision.c
new file mode 100644
index 0000000000..bb58b1bcf2
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF4/hardware_revision.c
@@ -0,0 +1,59 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "build/build_config.h"
+
+#include "drivers/system.h"
+#include "drivers/io.h"
+#include "drivers/exti.h"
+#include "hardware_revision.h"
+
+static const char * const hardwareRevisionNames[] = {
+ "Unknown",
+ "AlienFlight V1",
+ "AlienFlight V2"
+};
+
+uint8_t hardwareRevision = UNKNOWN;
+
+static IO_t HWDetectPin = IO_NONE;
+
+void detectHardwareRevision(void)
+{
+ HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
+ IOInit(HWDetectPin, OWNER_SYSTEM, 0);
+ IOConfigGPIO(HWDetectPin, IOCFG_IPU);
+
+ // Check hardware revision
+ delayMicroseconds(10); // allow configuration to settle
+
+ if (IORead(HWDetectPin)) {
+ hardwareRevision = AFF4_REV_1;
+ } else {
+ hardwareRevision = AFF4_REV_2;
+ }
+}
+
+void updateHardwareRevision(void)
+{
+}
diff --git a/src/main/target/ALIENFLIGHTF4/hardware_revision.h b/src/main/target/ALIENFLIGHTF4/hardware_revision.h
new file mode 100644
index 0000000000..dc9c8325c3
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF4/hardware_revision.h
@@ -0,0 +1,30 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+#pragma once
+
+typedef enum awf4HardwareRevision_t {
+ UNKNOWN = 0,
+ AFF4_REV_1,
+ AFF4_REV_2
+} awf4HardwareRevision_e;
+
+extern uint8_t hardwareRevision;
+
+void updateHardwareRevision(void);
+void detectHardwareRevision(void);
+
+struct extiConfig_s;
diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c
index 36d786ff20..9965a4e5c6 100644
--- a/src/main/target/ALIENFLIGHTF4/target.c
+++ b/src/main/target/ALIENFLIGHTF4/target.c
@@ -23,18 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
- { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
- { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
- { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
- { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
- { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
- { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
- { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
- { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
- { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
- { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
- { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
- { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
+ { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
+ { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
+ { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
+ { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
+ { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
+ { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
+ { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
+ { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
+ { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
+ { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
+ { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
+ { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
+ { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
};
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index f9c45d08df..cee01ea6fe 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -19,6 +19,9 @@
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define TARGET_CONFIG
+#define USE_HARDWARE_REVISION_DETECTION
+#define HW_PIN PC13
+
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "AlienFlight F4"
@@ -160,7 +163,6 @@
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define SERIALRX_UART SERIAL_PORT_USART3
#define RX_CHANNELS_TAER