From d0f622bb8115d8743032753cd883c3517c8df3b9 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 10 Nov 2014 00:53:48 +0100 Subject: [PATCH] PORT103R - Initial support for the Waveshare Port 103R development board. --- Makefile | 7 +- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/timer.c | 2 +- src/main/sensors/sonar.c | 2 +- src/main/target/PORT103R/target.h | 109 ++++++++++++++++++++++++++++++ 5 files changed, 117 insertions(+), 5 deletions(-) create mode 100644 src/main/target/PORT103R/target.h diff --git a/Makefile b/Makefile index 0bc35b386..b9fce24af 100644 --- a/Makefile +++ b/Makefile @@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0 FORKNAME = cleanflight -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R # Valid targets for OP BootLoader support OPBL_VALID_TARGETS = CC3D @@ -98,7 +98,7 @@ TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY endif -else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC)) +else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver @@ -266,6 +266,7 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ drivers/compass_hmc5883l.c \ drivers/display_ug2864hsweg01.h \ drivers/gpio_stm32f10x.c \ + drivers/inverter.c \ drivers/light_led_stm32f10x.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ @@ -282,6 +283,8 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ $(HIGHEND_SRC) \ $(COMMON_SRC) +PORT103R_SRC = $(EUSTM32F103RC_SRC) + OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_mpu6050.c \ drivers/adc.c \ diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index f39fa46ec..71b045384 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -69,7 +69,7 @@ enum { MAP_TO_SERVO_OUTPUT, }; -#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(MASSIVEF3) +#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(MASSIVEF3) || defined(PORT103R) static const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 13f7bbf6a..14cf26720 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -68,7 +68,7 @@ TIM4 4 channels */ -#if defined(CJMCU) || defined(EUSTM32F103RC) || defined(NAZE) || defined(OLIMEXINO) +#if defined(CJMCU) || defined(EUSTM32F103RC) || defined(NAZE) || defined(OLIMEXINO) || defined(PORT103R) const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2 diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index a123b1945..0f002e0d1 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -39,7 +39,7 @@ int32_t sonarAlt = -1; // in cm , -1 indicate sonar is not in range void Sonar_init(void) { -#if defined(NAZE) || defined(EUSTM32F103RC) +#if defined(NAZE) || defined(EUSTM32F103RC) || defined(PORT103R) static const sonarHardware_t const sonarPWM56 = { .trigger_pin = Pin_8, // PWM5 (PB8) - 5v tolerant .echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h new file mode 100644 index 000000000..b8a96ef34 --- /dev/null +++ b/src/main/target/PORT103R/target.h @@ -0,0 +1,109 @@ +/* + * 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 TARGET_BOARD_IDENTIFIER "103R" + +#define LED0_GPIO GPIOD +#define LED0_PIN Pin_2 // PD2 (LED) +#define LED0_PERIPHERAL RCC_APB2Periph_GPIOD + +#define BEEP_GPIO GPIOA +#define BEEP_PIN Pin_12 // PA12 (Beeper) +#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA + +#define BARO_XCLR_GPIO GPIOC +#define BARO_XCLR_PIN Pin_13 +#define BARO_EOC_GPIO GPIOC +#define BARO_EOC_PIN Pin_14 +#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC + +#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_GPIO GPIOB +#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB +#define INVERTER_USART USART2 + +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN GPIO_Pin_12 +#define MPU6000_SPI_INSTANCE SPI2 + +#define MPU6500_CS_GPIO GPIOB +#define MPU6500_CS_PIN GPIO_Pin_12 +#define MPU6500_SPI_INSTANCE SPI2 + +#define ACC +#define USE_FAKE_ACC +//#define USE_ACC_ADXL345 +//#define USE_ACC_BMA280 +//#define USE_ACC_MMA8452 +//#define USE_ACC_MPU3050 +#define USE_ACC_MPU6050 +//#define USE_ACC_SPI_MPU6000 +//#define USE_ACC_SPI_MPU6500 + +#define 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 BARO +#define USE_BARO_MS5611 +//#define USE_BARO_BMP085 + +#define MAG +#define SONAR +#define BEEPER +#define LED0 +#define INVERTER +#define DISPLAY + +#define USE_USART1 +#define USE_USART2 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 4 + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 +#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 +#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_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 SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG) + +#define LED0 +#define GPS +#define LED_STRIP +#define LED_STRIP_TIMER TIM3 + +#define TELEMETRY +#define SERIAL_RX +#define AUTOTUNE +