1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Disable ADC initialisation on CJMCU. Replace MASSIVEF3 with SPRACINGF3.

Conditional VCP code inclusion.  Other minor F1/F3 cleanups.
This commit is contained in:
Dominic Clifton 2015-01-20 23:33:03 +01:00
parent f825f15a9f
commit 650389afb6
24 changed files with 305 additions and 117 deletions

View file

@ -69,7 +69,7 @@ enum {
MAP_TO_SERVO_OUTPUT,
};
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(MASSIVEF3) || defined(PORT103R)
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || 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
@ -267,15 +267,64 @@ static const uint16_t multiPWM[] = {
};
static const uint16_t airPPM[] = {
// TODO
0xFFFF
};
static const uint16_t airPWM[] = {
// TODO
0xFFFF
};
#endif
#ifdef SPRACINGF3
static const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
static const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
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),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
static const uint16_t airPPM[] = {
// TODO
0xFFFF
};
static const uint16_t airPWM[] = {
// TODO
0xFFFF
};
#endif
static const uint16_t * const hardwareMaps[] = {
multiPWM,
multiPPM,
@ -387,6 +436,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if defined(SPRACINGF3)
// remap PWM15+16 as servos
if ((timerIndex == PWM15 || timerIndex == PWM16) && timerHardwarePtr->tim == TIM15)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if defined(NAZE32PRO) || (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3))
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
if (init->useSoftSerial) {