Merge pull request #7 from borisbstyle/betaflight
pull latest betaflight to 4way-interface
This commit is contained in:
commit
e681f9db3e
31
Makefile
31
Makefile
|
@ -42,7 +42,7 @@ FORKNAME = betaflight
|
|||
|
||||
CC3D_TARGETS = CC3D CC3D_OPBL
|
||||
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO
|
||||
|
||||
# Valid targets for OP VCP support
|
||||
VCP_VALID_TARGETS = $(CC3D_TARGETS)
|
||||
|
@ -52,9 +52,9 @@ OPBL_VALID_TARGETS = CC3D_OPBL
|
|||
|
||||
64K_TARGETS = CJMCU
|
||||
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO
|
||||
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO
|
||||
|
||||
|
||||
# Configure default flash sizes for the targets
|
||||
|
@ -356,7 +356,8 @@ VCP_SRC = \
|
|||
vcp/usb_istr.c \
|
||||
vcp/usb_prop.c \
|
||||
vcp/usb_pwr.c \
|
||||
drivers/serial_usb_vcp.c
|
||||
drivers/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
||||
drivers/accgyro_adxl345.c \
|
||||
|
@ -709,6 +710,28 @@ IRCFUSIONF3_SRC = \
|
|||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
SPRACINGF3EVO_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/display_ug2864hsweg01.h \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
drivers/sdcard.c \
|
||||
drivers/sdcard_standard.c \
|
||||
drivers/transponder_ir.c \
|
||||
drivers/transponder_ir_stm32f30x.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
io/asyncfatfs/fat_standard.c \
|
||||
io/transponder_ir.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
MOTOLAB_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu.c \
|
||||
|
|
|
@ -6,6 +6,7 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=COLIBRI_RACE" \
|
||||
"TARGET=LUX_RACE" \
|
||||
"TARGET=SPRACINGF3" \
|
||||
"TARGET=SPRACINGF3EVO" \
|
||||
"TARGET=SPRACINGF3MINI" \
|
||||
"TARGET=NAZE" \
|
||||
"TARGET=AFROMINI" \
|
||||
|
|
|
@ -479,6 +479,67 @@ static const uint16_t airPWM[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t multiPWM[] = {
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB)
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -159,7 +159,7 @@ static void pwmWriteOneshot42(uint8_t index, uint16_t value)
|
|||
|
||||
static void pwmWriteMultiShot(uint8_t index, uint16_t value)
|
||||
{
|
||||
*motors[index]->ccr = (uint16_t)((float)(value-1000) / 4.1666f)+ 60;
|
||||
*motors[index]->ccr = 60001 * (value - 1000) / 250000 + 60;
|
||||
}
|
||||
|
||||
void pwmWriteMotor(uint8_t index, uint16_t value)
|
||||
|
|
|
@ -278,6 +278,36 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3EVO)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// PPM / UART2 RX
|
||||
{ TIM8, GPIOA, Pin_15, TIM_Channel_1, TIM8_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_2}, // PPM
|
||||
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // PWM1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM2
|
||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM3
|
||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM4
|
||||
{ TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5
|
||||
{ TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM6
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM7
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM8
|
||||
|
||||
// UART3 RX/TX
|
||||
{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
|
||||
// IR / LED Strip Pad
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2
|
||||
|
|
|
@ -138,6 +138,11 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
|
||||
float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float
|
||||
|
||||
// Scaling factors for Pids to match rewrite and use same defaults
|
||||
static const float luxPTermScale = 1.0f / 128;
|
||||
static const float luxITermScale = 1000000.0f / 0x1000000;
|
||||
static const float luxDTermScale = (0.000001f * (float)0xFFFF) / 256;
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// Figure out the raw stick positions
|
||||
const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, rxConfig->midrc));
|
||||
|
@ -145,10 +150,10 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
|
||||
// Progressively turn off the horizon self level strength as the stick is banged over
|
||||
horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
|
||||
if(pidProfile->H_sensitivity == 0){
|
||||
if(pidProfile->D8[PIDLEVEL] == 0){
|
||||
horizonLevelStrength = 0;
|
||||
} else {
|
||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->H_sensitivity)) + 1, 0, 1);
|
||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -158,31 +163,31 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
|
||||
if (axis == FD_YAW) {
|
||||
// YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate
|
||||
AngleRate = (float)((rate + 10) * rcCommand[YAW]) / 50.0f;
|
||||
AngleRate = (float)((rate + 47) * rcCommand[YAW]) / 32.0f;
|
||||
} else {
|
||||
// ACRO mode, control is GYRO based, direct sticks control is applied to rate PID
|
||||
AngleRate = (float)((rate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max roll/pitch rate
|
||||
AngleRate = (float)((rate + 27) * rcCommand[axis]) / 16.0f; // 200dps to 1200dps max roll/pitch rate
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// calculate error angle and limit the angle to the max inclination
|
||||
#ifdef GPS
|
||||
const float errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here
|
||||
#else
|
||||
const float errorAngle = (constrain(rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
const float errorAngle = (constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here
|
||||
#endif
|
||||
if (FLIGHT_MODE(ANGLE_MODE)) {
|
||||
// ANGLE mode - control is angle based, so control loop is needed
|
||||
AngleRate = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
|
||||
AngleRate = errorAngle * pidProfile->P8[PIDLEVEL] / 16.0f;
|
||||
} else {
|
||||
// HORIZON mode - direct sticks control is applied to rate PID
|
||||
// mix up angle error to desired AngleRate to add a little auto-level feel
|
||||
AngleRate += errorAngle * pidProfile->I8[PIDLEVEL] / 10.0f * horizonLevelStrength;
|
||||
AngleRate += errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 16.0f;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
|
||||
gyroRate = gyroADC[axis] / 4.0f; // gyro output scaled to rewrite scale
|
||||
|
||||
// --------low-level gyro-based PID. ----------
|
||||
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
|
||||
|
@ -192,9 +197,9 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
|
||||
// -----calculate P component
|
||||
if (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) {
|
||||
PTerm = (pidProfile->P8[axis] / 40.0f * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig));
|
||||
PTerm = (luxPTermScale * pidProfile->P8[axis] * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig));
|
||||
} else {
|
||||
PTerm = RateError * (pidProfile->P8[axis] / 40.0f) * tpaFactor;
|
||||
PTerm = luxPTermScale * RateError * pidProfile->P8[axis] * tpaFactor;
|
||||
}
|
||||
|
||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||
|
@ -203,7 +208,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
|
||||
// -----calculate I component.
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * getdT() * pidProfile->I8[axis] / 10.0f, -250.0f, 250.0f);
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f);
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) {
|
||||
if (ABS(gyroRate) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = 0;
|
||||
|
@ -246,7 +251,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
// Apply moving average
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAveragef(delta, pidProfile->dterm_average_count, deltaState[axis]);
|
||||
|
||||
DTerm = constrainf(delta * (float)pidProfile->D8[axis] * 0.001f * tpaFactor, -300.0f, 300.0f);
|
||||
DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f);
|
||||
}
|
||||
|
||||
// -----calculate total PID output
|
||||
|
|
|
@ -113,10 +113,13 @@ bool areSticksInApModePosition(uint16_t ap_mode)
|
|||
|
||||
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
{
|
||||
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
|
||||
return THROTTLE_LOW;
|
||||
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig->mincheck))
|
||||
return THROTTLE_LOW;
|
||||
if (feature(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) {
|
||||
if ((rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
|
||||
return THROTTLE_LOW;
|
||||
} else {
|
||||
if (rcData[THROTTLE] < rxConfig->mincheck)
|
||||
return THROTTLE_LOW;
|
||||
}
|
||||
|
||||
return THROTTLE_HIGH;
|
||||
}
|
||||
|
|
|
@ -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/>.
|
||||
*
|
||||
* Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
|
||||
* by Nathan Tsoi <nathan@vertile.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
|
||||
extern uint8_t escCount;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* gpio;
|
||||
uint16_t pinpos;
|
||||
uint16_t pin;
|
||||
} escHardware_t;
|
||||
|
||||
|
||||
void usb1WireInitialize();
|
||||
void usb1WirePassthrough(uint8_t escIndex);
|
||||
void usb1WireDeInitialize(void);
|
||||
#endif
|
|
@ -0,0 +1,36 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*
|
||||
* Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
|
||||
* by Nathan Tsoi <nathan@vertile.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
|
||||
extern uint8_t escCount;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* gpio;
|
||||
uint16_t pinpos;
|
||||
uint16_t pin;
|
||||
} escHardware_t;
|
||||
|
||||
|
||||
void usb1WireInitialize();
|
||||
void usb1WirePassthrough(uint8_t escIndex);
|
||||
#endif
|
|
@ -193,7 +193,7 @@ static const char * const featureNames[] = {
|
|||
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", NULL
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", NULL
|
||||
};
|
||||
|
||||
// sync this with rxFailsafeChannelMode_e
|
||||
|
|
|
@ -131,7 +131,7 @@ void setGyroSamplingSpeed(uint16_t looptime) {
|
|||
masterConfig.mag_hardware = 1;
|
||||
masterConfig.pid_process_denom = 2;
|
||||
} else if (looptime < 375) {
|
||||
#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3)
|
||||
#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO)
|
||||
masterConfig.acc_hardware = 0;
|
||||
#else
|
||||
masterConfig.acc_hardware = 1;
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void transponderInit(uint8_t* transponderCode);
|
||||
|
||||
void transponderEnable(void);
|
||||
void transponderDisable(void);
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
@ -52,9 +53,9 @@
|
|||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/usb_io.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/sdcard.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -130,8 +131,6 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);
|
|||
void spektrumBind(rxConfig_t *rxConfig);
|
||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
|
||||
void sonarInit(const sonarHardware_t *sonarHardware);
|
||||
void transponderInit(uint8_t* transponderCode);
|
||||
//void usbCableDetectInit(void);
|
||||
|
||||
#ifdef STM32F303xC
|
||||
// from system_stm32f30x.c
|
||||
|
@ -256,6 +255,8 @@ void init(void)
|
|||
|
||||
timerInit(); // timer must be initialized before any channel is allocated
|
||||
|
||||
dmaInit();
|
||||
|
||||
serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL));
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
@ -534,12 +535,10 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
/* TODO - Fix in the future
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
usbCableDetectInit();
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
if (feature(FEATURE_TRANSPONDER)) {
|
||||
transponderInit(masterConfig.transponderData);
|
||||
|
@ -548,7 +547,6 @@ void init(void)
|
|||
systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
#ifdef NAZE
|
||||
|
|
|
@ -117,6 +117,7 @@ extern bool antiWindupProtection;
|
|||
|
||||
uint16_t filteredCycleTime;
|
||||
static bool isRXDataNew;
|
||||
static bool armingCalibrationWasInitialised;
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
|
@ -312,7 +313,7 @@ void annexCode(void)
|
|||
if (ARMING_FLAG(ARMED)) {
|
||||
LED0_ON;
|
||||
} else {
|
||||
if (IS_RC_MODE_ACTIVE(BOXARM) == 0) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXARM) == 0 || armingCalibrationWasInitialised) {
|
||||
ENABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
|
@ -341,6 +342,8 @@ void annexCode(void)
|
|||
|
||||
void mwDisarm(void)
|
||||
{
|
||||
armingCalibrationWasInitialised = false;
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
DISABLE_ARMING_FLAG(ARMED);
|
||||
|
||||
|
@ -366,11 +369,12 @@ void releaseSharedTelemetryPorts(void) {
|
|||
|
||||
void mwArm(void)
|
||||
{
|
||||
static bool armingCalibrationWasInitialisedOnce;
|
||||
static bool firstArmingCalibrationWasCompleted;
|
||||
|
||||
if (masterConfig.gyro_cal_on_first_arm && !armingCalibrationWasInitialisedOnce) {
|
||||
if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
|
||||
gyroSetCalibrationCycles(calculateCalibratingCycles());
|
||||
armingCalibrationWasInitialisedOnce = true;
|
||||
armingCalibrationWasInitialised = true;
|
||||
firstArmingCalibrationWasCompleted = true;
|
||||
}
|
||||
|
||||
if (!isGyroCalibrationComplete()) return; // prevent arming before gyro is calibrated
|
||||
|
|
|
@ -13,13 +13,19 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*
|
||||
* Driver for IBUS (Flysky) receiver
|
||||
* - initial implementation for MultiWii by Cesco/Plüschi
|
||||
* - implementation for BaseFlight by Andreas (fiendie) Tacke
|
||||
* - ported to CleanFlight by Konstantin (digitalentity) Sharlaimov
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
|
@ -32,9 +38,7 @@
|
|||
#include "rx/rx.h"
|
||||
#include "rx/ibus.h"
|
||||
|
||||
// Driver for IBUS (Flysky) receiver
|
||||
|
||||
#define IBUS_MAX_CHANNEL 8
|
||||
#define IBUS_MAX_CHANNEL 10
|
||||
#define IBUS_BUFFSIZE 32
|
||||
#define IBUS_SYNCBYTE 0x20
|
||||
|
||||
|
@ -95,7 +99,7 @@ static void ibusDataReceive(uint16_t c)
|
|||
|
||||
uint8_t ibusFrameStatus(void)
|
||||
{
|
||||
uint8_t i;
|
||||
uint8_t i, offset;
|
||||
uint8_t frameStatus = SERIAL_RX_FRAME_PENDING;
|
||||
uint16_t chksum, rxsum;
|
||||
|
||||
|
@ -112,15 +116,9 @@ uint8_t ibusFrameStatus(void)
|
|||
rxsum = ibus[30] + (ibus[31] << 8);
|
||||
|
||||
if (chksum == rxsum) {
|
||||
ibusChannelData[0] = (ibus[ 3] << 8) + ibus[ 2];
|
||||
ibusChannelData[1] = (ibus[ 5] << 8) + ibus[ 4];
|
||||
ibusChannelData[2] = (ibus[ 7] << 8) + ibus[ 6];
|
||||
ibusChannelData[3] = (ibus[ 9] << 8) + ibus[ 8];
|
||||
ibusChannelData[4] = (ibus[11] << 8) + ibus[10];
|
||||
ibusChannelData[5] = (ibus[13] << 8) + ibus[12];
|
||||
ibusChannelData[6] = (ibus[15] << 8) + ibus[14];
|
||||
ibusChannelData[7] = (ibus[17] << 8) + ibus[16];
|
||||
|
||||
for (i = 0, offset = 2; i < IBUS_MAX_CHANNEL; i++, offset += 2) {
|
||||
ibusChannelData[i] = ibus[offset] + (ibus[offset + 1] << 8);
|
||||
}
|
||||
frameStatus = SERIAL_RX_FRAME_COMPLETE;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,3 +18,4 @@
|
|||
#pragma once
|
||||
|
||||
uint8_t ibusFrameStatus(void);
|
||||
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
|
|
|
@ -117,7 +117,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3) || defined(SPRACINGF3MINI)
|
||||
#if defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(SPRACINGF3EVO)
|
||||
static const extiConfig_t spRacingF3MPUIntExtiConfig = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
||||
.gpioPort = GPIOC,
|
||||
|
|
|
@ -0,0 +1,371 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F30x devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f30x.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
* Supported STM32F30x device
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*----------------------------------------------------------------------------
|
||||
* PLLMUL | 9
|
||||
*-----------------------------------------------------------------------------
|
||||
* PREDIV | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* USB Clock | ENABLE
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "stm32f30x.h"
|
||||
|
||||
uint32_t hse_value = HSE_VALUE;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 72000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR &= 0xF87FC00C;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||
|
||||
/* Reset PREDIV1[3:0] bits */
|
||||
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||
|
||||
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
//SetSysClock(); // called from main()
|
||||
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock */
|
||||
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||
}
|
||||
break;
|
||||
default: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK clock frequency ----------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK clock frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in SystemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
|
||||
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer and set Flash Latency */
|
||||
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 2 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
#ifndef __SYSTEM_STM32F30X_H
|
||||
#define __SYSTEM_STM32F30X_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__SYSTEM_STM32F30X_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,239 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "SPEV"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_8
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
|
||||
|
||||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
|
||||
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
|
||||
|
||||
#define GYRO
|
||||
//#define USE_FAKE_GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
|
||||
#define ACC
|
||||
//#define USE_FAKE_ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
#define MAG
|
||||
#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
#define USE_MAG_AK8963
|
||||
//#define USE_MAG_HMC5883 // External
|
||||
|
||||
#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||
|
||||
//#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#endif
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#endif
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
|
||||
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard)
|
||||
|
||||
#define SPI1_GPIO GPIOB
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_NSS_PIN Pin_9
|
||||
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource9
|
||||
#define SPI1_SCK_PIN Pin_3
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
|
||||
#define SPI1_MISO_PIN Pin_4
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
|
||||
#define SPI1_MOSI_PIN Pin_5
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||
|
||||
#define SPI2_GPIO GPIOB
|
||||
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI2_NSS_PIN Pin_12
|
||||
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
|
||||
#define SPI2_SCK_PIN Pin_13
|
||||
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
|
||||
#define SPI2_MISO_PIN Pin_14
|
||||
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
|
||||
#define SPI2_MOSI_PIN Pin_15
|
||||
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI2
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN GPIO_Pin_14
|
||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
|
||||
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
|
||||
#define SDCARD_DETECT_GPIO_PORT GPIOC
|
||||
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
|
||||
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
|
||||
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL SPI1_GPIO_PERIPHERAL
|
||||
#define MPU6500_CS_GPIO SPI1_GPIO
|
||||
#define MPU6500_CS_PIN GPIO_Pin_9
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_6
|
||||
#define WS2811_PIN GPIO_Pin_8
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define TRANSPONDER
|
||||
#define TRANSPONDER_GPIO GPIOA
|
||||
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define TRANSPONDER_GPIO_AF GPIO_AF_6
|
||||
#define TRANSPONDER_PIN GPIO_Pin_8
|
||||
#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8
|
||||
#define TRANSPONDER_TIMER TIM1
|
||||
#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
|
||||
#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
|
||||
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define DISPLAY
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
||||
#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
|
||||
#ifdef USE_VCP
|
||||
#define USE_SERIAL_1WIRE_VCP
|
||||
#else
|
||||
#define USE_SERIAL_1WIRE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define S1W_TX_GPIO UART1_GPIO
|
||||
#define S1W_TX_PIN UART1_TX_PIN
|
||||
#define S1W_RX_GPIO UART1_GPIO
|
||||
#define S1W_RX_PIN UART1_RX_PIN
|
|
@ -83,7 +83,7 @@ enum
|
|||
// remaining 3 bits are crc (according to comments in openTx code)
|
||||
};
|
||||
|
||||
// these data identifiers are obtained from http://diydrones.com/forum/topics/amp-to-frsky-x8r-sport-converter
|
||||
// these data identifiers are obtained from https://github.com/opentx/opentx/blob/master/radio/src/telemetry/frsky.h
|
||||
enum
|
||||
{
|
||||
FSSP_DATAID_SPEED = 0x0830 ,
|
||||
|
@ -106,6 +106,8 @@ enum
|
|||
FSSP_DATAID_T1 = 0x0400 ,
|
||||
FSSP_DATAID_T2 = 0x0410 ,
|
||||
FSSP_DATAID_GPS_ALT = 0x0820 ,
|
||||
FSSP_DATAID_A3 = 0x0900 ,
|
||||
FSSP_DATAID_A4 = 0x0910 ,
|
||||
};
|
||||
|
||||
const uint16_t frSkyDataIdTable[] = {
|
||||
|
@ -130,6 +132,7 @@ const uint16_t frSkyDataIdTable[] = {
|
|||
FSSP_DATAID_T1 ,
|
||||
FSSP_DATAID_T2 ,
|
||||
FSSP_DATAID_GPS_ALT ,
|
||||
FSSP_DATAID_A4 ,
|
||||
0
|
||||
};
|
||||
|
||||
|
@ -471,6 +474,12 @@ void handleSmartPortTelemetry(void)
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
case FSSP_DATAID_A4 :
|
||||
if (feature(FEATURE_VBAT)) {
|
||||
smartPortSendPackage(id, vbat * 10 / batteryCellCount ); // given in 0.1V, convert to volts
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
// if nothing is sent, smartPortHasRequest isn't cleared, we already incremented the counter, just loop back to the start
|
||||
|
|
|
@ -2,6 +2,7 @@ ALL_TARGETS := naze
|
|||
ALL_TARGETS += cc3d
|
||||
ALL_TARGETS += cc3d_opbl
|
||||
ALL_TARGETS += spracingf3
|
||||
ALL_TARGETS += spracingf3evo
|
||||
ALL_TARGETS += spracingf3mini
|
||||
ALL_TARGETS += sparky
|
||||
ALL_TARGETS += alienflightf1
|
||||
|
@ -20,6 +21,7 @@ clean_cc3d cc3d: opts := TARGET=CC3D
|
|||
clean_cc3d_opbl cc3d_opbl : opts := TARGET=CC3D_OPBL
|
||||
clean_spracingf3mini spracingf3mini : opts := TARGET=SPRACINGF3MINI
|
||||
clean_spracingf3 spracingf3 : opts := TARGET=SPRACINGF3
|
||||
clean_spracingf3 spracingf3evo : opts := TARGET=SPRACINGF3EVO
|
||||
clean_sparky sparky : opts := TARGET=SPARKY
|
||||
clean_alienflightf1 alienflightf1 : opts := TARGET=ALIENFLIGHTF1
|
||||
clean_alienflightf3 alienflightf3 : opts := TARGET=ALIENFLIGHTF3
|
||||
|
|
Loading…
Reference in New Issue