Merge pull request #862 from martinbudden/bf_microscisky
Added Micro SciSky target
This commit is contained in:
commit
ab9bf9ba3e
|
@ -591,7 +591,11 @@ static void resetConf(void)
|
|||
#endif
|
||||
|
||||
// Radio
|
||||
#ifdef RX_CHANNELS_TAER
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
#else
|
||||
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
||||
#endif
|
||||
|
||||
resetRcControlsConfig(&masterConfig.rcControlsConfig);
|
||||
|
||||
|
|
|
@ -78,7 +78,6 @@ void targetConfiguration(void)
|
|||
masterConfig.motor_pwm_rate = 32000;
|
||||
masterConfig.failsafeConfig.failsafe_delay = 2;
|
||||
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
|
||||
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
|
|
|
@ -78,6 +78,7 @@
|
|||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define HARDWARE_BIND_PLUG
|
||||
// Hardware bind plug at PB5 (Pin 41)
|
||||
|
|
|
@ -92,7 +92,6 @@ void targetConfiguration(void) {
|
|||
currentProfile->pidProfile.P8[PITCH] = 90;
|
||||
currentProfile->pidProfile.I8[PITCH] = 44;
|
||||
currentProfile->pidProfile.D8[PITCH] = 60;
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
|
||||
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
|
|
|
@ -120,6 +120,7 @@
|
|||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -92,7 +92,6 @@ void targetConfiguration(void) {
|
|||
currentProfile->pidProfile.P8[PITCH] = 90;
|
||||
currentProfile->pidProfile.I8[PITCH] = 44;
|
||||
currentProfile->pidProfile.D8[PITCH] = 60;
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
|
||||
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
|
|
|
@ -165,6 +165,7 @@
|
|||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -0,0 +1,106 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
|
||||
};
|
||||
|
|
@ -0,0 +1,100 @@
|
|||
/*
|
||||
* 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 "MSKY" // Micro sciSKY
|
||||
|
||||
#define LED0 PB3
|
||||
#define LED1 PB4
|
||||
|
||||
#define BARO_XCLR_PIN PC13
|
||||
#define BARO_EOC_PIN PC14
|
||||
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
|
||||
#define USE_EXTI
|
||||
#define MAG_INT_EXTI PC14
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
//#define DEBUG_MAG_DATA_READY_INTERRUPT
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
|
||||
// SPI2
|
||||
// PB15 28 SPI2_MOSI
|
||||
// PB14 27 SPI2_MISO
|
||||
// PB13 26 SPI2_SCK
|
||||
// PB12 25 SPI2_NSS
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
#define GYRO_MPU6050_ALIGN CW0_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6050
|
||||
#define ACC_MPU6050_ALIGN CW0_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define SERIAL_PORT_COUNT 2
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
#define LED_STRIP
|
||||
#define WS2811_TIMER TIM3
|
||||
#define WS2811_PIN PA6
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
#define BRUSHED_MOTORS
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM1024
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#undef GPS
|
||||
#undef USE_SERVOS
|
||||
#define USE_QUAD_MIXER_ONLY
|
||||
#define DISPLAY
|
||||
|
||||
|
||||
// IO - assuming all IOs on 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
|
@ -0,0 +1,12 @@
|
|||
F1_TARGETS += $(TARGET)
|
||||
FEATURES = HIGHEND
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_bmp085.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c
|
Loading…
Reference in New Issue