Merge pull request #1644 from AlienWiiBF/AF_fix1

Various AlienFlight updates
This commit is contained in:
Martin Budden 2016-11-23 22:21:17 +01:00 committed by GitHub
commit 99d6fddc11
18 changed files with 242 additions and 71 deletions

View File

@ -20,7 +20,7 @@ Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1) - STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3) - STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4) - STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit - MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware - The MPU sensor interrupt is connected to the MCU for all new F3 and F4 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) - 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) - extra-wide traces on the PCB, for maximum power throughput (brushed variants)

View File

@ -20,6 +20,8 @@
#include <platform.h> #include <platform.h>
#include "drivers/pwm_output.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
@ -31,13 +33,21 @@
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "hardware_revision.h"
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {
config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motorConfig.motorPwmRate = 32000;
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.minthrottle = 1000;
config->motorConfig.motorPwmRate = 32000;
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
config->motorConfig.useUnsyncedPwm = true;
}
config->profile[0].pidProfile.P8[ROLL] = 90; config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44; config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60; config->profile[0].pidProfile.D8[ROLL] = 60;
@ -52,5 +62,5 @@ void targetConfiguration(master_t *config)
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R 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[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[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
} }

View File

@ -0,0 +1,64 @@
/*
* 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/io.h"
#include "drivers/exti.h"
#include "hardware_revision.h"
static const char * const hardwareRevisionNames[] = {
"Unknown",
"AlienFlight F1 V1",
};
uint8_t hardwareRevision = AFF1_REV_1;
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
static IO_t MotorDetectPin = IO_NONE;
void detectHardwareRevision(void)
{
MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
IOInit(MotorDetectPin, OWNER_SYSTEM, 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;
}
}
void updateHardwareRevision(void)
{
}
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
return NULL;
}

View File

@ -0,0 +1,37 @@
/*
* 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 awf1HardwareRevision_t {
AFF1_UNKNOWN = 0,
AFF1_REV_1, // MPU6050 (I2C)
} awf1HardwareRevision_e;
typedef enum awf4HardwareMotorType_t {
MOTOR_UNKNOWN = 0,
MOTOR_BRUSHED,
MOTOR_BRUSHLESS
} awf4HardwareMotorType_e;
extern uint8_t hardwareRevision;
extern uint8_t hardwareMotorType;
void updateHardwareRevision(void);
void detectHardwareRevision(void);
struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View File

@ -20,22 +20,23 @@
#include <platform.h> #include <platform.h>
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/timer.h"
#include "drivers/dma.h" #include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1 DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2 DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3 DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4 DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5 DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM | TIM_USE_LED, TIMER_INPUT_ENABLED ), // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6 DEF_TIM(TIM3, CH2, PA7, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7 DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8 DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1 DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2 DEF_TIM(TIM1, CH4, PA11, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3 DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4 DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5 DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6 DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ) // PWM14 - OUT6
}; };

View File

@ -20,6 +20,9 @@
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1. #define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
#define TARGET_CONFIG #define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define MOTOR_PIN PA8
#define LED0 PB3 #define LED0 PB3
#define LED1 PB4 #define LED1 PB4
@ -70,7 +73,6 @@
// Hardware bind plug at PB5 (Pin 41) // Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PIN PB5 #define BINDPLUG_PIN PB5
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 #define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048

View File

@ -20,7 +20,7 @@ Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1) - STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3) - STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4) - STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit - MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware - The MPU sensor interrupt is connected to the MCU for all new F3 and F4 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) - 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) - extra-wide traces on the PCB, for maximum power throughput (brushed variants)

View File

@ -24,6 +24,7 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/pwm_output.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -39,16 +40,24 @@
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "hardware_revision.h"
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motorConfig.motorPwmRate = 32000;
config->gyro_sync_denom = 2; config->gyro_sync_denom = 2;
config->mag_hardware = MAG_NONE; // disabled by default
config->pid_process_denom = 1; config->pid_process_denom = 1;
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.minthrottle = 1000;
config->motorConfig.motorPwmRate = 32000;
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
config->motorConfig.useUnsyncedPwm = true;
}
config->profile[0].pidProfile.P8[ROLL] = 90; config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44; config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60; config->profile[0].pidProfile.D8[ROLL] = 60;
@ -63,5 +72,5 @@ void targetConfiguration(master_t *config)
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R 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[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[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
} }

View File

@ -30,13 +30,15 @@
static const char * const hardwareRevisionNames[] = { static const char * const hardwareRevisionNames[] = {
"Unknown", "Unknown",
"AlienFlight V1", "AlienFlight F3 V1",
"AlienFlight V2" "AlienFlight F3 V2"
}; };
uint8_t hardwareRevision = UNKNOWN; uint8_t hardwareRevision = AFF3_UNKNOWN;
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
static IO_t HWDetectPin = IO_NONE; static IO_t HWDetectPin = IO_NONE;
static IO_t MotorDetectPin = IO_NONE;
void detectHardwareRevision(void) void detectHardwareRevision(void)
{ {
@ -44,14 +46,25 @@ void detectHardwareRevision(void)
IOInit(HWDetectPin, OWNER_SYSTEM, 0); IOInit(HWDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(HWDetectPin, IOCFG_IPU); IOConfigGPIO(HWDetectPin, IOCFG_IPU);
// Check hardware revision MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
delayMicroseconds(10); // allow configuration to settle delayMicroseconds(10); // allow configuration to settle
// Check hardware revision
if (IORead(HWDetectPin)) { if (IORead(HWDetectPin)) {
hardwareRevision = AFF3_REV_1; hardwareRevision = AFF3_REV_1;
} else { } else {
hardwareRevision = AFF3_REV_2; hardwareRevision = AFF3_REV_2;
} }
// Check presence of brushed ESC's
if (IORead(MotorDetectPin)) {
hardwareMotorType = MOTOR_BRUSHLESS;
} else {
hardwareMotorType = MOTOR_BRUSHED;
}
} }
void updateHardwareRevision(void) void updateHardwareRevision(void)

View File

@ -17,12 +17,19 @@
#pragma once #pragma once
typedef enum awf3HardwareRevision_t { typedef enum awf3HardwareRevision_t {
UNKNOWN = 0, AFF3_UNKNOWN = 0,
AFF3_REV_1, // MPU6050 / MPU9150 (I2C) AFF3_REV_1, // MPU6050 (I2C)
AFF3_REV_2 // MPU6500 / MPU9250 (SPI) AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
} awf3HardwareRevision_e; } awf3HardwareRevision_e;
typedef enum awf4HardwareMotorType_t {
MOTOR_UNKNOWN = 0,
MOTOR_BRUSHED,
MOTOR_BRUSHLESS
} awf4HardwareMotorType_e;
extern uint8_t hardwareRevision; extern uint8_t hardwareRevision;
extern uint8_t hardwareMotorType;
void updateHardwareRevision(void); void updateHardwareRevision(void);
void detectHardwareRevision(void); void detectHardwareRevision(void);

View File

@ -26,16 +26,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// up to 10 Motor Outputs // up to 10 Motor Outputs
DEF_TIM(TIM15, CH2, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 DEF_TIM(TIM15, CH2, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM1 - PB15 - DMA_NONE - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM4 - PB0 - DMA1_CH2 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM5 - PA6 - DMA1_CH6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM6 - PA2 - DMA1_CH1 - *TIM2_CH3, !TIM15_CH1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM7 - PB1 - DMA1_CH3 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM8 - PA7 - DMA1_CH7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
DEF_TIM(TIM3, CH2, PA4, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM9 - PA4 - *TIM3_CH2 DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM9 - PA4 - DMA_NONE - *TIM3_CH2
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, TIMER_INPUT_ENABLED ), // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM10 - PA1 - DMA1_CH7 - *TIM2_CH2, TIM15_CH1N
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED ), // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED ), // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
}; };

View File

@ -24,6 +24,7 @@
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2 #define HW_PIN PB2
#define MOTOR_PIN PB15
// LED's V1 // LED's V1
#define LED0 PB4 #define LED0 PB4
@ -114,7 +115,6 @@
// Hardware bind plug at PB12 (Pin 25) // Hardware bind plug at PB12 (Pin 25)
#define BINDPLUG_PIN PB12 #define BINDPLUG_PIN PB12
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 #define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048

View File

@ -20,7 +20,7 @@ Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1) - STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3) - STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4) - STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit - MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware - The MPU sensor interrupt is connected to the MCU for all new F3 and F4 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) - 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) - extra-wide traces on the PCB, for maximum power throughput (brushed variants)

View File

@ -24,6 +24,7 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/pwm_output.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -50,7 +51,19 @@
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {
config->batteryConfig.currentMeterOffset = 2500;
config->batteryConfig.currentMeterScale = -667;
config->gyro_sync_denom = 1;
config->mag_hardware = MAG_NONE; // disabled by default config->mag_hardware = MAG_NONE; // disabled by default
config->pid_process_denom = 1;
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.minthrottle = 1000;
config->motorConfig.motorPwmRate = 32000;
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
config->motorConfig.useUnsyncedPwm = true;
}
if (hardwareRevision == AFF4_REV_1) { if (hardwareRevision == AFF4_REV_1) {
config->rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048; config->rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048;
config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind = 5;
@ -61,12 +74,8 @@ void targetConfiguration(master_t *config)
config->serialConfig.portConfigs[SERIAL_PORT_USART2].functionMask = FUNCTION_TELEMETRY_FRSKY; config->serialConfig.portConfigs[SERIAL_PORT_USART2].functionMask = FUNCTION_TELEMETRY_FRSKY;
config->telemetryConfig.telemetry_inversion = 0; config->telemetryConfig.telemetry_inversion = 0;
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->enabledFeatures); intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->enabledFeatures);
config->batteryConfig.currentMeterOffset = 2500;
config->batteryConfig.currentMeterScale = -667;
} }
config->motorConfig.motorPwmRate = 32000;
config->gyro_sync_denom = 1;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 53; config->profile[0].pidProfile.P8[ROLL] = 53;
config->profile[0].pidProfile.I8[ROLL] = 45; config->profile[0].pidProfile.I8[ROLL] = 45;
config->profile[0].pidProfile.D8[ROLL] = 52; config->profile[0].pidProfile.D8[ROLL] = 52;

View File

@ -25,18 +25,19 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "hardware_revision.h" #include "hardware_revision.h"
static const char * const hardwareRevisionNames[] = { static const char * const hardwareRevisionNames[] = {
"Unknown", "Unknown",
"AlienFlight V1", "AlienFlight F4 V1",
"AlienFlight V2" "AlienFlight F4 V2"
}; };
uint8_t hardwareRevision = UNKNOWN; uint8_t hardwareRevision = AFF4_UNKNOWN;
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
static IO_t HWDetectPin = IO_NONE; static IO_t HWDetectPin = IO_NONE;
static IO_t MotorDetectPin = IO_NONE;
void detectHardwareRevision(void) void detectHardwareRevision(void)
{ {
@ -44,14 +45,25 @@ void detectHardwareRevision(void)
IOInit(HWDetectPin, OWNER_SYSTEM, 0); IOInit(HWDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(HWDetectPin, IOCFG_IPU); IOConfigGPIO(HWDetectPin, IOCFG_IPU);
// Check hardware revision MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
delayMicroseconds(10); // allow configuration to settle delayMicroseconds(10); // allow configuration to settle
// Check hardware revision
if (IORead(HWDetectPin)) { if (IORead(HWDetectPin)) {
hardwareRevision = AFF4_REV_1; hardwareRevision = AFF4_REV_1;
} else { } else {
hardwareRevision = AFF4_REV_2; hardwareRevision = AFF4_REV_2;
} }
// Check presence of brushed ESC's
if (IORead(MotorDetectPin)) {
hardwareMotorType = MOTOR_BRUSHLESS;
} else {
hardwareMotorType = MOTOR_BRUSHED;
}
} }
void updateHardwareRevision(void) void updateHardwareRevision(void)

View File

@ -17,14 +17,19 @@
#pragma once #pragma once
typedef enum awf4HardwareRevision_t { typedef enum awf4HardwareRevision_t {
UNKNOWN = 0, AFF4_UNKNOWN = 0,
AFF4_REV_1, AFF4_REV_1, // MPU6500 / MPU9250 (SPI), (V1.1 Current Sensor (ACS712), SDCard Reader)
AFF4_REV_2 AFF4_REV_2 // ICM-20602 (SPI), OpenSky RX (CC2510), Current Sensor (ACS712), SDCard Reader
} awf4HardwareRevision_e; } awf4HardwareRevision_e;
typedef enum awf4HardwareMotorType_t {
MOTOR_UNKNOWN = 0,
MOTOR_BRUSHED,
MOTOR_BRUSHLESS
} awf4HardwareMotorType_e;
extern uint8_t hardwareRevision; extern uint8_t hardwareRevision;
extern uint8_t hardwareMotorType;
void updateHardwareRevision(void); void updateHardwareRevision(void);
void detectHardwareRevision(void); void detectHardwareRevision(void);
struct extiConfig_s;

View File

@ -25,17 +25,17 @@
#include "drivers/timer_def.h" #include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PWM1 - PA8 RC1 DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PWM1 - PA8 RC1
DEF_TIM(TIM1, CH2, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 DEF_TIM(TIM1, CH2, PB0, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM2 - PB0 RC2
DEF_TIM(TIM1, CH3, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 DEF_TIM(TIM1, CH3, PB1, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM3 - PB1 RC3
DEF_TIM(TIM8, CH2, PB14, TIM_USE_PWM, 0, 0), // PWM4 - PA14 RC4 DEF_TIM(TIM8, CH2, PB14, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM4 - PA14 RC4
DEF_TIM(TIM8, CH3, PB15, TIM_USE_PWM, 0, 0), // PWM5 - PA15 RC5 DEF_TIM(TIM8, CH3, PB15, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM5 - PA15 RC5
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 1, 0), // PWM6 - PB8 OUT1 DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6 - PB8 OUT1 - DMA1_ST7
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 1, 0), // PWM7 - PB9 OUT2 DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7 - PB9 OUT2 - DMA1_ST3
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0), // PWM8 - PA0 OUT3 DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8 - PA0 OUT3 - DMA1_ST2
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 1, 0), // PWM9 - PA1 OUT4 DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM9 - PA1 OUT4 - DMA1_ST4
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, 1, 0), // PWM10 - PC6 OUT5 DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM10 - PC6 OUT5 - (DMA1_ST4)
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 1, 0), // PWM11 - PC7 OUT6 DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM11 - PC7 OUT6 - DMA1_ST5
DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, 1, 0), // PWM13 - PC8 OUT7 DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM13 - PC8 OUT7 - (DMA1_ST7)
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, 1, 0), // PWM13 - PC9 OUT8 DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM13 - PC9 OUT8 - (DMA1_ST2)
}; };

View File

@ -21,6 +21,7 @@
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13 #define HW_PIN PC13
#define MOTOR_PIN PB8
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
@ -82,10 +83,12 @@
// Divide to under 25MHz for normal operation: // Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
//#ifndef USE_DSHOT
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 #define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0 #define SDCARD_DMA_CHANNEL DMA_Channel_0
//#endif
// Performance logging for SD card operations: // Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING // #define AFATFS_USE_INTROSPECTIVE_LOGGING
@ -160,7 +163,6 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) #define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_UART SERIAL_PORT_USART2 #define SERIALRX_UART SERIAL_PORT_USART2