1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 11:29:56 +03:00

EUSTM32F103RC removed

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-04-24 08:54:10 +02:00
parent 7e49887490
commit 80f7d57a87
5 changed files with 3 additions and 188 deletions

View file

@ -2,7 +2,7 @@
Spektrum bind with hardware bind plug support. Spektrum bind with hardware bind plug support.
The Spektrum bind code is actually enabled for the CJMCU, EUSTM32F103RC, SPARKY, ALIENWIIF1, ALIENWIIF3 targets. The Spektrum bind code is actually enabled for the SPARKY, ALIENWIIF1, ALIENWIIF3 targets.
## Configure the bind code ## Configure the bind code
@ -24,7 +24,7 @@ The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during bu
## Function ## Function
The bind code will actually work for EUSTM32F103RC, SPARKY targets (USART2). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values. The bind code will actually work for SPARKY targets (USART2). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying. If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
@ -46,7 +46,7 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### Supported Hardware ### Supported Hardware
SPARKY, EUSTM32F103RC and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug SPARKY and ALIENWIIF3 targets with hardware bind plug
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller ### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller

View file

@ -4,7 +4,6 @@ targets=("PUBLISHMETA=True" \
"RUNTESTS=True" \ "RUNTESTS=True" \
"TARGET=CHEBUZZF3" \ "TARGET=CHEBUZZF3" \
"TARGET=COLIBRI_RACE" \ "TARGET=COLIBRI_RACE" \
"TARGET=EUSTM32F103RC" \
"TARGET=SPRACINGF3" \ "TARGET=SPRACINGF3" \
"TARGET=SPRACINGF3EVO" \ "TARGET=SPRACINGF3EVO" \
"TARGET=LUX_RACE" \ "TARGET=LUX_RACE" \

View file

@ -1,41 +0,0 @@
/*
* 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"
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
};

View file

@ -1,116 +0,0 @@
/*
* 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 "EUF1"
#define LED0 PB3
#define LED1 PB4
#define INVERTER_PIN_UART2 PB2
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
#define MPU6500_CS_PIN PB12
#define MPU6500_SPI_INSTANCE SPI2
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_L3G4200D
//#define USE_GYRO_L3GD20
//#define USE_GYRO_MPU3050
#define USE_GYRO_MPU6050
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6050_ALIGN CW0_DEG
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_ADXL345
//#define USE_ACC_BMA280
//#define USE_ACC_MMA8452
#define USE_ACC_MPU6050
//#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6050_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
// #define USE_RANGEFINDER
//#define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
#define RANGEFINDER_HCSR04_ECHO_PIN PB1
#define RANGEFINDER_HCSR04_TRIGGER_PIN_PWM PB8
#define RANGEFINDER_HCSR04_ECHO_PIN_PWM PB9
//#define USE_DASHBOARD
#define USE_UART1
#define USE_UART2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_RX_PIN PA6
#define SOFTSERIAL_1_TX_PIN PA7
#define SOFTSERIAL_2_RX_PIN PB0
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define USE_I2C_DEVICE_2
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define USE_ADC
#define ADC_CHANNEL_1_PIN PB1
#define ADC_CHANNEL_2_PIN PA4
#define ADC_CHANNEL_3_PIN PA1
#define ADC_CHANNEL_4_PIN PA5
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// IO - stm32f103RCT6 in 64pin package (TODO)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -1,27 +0,0 @@
F1_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH HIGHEND
DEVICE_FLAGS = -DSTM32F10X_HD
TARGET_SRC = \
drivers/accgyro/accgyro_adxl345.c \
drivers/accgyro/accgyro_bma280.c \
drivers/accgyro/accgyro_fake.c \
drivers/accgyro/accgyro_l3g4200d.c \
drivers/accgyro/accgyro_mma845x.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu3050.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms56xx.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stdperiph.c