diff --git a/src/main/drivers/max7456_symbols.h b/src/main/drivers/max7456_symbols.h index b2e8da72b5..ba798d1d97 100644 --- a/src/main/drivers/max7456_symbols.h +++ b/src/main/drivers/max7456_symbols.h @@ -178,7 +178,7 @@ // Voltage and amperage #define SYM_VOLT 0x06 #define SYM_AMP 0x9A -#define SYM_MAH 0xA4 +#define SYM_MAH 0x07 #define SYM_WATT 0x57 // Flying Mode diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index ced8d97fff..4663701179 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -298,7 +298,7 @@ uint32_t uartTotalRxBytesWaiting(serialPort_t *instance) if (s->rxDMAStream) { uint32_t rxDMAHead = s->rxDMAStream->NDTR; #else - if (s->rxDMAChannel) { + if (s->rxDMAChannel) { uint32_t rxDMAHead = s->rxDMAChannel->CNDTR; #endif if (rxDMAHead >= s->rxDMAPos) { @@ -421,13 +421,13 @@ void uartWrite(serialPort_t *instance, uint8_t ch) const struct serialPortVTable uartVTable[] = { { - uartWrite, - uartTotalRxBytesWaiting, - uartTotalTxBytesFree, - uartRead, - uartSetBaudRate, - isUartTransmitBufferEmpty, - uartSetMode, + .serialWrite = uartWrite, + .serialTotalRxWaiting = uartTotalRxBytesWaiting, + .serialTotalTxFree = uartTotalTxBytesFree, + .serialRead = uartRead, + .serialSetBaudRate = uartSetBaudRate, + .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, + .setMode = uartSetMode, .writeBuf = NULL, .beginWrite = NULL, .endWrite = NULL, diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 8360b0068f..2c2cebbac6 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -171,9 +171,9 @@ static const struct serialPortVTable usbVTable[] = { .serialSetBaudRate = usbVcpSetBaudRate, .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, .setMode = usbVcpSetMode, + .writeBuf = usbVcpWriteBuf, .beginWrite = usbVcpBeginWrite, - .endWrite = usbVcpEndWrite, - .writeBuf = usbVcpWriteBuf + .endWrite = usbVcpEndWrite } }; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ea458e66ee..abd862dd13 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -20,6 +20,7 @@ #include #include #include +#include #include "platform.h" #include "version.h" @@ -753,6 +754,28 @@ void updateOsd(void) sprintf(line+1, "%d.%1d", vbat / 10, vbat % 10); max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE]); } + + if (masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW] != -1) { + line[0] = SYM_AMP; + sprintf(line+1, "%d.%02d", amperage / 100, amperage % 100); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW]); + } + + if (masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN] != -1) { + line[0] = SYM_MAH; + sprintf(line+1, "%d", mAhDrawn); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN]); + } + + if (masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME] != -1) { + for (uint8_t i = 0; i < MAX_NAME_LENGTH; i++) { + line[i] = toupper((unsigned char)masterConfig.name[i]); + if (masterConfig.name[i] == 0) + break; + } + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME]); + } + if (masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] != -1) { line[0] = SYM_RSSI; sprintf(line+1, "%d", rssi / 10); @@ -823,6 +846,9 @@ void resetOsdConfig(void) masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109; masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] = -1; masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] = -1; + masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW] = -23; + masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN] = -18; + masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME] = 1; } #endif diff --git a/src/main/io/osd.h b/src/main/io/osd.h index e348e4573c..b5f4e953db 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -50,6 +50,9 @@ typedef enum { OSD_DISARMED, OSD_ARTIFICIAL_HORIZON, OSD_HORIZON_SIDEBARS, + OSD_CURRENT_DRAW, + OSD_MAH_DRAWN, + OSD_CRAFT_NAME, OSD_MAX_ITEMS, // MUST BE LAST } osd_items_t; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 0f94c7bc15..2e8e2eab44 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -194,7 +194,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction #ifdef TELEMETRY #define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT) #else -#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM) +#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK) #endif #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK) @@ -270,7 +270,7 @@ serialPort_t *openSerialPort( portMode_t mode, portOptions_t options) { -#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) +#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_UART4) && !defined(USE_UART5) && !defined(USE_UART6) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)) UNUSED(callback); UNUSED(baudRate); UNUSED(mode); diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 077ad07293..924f582323 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -34,6 +34,7 @@ typedef enum { FUNCTION_RX_SERIAL = (1 << 6), // 64 FUNCTION_BLACKBOX = (1 << 7), // 128 FUNCTION_PASSTHROUGH = (1 << 8), // 256 + FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512 } serialPortFunction_e; typedef enum { diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 87fd199559..5e89ff37e0 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -893,6 +893,9 @@ const clivalue_t valueTable[] = { { "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } }, { "osd_artificial_horizon", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { -1, 0 } }, { "osd_horizon_sidebars", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], .config.minmax = { -1, 0 } }, + { "osd_current_draw_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], .config.minmax = { -480, 480 } }, + { "osd_mah_drawn_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], .config.minmax = { -480, 480 } }, + { "osd_craft_name_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], .config.minmax = { -480, 480 } }, #endif }; diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index d3ac730016..2836d5ebca 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -35,16 +35,17 @@ */ #include -#include #include -#include "common/utils.h" #include "platform.h" + +#include "common/utils.h" #include "build_config.h" #include "drivers/system.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" #include "io/serial.h" +#include "rx/rx.h" #include "rx/jetiexbus.h" @@ -55,6 +56,7 @@ #include "sensors/battery.h" #include "sensors/barometer.h" #include "telemetry/telemetry.h" +#include "telemetry/jetiexbus.h" #endif //TELEMETRY diff --git a/src/main/rx/jetiexbus.h b/src/main/rx/jetiexbus.h index a975e5c643..52b0bb45c4 100644 --- a/src/main/rx/jetiexbus.h +++ b/src/main/rx/jetiexbus.h @@ -17,19 +17,6 @@ #pragma once - -#include "rx/rx.h" - bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); uint8_t jetiExBusFrameStatus(void); - -#ifdef TELEMETRY - -#include "telemetry/telemetry.h" - -void initJetiExBusTelemetry(telemetryConfig_t *initialTelemetryConfig); -void checkJetiExBusTelemetryState(void); -void handleJetiExBusTelemetry(void); - -#endif //TELEMETRY diff --git a/src/main/target/AIORACERF3/target.c b/src/main/target/AIORACERF3/target.c new file mode 100644 index 0000000000..e780364ec2 --- /dev/null +++ b/src/main/target/AIORACERF3/target.c @@ -0,0 +1,96 @@ +/* + * 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 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + // PPM / UART2 RX + { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM4 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_RX (AF7) + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, //LED_STRIP +}; diff --git a/src/main/target/AIORACERF3/target.h b/src/main/target/AIORACERF3/target.h new file mode 100644 index 0000000000..1bf8886220 --- /dev/null +++ b/src/main/target/AIORACERF3/target.h @@ -0,0 +1,164 @@ +/* + * 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 "ARF3" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define LED0 PB8 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip + +#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect + +#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_SPI_MPU6500 + +#define ACC +#define USE_ACC_SPI_MPU6500 + +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG + +#define BARO +#define USE_BARO_BMP280 + +#define MAG +#define USE_MAG_AK8963 +//#define USE_MAG_HMC5883 // External + +#define MAG_AK8963_ALIGN CW90_DEG_FLIP + +//#define SONAR + +#define USB_IO + +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define SERIAL_PORT_COUNT 4 + +#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 USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard) + +#define SPI1_NSS_PIN PB9 +#define SPI1_SCK_PIN PB3 +#define SPI1_MISO_PIN PB4 +#define SPI1_MOSI_PIN PB5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SDCARD +#define USE_SDCARD_SPI2 + +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN PC14 +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN + +// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 + +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. +#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 + +#define MPU6500_CS_PIN PB9 +#define MPU6500_SPI_INSTANCE SPI1 + +#define BOARD_HAS_VOLTAGE_DIVIDER +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PA4 +#define RSSI_ADC_PIN PB2 + +#define LED_STRIP +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#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 TRANSPONDER +#define TRANSPONDER_GPIO GPIOA +#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define TRANSPONDER_GPIO_AF GPIO_AF_6 +#define TRANSPONDER_PIN GPIO_Pin_8 +#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 +#define TRANSPONDER_TIMER TIM1 +#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 +#define TRANSPONDER_IRQ DMA1_Channel2_IRQn +#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 +#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) + +#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(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) + diff --git a/src/main/target/AIORACERF3/target.mk b/src/main/target/AIORACERF3/target.mk new file mode 100644 index 0000000000..9b179afe4b --- /dev/null +++ b/src/main/target/AIORACERF3/target.mk @@ -0,0 +1,16 @@ +F3_TARGETS += $(TARGET) +FEATURES = VCP SDCARD + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8963.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/transponder_ir.c + diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 5bd61457fc..3469c0c113 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -32,12 +32,12 @@ #define INVERTER_USART USART2 // MPU interrupt +#define USE_EXTI +#define MPU_INT_EXTI PC14 +#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready //#define DEBUG_MPU_DATA_READY_INTERRUPT #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready -#define MPU_INT_EXTI PC14 -#define USE_EXTI #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 73f7f86c99..737338b054 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -40,6 +40,12 @@ #define INVERTER PB15 #define INVERTER_USART USART6 +// MPU6500 interrupt +//#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW +//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready +#define MPU_INT_EXTI PC5 #define MPU6500_CS_PIN PC4 #define MPU6500_SPI_INSTANCE SPI1 @@ -87,15 +93,6 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USABLE_TIMER_CHANNEL_COUNT 7 - -// MPU6500 interrupt -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW -//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready -#define MPU_INT_EXTI PC5 - #define USE_VCP //#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_ENABLED @@ -169,5 +166,6 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) +#define USABLE_TIMER_CHANNEL_COUNT 7 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index c6263bcd47..073e2fb916 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -31,6 +31,12 @@ #define INVERTER PC0 // PC0 used as inverter select GPIO #define INVERTER_USART USART1 +// MPU6000 interrupts +#define USE_EXTI +#define MPU_INT_EXTI PC4 +#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) +#define USE_MPU_DATA_READY_SIGNAL + #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 @@ -50,12 +56,6 @@ #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG -// MPU6000 interrupts -#define USE_MPU_DATA_READY_SIGNAL -#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC4 -#define USE_EXTI - #define BARO #define USE_BARO_MS5611 #define MS5611_I2C_INSTANCE I2CDEV_1 diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 87c5c286a9..0a0ec2593d 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -26,14 +26,11 @@ #define BEEPER PC15 #define BEEPER_INVERTED -#define USABLE_TIMER_CHANNEL_COUNT 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. - -#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect - +#define USE_EXTI +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC13 -#define USE_EXTI +#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect #define MPU6000_SPI_INSTANCE SPI1 #define MPU6000_CS_PIN PA4 @@ -71,7 +68,7 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PA9 #define UART1_RX_PIN PA10 @@ -192,4 +189,5 @@ #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 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index fccca3016b..5250a336b7 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -26,28 +26,30 @@ #define USBD_SERIALNUMBER_STRING "0x8020000" #endif -#define LED0 PB5 -#define LED1 PB4 -#define BEEPER PB4 -#define INVERTER PC0 // PC0 used as inverter select GPIO -#define INVERTER_USART USART1 +#define LED0 PB5 +#define LED1 PB4 -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define BEEPER PB4 + +#define INVERTER PC0 // PC0 used as inverter select GPIO +#define INVERTER_USART USART1 + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 #define ACC #define USE_ACC_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG #define GYRO #define USE_GYRO_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#define ACC_MPU6000_ALIGN CW270_DEG // MPU6000 interrupts +#define USE_EXTI +#define MPU_INT_EXTI PC4 #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC4 -#define USE_EXTI #define MAG #define USE_MAG_HMC5883 @@ -61,8 +63,8 @@ #define OSD #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI3 -#define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_SPI_INSTANCE SPI3 +#define MAX7456_SPI_CS_PIN PA15 #define MAX7456_DMA_CHANNEL_TX DMA1_Stream5 #define MAX7456_DMA_CHANNEL_RX DMA1_Stream0 @@ -72,31 +74,29 @@ //#define USE_PITOT_MS4525 //#define MS4525_BUS I2C_DEVICE_EXT -#define M25P16_CS_PIN SPI3_NSS_PIN -#define M25P16_SPI_INSTANCE SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define M25P16_SPI_INSTANCE SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USABLE_TIMER_CHANNEL_COUNT 12 - #define USE_VCP #define VBUS_SENSING_PIN PC5 -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 +#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 #define USE_SPI @@ -112,16 +112,16 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC -#define CURRENT_METER_ADC_PIN PC1 -#define VBAT_ADC_PIN PC2 -#define RSSI_ADC_GPIO_PIN PA0 +#define CURRENT_METER_ADC_PIN PC1 +#define VBAT_ADC_PIN PC2 +#define RSSI_ADC_GPIO_PIN PA0 #define SENSORS_SET (SENSOR_ACC) -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125 | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125 | FEATURE_RX_SERIAL) #define USE_SERIAL_4WAY_BLHELI_INTERFACE @@ -130,4 +130,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff +#define USABLE_TIMER_CHANNEL_COUNT 12 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 1632d2046d..cab5ad2edd 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -128,6 +128,8 @@ #define USE_ADC #define ADC_INSTANCE ADC1 #define VBAT_ADC_PIN PA0 +#define CURRENT_METER_ADC_PIN PA3 +#define RSSI_ADC_PIN PA2 //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 94117a125c..9ba3c4a989 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -26,12 +26,9 @@ #define BEEPER PC15 #define BEEPER_INVERTED -#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip - -#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect - #define USE_EXTI #define MPU_INT_EXTI PC13 +#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW @@ -160,5 +157,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 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 799da79d47..b5ee87abf3 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -29,12 +29,9 @@ #define BEEPER PC15 #define BEEPER_INVERTED -#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. - -#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect - #define USE_EXTI #define MPU_INT_EXTI PC13 +#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW @@ -176,5 +173,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 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. #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/telemetry/frsky.c b/src/main/telemetry/frsky.c index 35185b9676..33bd13193c 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -21,7 +21,6 @@ */ #include #include -#include #include "platform.h" diff --git a/src/main/telemetry/frsky.h b/src/main/telemetry/frsky.h index 8d1b82d61c..555eb43e83 100644 --- a/src/main/telemetry/frsky.h +++ b/src/main/telemetry/frsky.h @@ -15,10 +15,9 @@ * along with Cleanflight. If not, see . */ -#include "rx/rx.h" +#pragma once -#ifndef TELEMETRY_FRSKY_H_ -#define TELEMETRY_FRSKY_H_ +#include "rx/rx.h" typedef enum { FRSKY_VFAS_PRECISION_LOW = 0, @@ -32,4 +31,3 @@ void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig); void configureFrSkyTelemetryPort(void); void freeFrSkyTelemetryPort(void); -#endif /* TELEMETRY_FRSKY_H_ */ diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 7ccf8ea197..dcab855ae0 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -57,11 +57,12 @@ #include #include "platform.h" -#include "build_config.h" -#include "debug.h" #ifdef TELEMETRY +#include "build_config.h" +#include "debug.h" + #include "common/axis.h" #include "drivers/system.h" diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h index 37b8e6f10f..64a43bd507 100644 --- a/src/main/telemetry/hott.h +++ b/src/main/telemetry/hott.h @@ -23,9 +23,7 @@ * Texmode add-on by Michi (mamaretti32@gmail.com) */ -#ifndef HOTT_TELEMETRY_H_ -#define HOTT_TELEMETRY_H_ - +#pragma once #define HOTTV4_RXTX 4 @@ -498,4 +496,3 @@ uint32_t getHoTTTelemetryProviderBaudRate(void); void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage); -#endif /* HOTT_TELEMETRY_H_ */ diff --git a/src/main/telemetry/jetiexbus.h b/src/main/telemetry/jetiexbus.h new file mode 100644 index 0000000000..79440c0df2 --- /dev/null +++ b/src/main/telemetry/jetiexbus.h @@ -0,0 +1,23 @@ +/* + * 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 + +struct telemetryConfig_s; +void initJetiExBusTelemetry(struct telemetryConfig_s *initialTelemetryConfig); +void checkJetiExBusTelemetryState(void); +void handleJetiExBusTelemetry(void); diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index c70146f64f..a7b7556e10 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -33,10 +33,10 @@ #include "platform.h" -#include "build_config.h" - #ifdef TELEMETRY +#include "build_config.h" + #include "common/maths.h" #include "common/axis.h" #include "common/color.h" @@ -79,8 +79,6 @@ #include "config/config.h" #include "config/runtime_config.h" -#include "config/config_profile.h" -#include "config/config_master.h" #define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX #define LTM_CYCLETIME 100 diff --git a/src/main/telemetry/ltm.h b/src/main/telemetry/ltm.h index c78dfc22e4..6e4b80cbfa 100644 --- a/src/main/telemetry/ltm.h +++ b/src/main/telemetry/ltm.h @@ -17,8 +17,7 @@ * along with Cleanflight. If not, see . */ -#ifndef TELEMETRY_LTM_H_ -#define TELEMETRY_LTM_H_ +#pragma once void initLtmTelemetry(telemetryConfig_t *initialTelemetryConfig); void handleLtmTelemetry(void); @@ -27,4 +26,3 @@ void checkLtmTelemetryState(void); void freeLtmTelemetryPort(void); void configureLtmTelemetryPort(void); -#endif /* TELEMETRY_LTM_H_ */ diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 03f257d05f..8d167dd2ca 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -60,8 +60,6 @@ #include "config/runtime_config.h" #include "config/config.h" -#include "config/config_profile.h" -#include "config/config_master.h" enum { diff --git a/src/main/telemetry/smartport.h b/src/main/telemetry/smartport.h index 74643f629f..b24be90708 100644 --- a/src/main/telemetry/smartport.h +++ b/src/main/telemetry/smartport.h @@ -5,8 +5,7 @@ * Author: Frank26080115 */ -#ifndef TELEMETRY_SMARTPORT_H_ -#define TELEMETRY_SMARTPORT_H_ +#pragma once void initSmartPortTelemetry(telemetryConfig_t *); @@ -18,4 +17,3 @@ void freeSmartPortTelemetryPort(void); bool isSmartPortTimedOut(void); -#endif /* TELEMETRY_SMARTPORT_H_ */ diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index e3871aead0..96e2193e9a 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" @@ -40,7 +39,7 @@ #include "telemetry/hott.h" #include "telemetry/smartport.h" #include "telemetry/ltm.h" -#include "rx/jetiexbus.h" +#include "telemetry/jetiexbus.h" static telemetryConfig_t *telemetryConfig;