From 2f65e0d7f72e43b93e007c605531800d52215716 Mon Sep 17 00:00:00 2001 From: Maxim Khomenko Date: Sun, 6 Mar 2016 15:28:26 +0200 Subject: [PATCH 1/4] Some reworking of INDICATOR's and RING's functionality. * RING: phase start and direction of animation now depends on LED's X:Y coordinates on the grid (X+Y) * INDICATOR: it works only at LEDs with defined direction (North, South, East, West). Also the colors are changed: Orange for turns, Blue for acceleration, Red for decceleration. --- src/main/io/ledstrip.c | 112 ++++++++++++----------------------------- 1 file changed, 31 insertions(+), 81 deletions(-) diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 701d29a0a5..1fd4bae7a7 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -558,42 +558,6 @@ void applyDirectionalModeColor(const uint8_t ledIndex, const ledConfig_t *ledCon } -typedef enum { - QUADRANT_NORTH_EAST = 1, - QUADRANT_SOUTH_EAST, - QUADRANT_SOUTH_WEST, - QUADRANT_NORTH_WEST -} quadrant_e; - -void applyQuadrantColor(const uint8_t ledIndex, const ledConfig_t *ledConfig, const quadrant_e quadrant, const hsvColor_t *color) -{ - switch (quadrant) { - case QUADRANT_NORTH_EAST: - if (GET_LED_Y(ledConfig) <= highestYValueForNorth && GET_LED_X(ledConfig) >= lowestXValueForEast) { - setLedHsv(ledIndex, color); - } - return; - - case QUADRANT_SOUTH_EAST: - if (GET_LED_Y(ledConfig) >= lowestYValueForSouth && GET_LED_X(ledConfig) >= lowestXValueForEast) { - setLedHsv(ledIndex, color); - } - return; - - case QUADRANT_SOUTH_WEST: - if (GET_LED_Y(ledConfig) >= lowestYValueForSouth && GET_LED_X(ledConfig) <= highestXValueForWest) { - setLedHsv(ledIndex, color); - } - return; - - case QUADRANT_NORTH_WEST: - if (GET_LED_Y(ledConfig) <= highestYValueForNorth && GET_LED_X(ledConfig) <= highestXValueForWest) { - setLedHsv(ledIndex, color); - } - return; - } -} - void applyLedModeLayer(void) { const ledConfig_t *ledConfig; @@ -713,18 +677,24 @@ void applyLedWarningLayer(uint8_t updateNow) void applyLedIndicatorLayer(uint8_t indicatorFlashState) { const ledConfig_t *ledConfig; - static const hsvColor_t *flashColor; + static const hsvColor_t *turnColor; + static const hsvColor_t *accColor; + static const hsvColor_t *decColor; if (!rxIsReceivingSignal()) { return; } if (indicatorFlashState == 0) { - flashColor = &hsv_orange; + turnColor = &hsv_orange; + accColor = &hsv_blue; + decColor = &hsv_red; } else { - flashColor = &hsv_black; + turnColor = &hsv_black; + accColor = &hsv_black; + decColor = &hsv_black; } - + uint8_t ledIndex; for (ledIndex = 0; ledIndex < ledCount; ledIndex++) { @@ -734,25 +704,31 @@ void applyLedIndicatorLayer(uint8_t indicatorFlashState) if (!(ledConfig->flags & LED_FUNCTION_INDICATOR)) { continue; } - + if (rcCommand[ROLL] > INDICATOR_DEADBAND) { - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_EAST, flashColor); - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_EAST, flashColor); + if ((ledConfig->flags & LED_DIRECTION_EAST)) { + setLedHsv(ledIndex, turnColor); + continue; + } } if (rcCommand[ROLL] < -INDICATOR_DEADBAND) { - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_WEST, flashColor); - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_WEST, flashColor); + if ((ledConfig->flags & LED_DIRECTION_WEST)) { + setLedHsv(ledIndex, turnColor); + continue; + } } if (rcCommand[PITCH] > INDICATOR_DEADBAND) { - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_EAST, flashColor); - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_WEST, flashColor); + if ((ledConfig->flags & LED_DIRECTION_NORTH)) { + setLedHsv(ledIndex, accColor); + } } if (rcCommand[PITCH] < -INDICATOR_DEADBAND) { - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_EAST, flashColor); - applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_WEST, flashColor); + if ((ledConfig->flags & LED_DIRECTION_SOUTH)) { + setLedHsv(ledIndex, decColor); + } } } } @@ -790,11 +766,8 @@ void applyLedThrustRingLayer(void) uint8_t ledIndex; // initialised to special value instead of using more memory for a flag. - static uint8_t rotationSeqLedCount = RING_PATTERN_NOT_CALCULATED; static uint8_t rotationPhase = ROTATION_SEQUENCE_LED_COUNT; - bool nextLedOn = false; - uint8_t ledRingIndex = 0; for (ledIndex = 0; ledIndex < ledCount; ledIndex++) { ledConfig = &ledConfigs[ledIndex]; @@ -803,16 +776,15 @@ void applyLedThrustRingLayer(void) continue; } + uint8_t ledRingIndex = GET_LED_X(ledConfig) + GET_LED_Y(ledConfig); bool applyColor = false; + if (ARMING_FLAG(ARMED)) { - if ((ledRingIndex + rotationPhase) % rotationSeqLedCount < ROTATION_SEQUENCE_LED_WIDTH) { + if ((ledRingIndex + rotationPhase) % ROTATION_SEQUENCE_LED_COUNT < ROTATION_SEQUENCE_LED_WIDTH) { applyColor = true; } } else { - if (nextLedOn == false) { - applyColor = true; - } - nextLedOn = !nextLedOn; + applyColor = (ledRingIndex % 2) == 0; } if (applyColor) { @@ -822,33 +794,11 @@ void applyLedThrustRingLayer(void) } setLedHsv(ledIndex, &ringColor); - - ledRingIndex++; } - - uint8_t ledRingLedCount = ledRingIndex; - if (rotationSeqLedCount == RING_PATTERN_NOT_CALCULATED) { - // update ring pattern according to total number of ring leds found - - rotationSeqLedCount = ledRingLedCount; - - // try to split in segments/rings of exactly ROTATION_SEQUENCE_LED_COUNT leds - if ((ledRingLedCount % ROTATION_SEQUENCE_LED_COUNT) == 0) { - rotationSeqLedCount = ROTATION_SEQUENCE_LED_COUNT; - } else { - // else split up in equal segments/rings of at most ROTATION_SEQUENCE_LED_COUNT leds - while ((rotationSeqLedCount > ROTATION_SEQUENCE_LED_COUNT) && ((rotationSeqLedCount % 2) == 0)) { - rotationSeqLedCount >>= 1; - } - } - - // trigger start over - rotationPhase = 1; - } - + rotationPhase--; if (rotationPhase == 0) { - rotationPhase = rotationSeqLedCount; + rotationPhase = ROTATION_SEQUENCE_LED_COUNT; } } From 7f96eafc2d4291d0a7648b61cf66537c8433af16 Mon Sep 17 00:00:00 2001 From: Maxim Khomenko Date: Mon, 8 Aug 2016 23:37:34 +0300 Subject: [PATCH 2/4] Revert "Some reworking of INDICATOR's and RING's functionality." This reverts commit 2f65e0d7f72e43b93e007c605531800d52215716. --- src/main/io/ledstrip.c | 112 +++++++++++++++++++++++++++++------------ 1 file changed, 81 insertions(+), 31 deletions(-) diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 1fd4bae7a7..701d29a0a5 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -558,6 +558,42 @@ void applyDirectionalModeColor(const uint8_t ledIndex, const ledConfig_t *ledCon } +typedef enum { + QUADRANT_NORTH_EAST = 1, + QUADRANT_SOUTH_EAST, + QUADRANT_SOUTH_WEST, + QUADRANT_NORTH_WEST +} quadrant_e; + +void applyQuadrantColor(const uint8_t ledIndex, const ledConfig_t *ledConfig, const quadrant_e quadrant, const hsvColor_t *color) +{ + switch (quadrant) { + case QUADRANT_NORTH_EAST: + if (GET_LED_Y(ledConfig) <= highestYValueForNorth && GET_LED_X(ledConfig) >= lowestXValueForEast) { + setLedHsv(ledIndex, color); + } + return; + + case QUADRANT_SOUTH_EAST: + if (GET_LED_Y(ledConfig) >= lowestYValueForSouth && GET_LED_X(ledConfig) >= lowestXValueForEast) { + setLedHsv(ledIndex, color); + } + return; + + case QUADRANT_SOUTH_WEST: + if (GET_LED_Y(ledConfig) >= lowestYValueForSouth && GET_LED_X(ledConfig) <= highestXValueForWest) { + setLedHsv(ledIndex, color); + } + return; + + case QUADRANT_NORTH_WEST: + if (GET_LED_Y(ledConfig) <= highestYValueForNorth && GET_LED_X(ledConfig) <= highestXValueForWest) { + setLedHsv(ledIndex, color); + } + return; + } +} + void applyLedModeLayer(void) { const ledConfig_t *ledConfig; @@ -677,24 +713,18 @@ void applyLedWarningLayer(uint8_t updateNow) void applyLedIndicatorLayer(uint8_t indicatorFlashState) { const ledConfig_t *ledConfig; - static const hsvColor_t *turnColor; - static const hsvColor_t *accColor; - static const hsvColor_t *decColor; + static const hsvColor_t *flashColor; if (!rxIsReceivingSignal()) { return; } if (indicatorFlashState == 0) { - turnColor = &hsv_orange; - accColor = &hsv_blue; - decColor = &hsv_red; + flashColor = &hsv_orange; } else { - turnColor = &hsv_black; - accColor = &hsv_black; - decColor = &hsv_black; + flashColor = &hsv_black; } - + uint8_t ledIndex; for (ledIndex = 0; ledIndex < ledCount; ledIndex++) { @@ -704,31 +734,25 @@ void applyLedIndicatorLayer(uint8_t indicatorFlashState) if (!(ledConfig->flags & LED_FUNCTION_INDICATOR)) { continue; } - + if (rcCommand[ROLL] > INDICATOR_DEADBAND) { - if ((ledConfig->flags & LED_DIRECTION_EAST)) { - setLedHsv(ledIndex, turnColor); - continue; - } + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_EAST, flashColor); + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_EAST, flashColor); } if (rcCommand[ROLL] < -INDICATOR_DEADBAND) { - if ((ledConfig->flags & LED_DIRECTION_WEST)) { - setLedHsv(ledIndex, turnColor); - continue; - } + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_WEST, flashColor); + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_WEST, flashColor); } if (rcCommand[PITCH] > INDICATOR_DEADBAND) { - if ((ledConfig->flags & LED_DIRECTION_NORTH)) { - setLedHsv(ledIndex, accColor); - } + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_EAST, flashColor); + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_NORTH_WEST, flashColor); } if (rcCommand[PITCH] < -INDICATOR_DEADBAND) { - if ((ledConfig->flags & LED_DIRECTION_SOUTH)) { - setLedHsv(ledIndex, decColor); - } + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_EAST, flashColor); + applyQuadrantColor(ledIndex, ledConfig, QUADRANT_SOUTH_WEST, flashColor); } } } @@ -766,8 +790,11 @@ void applyLedThrustRingLayer(void) uint8_t ledIndex; // initialised to special value instead of using more memory for a flag. + static uint8_t rotationSeqLedCount = RING_PATTERN_NOT_CALCULATED; static uint8_t rotationPhase = ROTATION_SEQUENCE_LED_COUNT; + bool nextLedOn = false; + uint8_t ledRingIndex = 0; for (ledIndex = 0; ledIndex < ledCount; ledIndex++) { ledConfig = &ledConfigs[ledIndex]; @@ -776,15 +803,16 @@ void applyLedThrustRingLayer(void) continue; } - uint8_t ledRingIndex = GET_LED_X(ledConfig) + GET_LED_Y(ledConfig); bool applyColor = false; - if (ARMING_FLAG(ARMED)) { - if ((ledRingIndex + rotationPhase) % ROTATION_SEQUENCE_LED_COUNT < ROTATION_SEQUENCE_LED_WIDTH) { + if ((ledRingIndex + rotationPhase) % rotationSeqLedCount < ROTATION_SEQUENCE_LED_WIDTH) { applyColor = true; } } else { - applyColor = (ledRingIndex % 2) == 0; + if (nextLedOn == false) { + applyColor = true; + } + nextLedOn = !nextLedOn; } if (applyColor) { @@ -794,11 +822,33 @@ void applyLedThrustRingLayer(void) } setLedHsv(ledIndex, &ringColor); + + ledRingIndex++; } - + + uint8_t ledRingLedCount = ledRingIndex; + if (rotationSeqLedCount == RING_PATTERN_NOT_CALCULATED) { + // update ring pattern according to total number of ring leds found + + rotationSeqLedCount = ledRingLedCount; + + // try to split in segments/rings of exactly ROTATION_SEQUENCE_LED_COUNT leds + if ((ledRingLedCount % ROTATION_SEQUENCE_LED_COUNT) == 0) { + rotationSeqLedCount = ROTATION_SEQUENCE_LED_COUNT; + } else { + // else split up in equal segments/rings of at most ROTATION_SEQUENCE_LED_COUNT leds + while ((rotationSeqLedCount > ROTATION_SEQUENCE_LED_COUNT) && ((rotationSeqLedCount % 2) == 0)) { + rotationSeqLedCount >>= 1; + } + } + + // trigger start over + rotationPhase = 1; + } + rotationPhase--; if (rotationPhase == 0) { - rotationPhase = ROTATION_SEQUENCE_LED_COUNT; + rotationPhase = rotationSeqLedCount; } } From e9f99462195336ca7594ef3e13354de5e54bc6c9 Mon Sep 17 00:00:00 2001 From: Maxim Khomenko Date: Tue, 9 Aug 2016 00:15:44 +0300 Subject: [PATCH 3/4] Target for I-Shaped F3 FC from BG: http://www.banggood.com/I-shaped-F3-10DF-Flight-Controller-5V-2A-BEC-Bent-Straight-Pins-For-RC-Multirotors-p-1047005.html --- src/main/target/ISHAPEDF3/target.c | 121 +++++++++++++++++++++++++++ src/main/target/ISHAPEDF3/target.h | 122 ++++++++++++++++++++++++++++ src/main/target/ISHAPEDF3/target.mk | 11 +++ 3 files changed, 254 insertions(+) create mode 100644 src/main/target/ISHAPEDF3/target.c create mode 100644 src/main/target/ISHAPEDF3/target.h create mode 100644 src/main/target/ISHAPEDF3/target.mk diff --git a/src/main/target/ISHAPEDF3/target.c b/src/main/target/ISHAPEDF3/target.c new file mode 100644 index 0000000000..ec9176a27f --- /dev/null +++ b/src/main/target/ISHAPEDF3/target.c @@ -0,0 +1,121 @@ +/* + * 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/pwm_mapping.h" + +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), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +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 +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + 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), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 + + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP +}; + diff --git a/src/main/target/ISHAPEDF3/target.h b/src/main/target/ISHAPEDF3/target.h new file mode 100644 index 0000000000..5efad550fd --- /dev/null +++ b/src/main/target/ISHAPEDF3/target.h @@ -0,0 +1,122 @@ +/* + * 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 "ISF3" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE + +#define LED0 PB3 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 + +#define USE_EXTI +#define MPU_INT_EXTI PC13 +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH + +#define GYRO +#define USE_GYRO_MPU6500 +//#define USE_GYRO_SPI_MPU6500 + +#define ACC +#define USE_ACC_MPU6500 +//#define USE_ACC_SPI_MPU6500 + +#define BARO +#define USE_BARO_BMP280 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define SONAR +#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 5 + +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 + +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) + +#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_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +#define BOARD_HAS_VOLTAGE_DIVIDER +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#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 DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PIN PB11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#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(3)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 17 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) + + diff --git a/src/main/target/ISHAPEDF3/target.mk b/src/main/target/ISHAPEDF3/target.mk new file mode 100644 index 0000000000..94676e07dc --- /dev/null +++ b/src/main/target/ISHAPEDF3/target.mk @@ -0,0 +1,11 @@ +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c From f823a815406d2d931363bc5a7d38e197a91b1ff8 Mon Sep 17 00:00:00 2001 From: blckmn Date: Fri, 19 Aug 2016 22:51:59 +1000 Subject: [PATCH 4/4] Small PPM fixes and updates to REVO --- src/main/drivers/pwm_mapping.c | 20 +++++++++++--------- src/main/target/REVO/target.c | 11 ++++++----- 2 files changed, 17 insertions(+), 14 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 1466aa2d25..bc9336cbee 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -109,7 +109,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #else setup = hardwareMaps[i]; #endif - + TIM_TypeDef* ppmTimer = NULL; for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT && setup[i] != 0xFFFF; i++) { uint8_t timerIndex = setup[i] & 0x00FF; uint8_t type = (setup[i] & 0xFF00) >> 8; @@ -162,13 +162,13 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) } #endif -#ifdef RSSI_ADC_GPIO +#ifdef RSSI_ADC_PIN if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) { continue; } #endif -#ifdef CURRENT_METER_ADC_GPIO +#ifdef CURRENT_METER_ADC_PIN if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) { continue; } @@ -292,11 +292,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (type == MAP_TO_PPM_INPUT) { #ifndef SKIP_RX_PWM_PPM -#if defined(SPARKY) || defined(ALIENFLIGHTF3) - if (!(init->pwmProtocolType == PWM_TYPE_CONVENTIONAL)) { - ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2, init->pwmProtocolType); - } -#endif + ppmTimer = timerHardwarePtr->tim; ppmInConfig(timerHardwarePtr); #endif } else if (type == MAP_TO_PWM_INPUT) { @@ -313,9 +309,15 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; } #endif + if (init->usePPM) { + if (init->pwmProtocolType != PWM_TYPE_CONVENTIONAL && timerHardwarePtr->tim == ppmTimer) { + ppmAvoidPWMTimerClash(timerHardwarePtr, ppmTimer, init->pwmProtocolType); + } + } + if (init->useFastPwm) { pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType); - pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT; + pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT; } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_MOTOR_MODE_BRUSHED; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index e33f1a58c8..065e0d0f71 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input @@ -29,11 +30,11 @@ const uint16_t multiPPM[] = { PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), 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 + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed 0xFFFF };