From 5f435f7aadd3937429776297604a84fa7315b694 Mon Sep 17 00:00:00 2001 From: fishpepper Date: Mon, 7 Nov 2016 22:01:25 +0100 Subject: [PATCH] adding tinyfish fc --- src/main/target/TINYFISH/config.c | 56 +++++++++++++ src/main/target/TINYFISH/target.c | 35 ++++++++ src/main/target/TINYFISH/target.h | 123 +++++++++++++++++++++++++++++ src/main/target/TINYFISH/target.mk | 7 ++ 4 files changed, 221 insertions(+) create mode 100644 src/main/target/TINYFISH/config.c create mode 100644 src/main/target/TINYFISH/target.c create mode 100644 src/main/target/TINYFISH/target.h create mode 100644 src/main/target/TINYFISH/target.mk diff --git a/src/main/target/TINYFISH/config.c b/src/main/target/TINYFISH/config.c new file mode 100644 index 0000000000..2812a1d7a4 --- /dev/null +++ b/src/main/target/TINYFISH/config.c @@ -0,0 +1,56 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include +#include "drivers/io.h" + +#include "drivers/timer.h" +#include "drivers/dma.h" + +#include "config/config_profile.h" +#include "config/config_master.h" +#include "config/feature.h" + +#include "io/serial.h" + +#include "target.h" + +#define TARGET_CPU_VOLTAGE 3.0 + +// set default settings to match our target +void targetConfiguration(master_t *config) +{ + config->batteryConfig.currentMeterOffset = 0; + // we use an ina139, RL=0.005, Rs=30000 + // V/A = (0.005 * 0.001 * 30000) * I + // rescale to 1/10th mV / A -> * 1000 * 10 + // we use 3.0V as cpu and adc voltage -> rescale by 3.0/3.3 + config->batteryConfig.currentMeterScale = (0.005 * 0.001 * 30000) * 1000 * 10 * (TARGET_CPU_VOLTAGE / 3.3); + + // we use the same uart for frsky telemetry and SBUS, both non inverted + int index = findSerialPortIndexByIdentifier(SBUS_TELEMETRY_UART); + config->serialConfig.portConfigs[index].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; + + config->rxConfig.serialrx_provider = SERIALRX_SBUS; + config->telemetryConfig.telemetry_inversion = 0; + config->rxConfig.sbus_inversion = 0; + + intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->enabledFeatures); +} + diff --git a/src/main/target/TINYFISH/target.c b/src/main/target/TINYFISH/target.c new file mode 100644 index 0000000000..8f16d10536 --- /dev/null +++ b/src/main/target/TINYFISH/target.c @@ -0,0 +1,35 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include +#include "drivers/io.h" + +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH5 + DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA2_CH1 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH7 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH1 + + DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, TIMER_OUTPUT_ENABLED) //DMA1_CH2 - LED +}; + diff --git a/src/main/target/TINYFISH/target.h b/src/main/target/TINYFISH/target.h new file mode 100644 index 0000000000..86b41936a9 --- /dev/null +++ b/src/main/target/TINYFISH/target.h @@ -0,0 +1,123 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define USB_VCP_ENABLED 1 + +#define TARGET_BOARD_IDENTIFIER "TFSH" // http://fishpepper.de/projects/tinyFISH + + +#define LED0 PC14 +#define LED1 PC15 + +#define BEEPER PB2 + +#define USE_EXTI +#define MPU_INT_EXTI PC13 +#define USE_MPU_DATA_READY_SIGNAL +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT + +#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP + +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG_FLIP + + +#if USB_VCP_ENABLED + #define USE_VCP + #define USB_IO + #define USBD_PRODUCT_STRING "tinyFISH" + #define SERIAL_PORT_COUNT 4 +#else + #define SERIAL_PORT_COUNT 3 +#endif + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 + +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define SBUS_TELEMETRY_UART SERIAL_PORT_USART2 + +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI +#define USE_SPI_DEVICE_2 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define M25P16_CS_PIN SPI2_NSS_PIN +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define VBAT_ADC_PIN PB1 +#define CURRENT_METER_ADC_PIN PB0 +#define ADC_INSTANCE ADC3 +#define VBAT_SCALE_DEFAULT 100 + +#define LED_STRIP +#define WS2811_PIN PA8 +#define WS2811_TIMER 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 USE_DSHOT + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_TELEMETRY) +#define TARGET_CONFIG + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#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)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 5 +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(8)) diff --git a/src/main/target/TINYFISH/target.mk b/src/main/target/TINYFISH/target.mk new file mode 100644 index 0000000000..ee1225563f --- /dev/null +++ b/src/main/target/TINYFISH/target.mk @@ -0,0 +1,7 @@ +F3_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/flash_m25p16.c \ + drivers/accgyro_spi_mpu6000.c