Merge pull request #3158 from AlienWiiBF/AcroWhoop
Adding various PikoBLX based FuriousFPV targets
This commit is contained in:
commit
270817a4c8
5
Makefile
5
Makefile
|
@ -128,8 +128,12 @@ GROUP_2_TARGETS := \
|
|||
F4BY \
|
||||
FISHDRONEF4 \
|
||||
FLIP32F3OSD \
|
||||
FF_ACROWHOOPSP \
|
||||
FF_FORTINIF4 \
|
||||
FF_KOMBINI \
|
||||
FF_PIKOBLX \
|
||||
FF_PIKOF4 \
|
||||
FF_RADIANCE \
|
||||
FURYF3 \
|
||||
FURYF4 \
|
||||
FURYF7 \
|
||||
|
@ -152,7 +156,6 @@ GROUP_3_TARGETS := \
|
|||
OMNIBUS \
|
||||
OMNIBUSF4 \
|
||||
OMNIBUSF4SD \
|
||||
PIKOBLX \
|
||||
PLUMF4 \
|
||||
PODIUMF4 \
|
||||
|
||||
|
|
|
@ -0,0 +1,3 @@
|
|||
# ACROWHOOPSP is a variant of PIKOBLX
|
||||
# small brushed FC with Spektrum receiver onboard
|
||||
# designed for inductrix and similar copters
|
|
@ -0,0 +1,3 @@
|
|||
# KOMBINID is a variant of PIKOBLX (DSHOT ready version)
|
||||
# FC with integrated PDB and current sensor
|
||||
# 12V and 5V BEC onboard
|
|
@ -0,0 +1,2 @@
|
|||
# RADIANCED is a variant of PIKOBLX (DSHOT ready version)
|
||||
# similar to Kombini, but without PDB and current sensor
|
|
@ -0,0 +1,85 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1049;
|
||||
|
||||
#if defined(FF_ACROWHOOPSP)
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048;
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
#else
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
featureSet(FEATURE_TELEMETRY);
|
||||
#endif
|
||||
parseRcChannels("TAER1234", rxConfigMutable());
|
||||
|
||||
pidProfilesMutable(0)->pid[PID_ROLL].P = 80;
|
||||
pidProfilesMutable(0)->pid[PID_ROLL].I = 37;
|
||||
pidProfilesMutable(0)->pid[PID_ROLL].D = 35;
|
||||
pidProfilesMutable(0)->pid[PID_PITCH].P = 100;
|
||||
pidProfilesMutable(0)->pid[PID_PITCH].I = 37;
|
||||
pidProfilesMutable(0)->pid[PID_PITCH].D = 35;
|
||||
pidProfilesMutable(0)->pid[PID_YAW].P = 180;
|
||||
pidProfilesMutable(0)->pid[PID_YAW].D = 45;
|
||||
|
||||
controlRateProfilesMutable(0)->rcRate8 = 100;
|
||||
controlRateProfilesMutable(0)->rcYawRate8 = 100;
|
||||
controlRateProfilesMutable(0)->rcExpo8 = 15;
|
||||
controlRateProfilesMutable(0)->rcYawExpo8 = 15;
|
||||
controlRateProfilesMutable(0)->rates[PID_ROLL] = 80;
|
||||
controlRateProfilesMutable(0)->rates[PID_PITCH] = 80;
|
||||
controlRateProfilesMutable(0)->rates[PID_YAW] = 80;
|
||||
}
|
||||
}
|
||||
#endif
|
|
@ -25,15 +25,26 @@
|
|||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
#if defined(FF_RADIANCE) || defined(FF_KOMBINI)
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, 1), // PWM1 - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_PPM, 0), // PPM - PA4
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0),
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8
|
||||
#else
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, 1), // PWM1 - PA4 - *TIM3_CH2
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 1), // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 1), // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0),
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8
|
||||
#endif
|
||||
};
|
||||
|
|
@ -17,10 +17,21 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV Piko BLX
|
||||
#if defined(FF_RADIANCE)
|
||||
#define TARGET_BOARD_IDENTIFIER "RADI" // Furious FPV RADIANCE
|
||||
#elif defined(FF_KOMBINI)
|
||||
#define TARGET_BOARD_IDENTIFIER "KOMB" // Furious FPV KOMBINI
|
||||
#elif defined(FF_ACROWHOOPSP)
|
||||
#define TARGET_BOARD_IDENTIFIER "AWHS" // Furious FPV ACROWHOOP SPEKTRUM
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV PIKOBLX
|
||||
#endif
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define TARGET_CONFIG
|
||||
#define BRUSHED_ESC_AUTODETECT
|
||||
|
||||
#define LED0 PB9
|
||||
#define LED1 PB5
|
||||
|
||||
|
@ -63,45 +74,41 @@
|
|||
#define UART2_TX_PIN PB3
|
||||
#define UART2_RX_PIN PB4
|
||||
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define CURRENT_METER_ADC_PIN PB2
|
||||
#define VBAT_ADC_PIN PA5
|
||||
|
||||
|
||||
#if defined(FF_KOMBINI)
|
||||
#define CURRENT_METER_SCALE_DEFAULT 125
|
||||
#endif
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
|
||||
#if defined(FF_RADIANCE)
|
||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
||||
#else
|
||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
||||
#endif
|
||||
|
||||
#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 SPEKTRUM_BIND_PIN UART3_RX_PIN
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
// #define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
// !!TODO - check the following line is correct
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 9
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(16) | TIM_N(17))
|
Loading…
Reference in New Issue