Skip to content

Commit

Permalink
CC3DF3 Initial Target
Browse files Browse the repository at this point in the history
  • Loading branch information
kc10kevin committed Aug 28, 2016
1 parent 00cad53 commit c25d561
Show file tree
Hide file tree
Showing 9 changed files with 306 additions and 12 deletions.
8 changes: 4 additions & 4 deletions src/main/config/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -575,8 +575,8 @@ void createDefaultConfig(master_t *config)

config->servo_pwm_rate = 50;

#ifdef CC3D
config->use_buzzer_p6 = 0;
#if defined(CC3D) || defined(CC3DF3)
masterConfig.use_buzzer_p6 = 0;
#endif

#ifdef GPS
Expand Down Expand Up @@ -884,7 +884,7 @@ void validateAndFixConfig(void)
}
#endif

#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
#if (defined(CC3D) || defined(CC3DF3)) && defined(DISPLAY) && defined(USE_UART3)
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
featureClear(FEATURE_DISPLAY);
}
Expand All @@ -903,7 +903,7 @@ void validateAndFixConfig(void)
#endif
*/

#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
#if (defined(CC3D) || defined(CC3DF3)) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
// shared pin
if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
featureClear(FEATURE_SONAR);
Expand Down
2 changes: 1 addition & 1 deletion src/main/config/config_master.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ typedef struct master_t {
gimbalConfig_t gimbalConfig;
#endif

#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
uint8_t use_buzzer_p6;
#endif

Expand Down
4 changes: 2 additions & 2 deletions src/main/drivers/pwm_mapping.c
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ const uint16_t * const hardwareMaps[] = {
airPPM,
};

#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
const uint16_t * const hardwareMapsBP6[] = {
multiPWM_BP6,
multiPPM_BP6,
Expand Down Expand Up @@ -104,7 +104,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (init->usePPM || init->useSerialRx)
i++; // next index is for PPM

#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
setup = init->useBuzzerP6 ? hardwareMapsBP6[i] : hardwareMaps[i];
#else
setup = hardwareMaps[i];
Expand Down
4 changes: 2 additions & 2 deletions src/main/drivers/pwm_mapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ typedef struct drv_pwm_config_s {
uint16_t servoPwmRate;
uint16_t servoCenterPulse;
#endif
#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
bool useBuzzerP6;
#endif
bool airplane; // fixed wing hardware config, lots of servos etc
Expand Down Expand Up @@ -130,7 +130,7 @@ extern const uint16_t multiPWM[];
extern const uint16_t airPPM[];
extern const uint16_t airPWM[];

#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
extern const uint16_t multiPPM_BP6[];
extern const uint16_t multiPWM_BP6[];
extern const uint16_t airPPM_BP6[];
Expand Down
2 changes: 1 addition & 1 deletion src/main/io/serial_cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -676,7 +676,7 @@ const clivalue_t valueTable[] = {
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },

#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
#endif
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
Expand Down
4 changes: 2 additions & 2 deletions src/main/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,7 @@ void init(void)
featureClear(FEATURE_3D);
pwm_params.idlePulse = 0; // brushed motors
}
#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
#endif
#ifndef SKIP_RX_PWM_PPM
Expand Down Expand Up @@ -340,7 +340,7 @@ void init(void)
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
}
#endif
#ifdef CC3D
#if defined(CC3D) || defined(CC3DF3)
if (masterConfig.use_buzzer_p6 == 1)
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
#endif
Expand Down
162 changes: 162 additions & 0 deletions src/main/target/CC3DF3/target.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,162 @@
/*
* 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
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (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), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
0xFFFF
};

const uint16_t airPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 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), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};

const uint16_t multiPPM_BP6[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};

const uint16_t multiPWM_BP6[] = {
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), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};

const uint16_t airPPM_BP6[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};

const uint16_t airPWM_BP6[] = {
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), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
0xFFFF
};

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5}, // S1_IN - PPM IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // S2_IN - SoftSerial TX / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // S6_IN - RSSI

{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // ??time17ch1 tim8 ch3??? S1 - PB9 - TIM4_CH4 - AF02
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // ??time16ch1 tim8 ch2???S2 - PB8 - TIM4_CH3 - AF02
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // S3 - PB7 - TIM4_CH2 - AF02
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // S5 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // S6 - PA2 - TIM2_CH3 - AF01
};

119 changes: 119 additions & 0 deletions src/main/target/CC3DF3/target.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
/*
* 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 "CC3DF3"


#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define CONFIG_PREFER_ACC_ON

#define LED0 PB3

#define BEEPER PA15
#define BEEPER_OPT PA2

#define USE_EXTI
#define MPU_INT_EXTI PA3
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU INT, SDCardDetect
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW

#define GYRO

#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1

#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG

#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2

#define USABLE_TIMER_CHANNEL_COUNT 12

#define USB_IO

#define USE_VCP
#define USE_UART1
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 4

#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3

#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10

//#define UART2_TX_PIN PA14
//#define UART2_RX_PIN PA15

#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)


//#define USE_I2C
//#define I2C_DEVICE (I2CDEV_2) // SCL/PB10, SDA/PB11 - no I2C on PB10/PB11 on the STM32F303

#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PA1
//#define CURRENT_METER_ADC_PIN PB1

#define LED_STRIP

#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PB4
#define WS2811_TIMER TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER

#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB5

#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11

#define USE_SERIAL_4WAY_BLHELI_INTERFACE

#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))

#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16))
13 changes: 13 additions & 0 deletions src/main/target/CC3DF3/target.mk
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP ONBOARDFLASH

TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/barometer_ms5611.c \
drivers/barometer_bmp085.c \
drivers/barometer_bmp280.c \
drivers/accgyro_spi_mpu6000.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/sonar_hcsr04.c \
drivers/serial_softserial.c

0 comments on commit c25d561

Please sign in to comment.