Optimisation of driver header files

This commit is contained in:
Martin Budden 2016-08-04 00:55:16 +01:00 committed by borisbstyle
parent 4bb0816122
commit 07adf66bbb
100 changed files with 212 additions and 138 deletions

View File

@ -23,6 +23,7 @@
#include "debug.h"
#include "build_config.h"
#include "debug.h"
#include "blackbox/blackbox_io.h"

View File

@ -21,7 +21,7 @@
#include "platform.h"
#include "system.h"
#include "gpio.h"
#include "io.h"
#include "bus_i2c.h"
#include "sensor.h"

View File

@ -27,6 +27,8 @@
#include "adc.h"
#include "adc_impl.h"
#include "common/utils.h"
//#define DEBUG_ADC_CHANNELS
#ifdef USE_ADC

View File

@ -17,7 +17,7 @@
#pragma once
#include "io.h"
#include "io_types.h"
typedef enum {
ADC_BATTERY = 0,

View File

@ -17,8 +17,8 @@
#pragma once
#include "io.h"
#include "rcc.h"
#include "io_types.h"
#include "rcc_types.h"
#if defined(STM32F4)
#define ADC_TAG_MAP_COUNT 16
@ -65,4 +65,4 @@ extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelByTag(ioTag_t ioTag);
uint8_t adcChannelByTag(ioTag_t ioTag);

View File

@ -15,6 +15,7 @@
* along with Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
@ -24,6 +25,7 @@
#include "barometer.h"
#include "barometer_bmp280.h"
#include "io.h"
#ifdef USE_BARO_SPI_BMP280
#define DISABLE_BMP280 IOHi(bmp280CsPin)

View File

@ -21,8 +21,8 @@
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#include "drivers/io.h"
#include "drivers/rcc.h"
#include "io_types.h"
#include "rcc_types.h"
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID

View File

@ -22,7 +22,7 @@
#include "build_config.h"
#include "bus_i2c.h"
#include "drivers/io.h"
#include "io.h"
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)

View File

@ -20,9 +20,10 @@
#include <platform.h>
#include "gpio.h"
#include "system.h"
#include "drivers/io_impl.h"
#include "io.h"
#include "io_impl.h"
#include "rcc.h"
#include "bus_i2c.h"

View File

@ -17,9 +17,8 @@
#pragma once
#include <stdint.h>
#include "io.h"
#include "rcc.h"
#include "io_types.h"
#include "rcc_types.h"
#if defined(STM32F4) || defined(STM32F3)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)

View File

@ -17,7 +17,7 @@
#pragma once
#include "io.h"
#include "io_types.h"
typedef struct hmc5883Config_s {
ioTag_t intTag;

View File

@ -21,8 +21,8 @@
#include <platform.h>
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "nvic.h"
#include "dma.h"
/*
* DMA descriptors.

View File

@ -21,8 +21,8 @@
#include <platform.h>
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "nvic.h"
#include "dma.h"
/*
* DMA descriptors.

View File

@ -22,9 +22,10 @@
#ifdef USE_FLASH_M25P16
#include "drivers/flash_m25p16.h"
#include "drivers/bus_spi.h"
#include "drivers/system.h"
#include "flash_m25p16.h"
#include "io.h"
#include "bus_spi.h"
#include "system.h"
#define M25P16_INSTRUCTION_RDID 0x9F
#define M25P16_INSTRUCTION_READ_BYTES 0x03

View File

@ -19,7 +19,7 @@
#include <stdint.h>
#include "flash.h"
#include "io.h"
#include "io_types.h"
#define M25P16_PAGESIZE 256

View File

@ -10,9 +10,9 @@
#include "platform.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/gyro_sync.h"
#include "sensor.h"
#include "accgyro.h"
#include "gyro_sync.h"
static uint8_t mpuDividerDrops;

View File

@ -6,16 +6,7 @@
#include <platform.h>
#include "resource.h"
// IO pin identification
// make sure that ioTag_t can't be assigned into IO_t without warning
typedef uint8_t ioTag_t; // packet tag to specify IO pin
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
// NONE initializer for ioTag_t variables
#define IOTAG_NONE ((ioTag_t)0)
// NONE initializer for IO_t variable
#define IO_NONE ((IO_t)0)
#include "io_types.h"
// preprocessor is used to convert pinid to requested C data value
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)
@ -24,19 +15,6 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin
// expand pinid to to ioTag_t
#define IO_TAG(pinid) DEFIO_TAG(pinid)
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
// this simplifies initialization (globals are zeroed on start) and allows
// omitting unused fields in structure initializers.
// it is also possible to use IO_t and ioTag_t as boolean value
// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
// IO_t being pointer is only possibility I know of ..
// pin config handling
// pin config is packed into ioConfig_t to decrease memory requirements
// IOCFG_x macros are defined for common combinations for all CPUs; this
// helps masking CPU differences
typedef uint8_t ioConfig_t; // packed IO configuration
#if defined(STM32F1)
// mode is using only bits 6-2

View File

@ -0,0 +1,28 @@
#pragma once
#include <stdint.h>
// IO pin identification
// make sure that ioTag_t can't be assigned into IO_t without warning
typedef uint8_t ioTag_t; // packet tag to specify IO pin
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
// NONE initializer for ioTag_t variables
#define IOTAG_NONE ((ioTag_t)0)
// NONE initializer for IO_t variable
#define IO_NONE ((IO_t)0)
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
// this simplifies initialization (globals are zeroed on start) and allows
// omitting unused fields in structure initializers.
// it is also possible to use IO_t and ioTag_t as boolean value
// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
// IO_t being pointer is only possibility I know of ..
// pin config handling
// pin config is packed into ioConfig_t to decrease memory requirements
// IOCFG_x macros are defined for common combinations for all CPUs; this
// helps masking CPU differences
typedef uint8_t ioConfig_t; // packed IO configuration

View File

@ -36,8 +36,8 @@
#include "common/color.h"
#include "common/colorconversion.h"
#include "drivers/dma.h"
#include "drivers/light_ws2811strip.h"
#include "dma.h"
#include "light_ws2811strip.h"
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
volatile uint8_t ws2811LedDataTransferInProgress = 0;

View File

@ -23,10 +23,11 @@
#ifdef LED_STRIP
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
#include "light_ws2811strip.h"
#include "nvic.h"
#include "io.h"
#include "dma.h"
#include "rcc.h"
#include "timer.h"
static IO_t ws2811IO = IO_NONE;

View File

@ -26,7 +26,7 @@
#include "nvic.h"
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
#include "light_ws2811strip.h"
#include "dma.h"
#include "rcc.h"
#include "timer.h"

View File

@ -19,16 +19,19 @@
#include <stdint.h>
#include "platform.h"
#include "version.h"
#ifdef USE_MAX7456
#include "version.h"
#include "common/printf.h"
#include "drivers/bus_spi.h"
#include "drivers/light_led.h"
#include "drivers/system.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "bus_spi.h"
#include "light_led.h"
#include "io.h"
#include "system.h"
#include "nvic.h"
#include "dma.h"
#include "max7456.h"
#include "max7456_symbols.h"

View File

@ -17,7 +17,7 @@
#pragma once
#include "timer.h"
#include "io_types.h"
#define MAX_PWM_MOTORS 12
#define MAX_PWM_SERVOS 8
@ -88,10 +88,11 @@ typedef enum {
PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4)
} pwmPortFlags_e;
struct timerHardware_s;
typedef struct pwmPortConfiguration_s {
uint8_t index;
pwmPortFlags_e flags;
const timerHardware_t *timerHardware;
const struct timerHardware_s *timerHardware;
} pwmPortConfiguration_t;
typedef struct pwmOutputConfiguration_s {

View File

@ -30,7 +30,7 @@
#include "system.h"
#include "nvic.h"
#include "gpio.h"
#include "io.h"
#include "timer.h"
#include "pwm_output.h"

View File

@ -2,6 +2,7 @@
#include "platform.h"
#include "common/utils.h"
#include "rcc_types.h"
enum rcc_reg {
RCC_EMPTY = 0, // make sure that default value (0) does not enable anything
@ -17,9 +18,6 @@ enum rcc_reg {
#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN)
#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN)
typedef uint8_t rccPeriphTag_t;
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);

View File

@ -0,0 +1,4 @@
#pragma once
typedef uint8_t rccPeriphTag_t;

View File

@ -25,8 +25,8 @@
#include "nvic.h"
#include "io.h"
#include "drivers/bus_spi.h"
#include "drivers/system.h"
#include "bus_spi.h"
#include "system.h"
#include "sdcard.h"
#include "sdcard_standard.h"

View File

@ -22,7 +22,7 @@
#include "build_config.h"
#include "common/utils.h"
#include "drivers/io.h"
#include "io.h"
#include "usb_core.h"
#ifdef STM32F4
@ -32,7 +32,7 @@
#include "hw_config.h"
#endif
#include "drivers/system.h"
#include "system.h"
#include "serial.h"
#include "serial_usb_vcp.h"

View File

@ -17,8 +17,7 @@
#pragma once
#include "platform.h"
#include "io.h"
#include "io_types.h"
typedef struct sonarHardware_s {
ioTag_t triggerTag;

View File

@ -17,7 +17,7 @@
#pragma once
#include "drivers/io.h"
#include "io_types.h"
#ifdef BEEPER
#define BEEP_TOGGLE systemBeepToggle()

View File

@ -25,7 +25,7 @@
#include "nvic.h"
#include "gpio.h"
#include "io.h"
#include "rcc.h"
#include "system.h"

View File

@ -17,12 +17,11 @@
#pragma once
#include "io.h"
#include "rcc.h"
#include <stdbool.h>
#include <stdint.h>
#if !defined(USABLE_TIMER_CHANNEL_COUNT)
#define USABLE_TIMER_CHANNEL_COUNT 14
#endif
#include "io_types.h"
#include "rcc_types.h"
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)

View File

@ -5,6 +5,11 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "stm32f10x.h"
#include "rcc.h"
#include "timer.h"

View File

@ -5,6 +5,11 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "stm32f30x.h"
#include "rcc.h"
#include "timer.h"

View File

@ -5,9 +5,14 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "stm32f4xx.h"
#include "timer.h"
#include "rcc.h"
#include "timer.h"
/**
* @brief Selects the TIM Output Compare Mode.

View File

@ -21,9 +21,9 @@
#include <platform.h>
#include "drivers/dma.h"
#include "drivers/nvic.h"
#include "drivers/transponder_ir.h"
#include "dma.h"
#include "nvic.h"
#include "transponder_ir.h"
/*
* Implementation note:

View File

@ -20,9 +20,9 @@
#include <platform.h>
#include "drivers/gpio.h"
#include "drivers/transponder_ir.h"
#include "drivers/nvic.h"
#include "gpio.h"
#include "transponder_ir.h"
#include "nvic.h"
#ifndef TRANSPONDER_GPIO
#define USE_TRANSPONDER_ON_DMA1_CHANNEL3

View File

@ -31,9 +31,9 @@
#include "common/maths.h"
#include "drivers/vtx_rtc6705.h"
#include "drivers/bus_spi.h"
#include "drivers/system.h"
#include "vtx_rtc6705.h"
#include "bus_spi.h"
#include "system.h"
#define RTC6705_SET_HEAD 0x3210 //fosc=8mhz r=400
#define RTC6705_SET_A1 0x8F3031 //5865

View File

@ -22,9 +22,10 @@
#ifdef USE_RTC6705
#include "drivers/bus_spi.h"
#include "drivers/system.h"
#include "drivers/light_led.h"
#include "bus_spi.h"
#include "io.h"
#include "system.h"
#include "light_led.h"
#include "vtx_soft_spi_rtc6705.h"

View File

@ -25,8 +25,10 @@
#include "platform.h"
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "drivers/io_types.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/timer.h"
#include "drivers/pwm_mapping.h"
#include "io/serial.h"
#include "io/serial_msp.h"

View File

@ -33,6 +33,7 @@
#include "drivers/system.h"
#include "drivers/dma.h"
#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/timer.h"

View File

@ -24,7 +24,7 @@
#include "common/axis.h"
#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/system.h"
#include "drivers/exti.h"

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -90,4 +90,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -35,8 +35,6 @@
#define BEEPER PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_EXTI
@ -131,5 +129,6 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -71,4 +71,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -67,11 +67,6 @@
#define M25P16_CS_PIN PC15
#define M25P16_SPI_INSTANCE SPI2
// timer definitions in drivers/timer.c
// channel mapping in drivers/pwm_mapping.c
// only 6 outputs available on hardware
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
@ -147,5 +142,9 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
// timer definitions in drivers/timer.c
// channel mapping in drivers/pwm_mapping.c
// only 6 outputs available on hardware
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -113,5 +113,6 @@
#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

@ -3,17 +3,18 @@
#include <platform.h>
#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
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
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), // Swap to servo if needed
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
@ -47,13 +48,13 @@ const uint16_t multiPWM[] = {
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
@ -84,23 +85,23 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
};

View File

@ -74,8 +74,6 @@
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_VCP
#define VBUS_SENSING_PIN PA9
@ -156,5 +154,6 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -101,8 +101,6 @@
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED
@ -167,5 +165,6 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -23,8 +23,6 @@
#define LED0 PB3
#define USABLE_TIMER_CHANNEL_COUNT 17
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready, no MAG
#define USE_MPU_DATA_READY_SIGNAL
@ -105,5 +103,6 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|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))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM7 | (MAP_TO_PPM_INPUT << 8),

View File

@ -28,8 +28,6 @@
#define BEEPER PB13
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USE_EXTI
#define MPU_INT_EXTI PB2
#define USE_MPU_DATA_READY_SIGNAL
@ -84,4 +82,5 @@
#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(15) | TIM_N(16) | TIM_N(17))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -97,4 +97,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -163,4 +163,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -91,4 +91,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (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

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -28,8 +28,6 @@
#define BEEPER PA0
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
@ -136,5 +134,6 @@
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -123,5 +123,6 @@
#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

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8),

View File

@ -25,8 +25,6 @@
#define BEEPER PC15
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
@ -115,5 +113,6 @@
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM7 | (MAP_TO_PPM_INPUT << 8),

View File

@ -20,6 +20,7 @@
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -20,6 +20,7 @@
#include <platform.h>
#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

View File

@ -165,5 +165,6 @@
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0x00ff
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))

View File

@ -5,6 +5,7 @@
#include <platform.h>
#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

View File

@ -26,8 +26,6 @@
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
@ -128,5 +126,6 @@
#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) )

View File

@ -5,6 +5,7 @@
#include <platform.h>
#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

View File

@ -101,6 +101,5 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View File

@ -19,6 +19,8 @@
* Initial FrSky Telemetry implementation by silpstream @ rcgroups.
* Addition protocol work by airmamaf @ github.
*/
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>

View File

@ -15,6 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
@ -22,7 +23,6 @@
#ifdef TELEMETRY
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"