Merge remote-tracking branch 'refs/remotes/betaflight/master'

This commit is contained in:
Thomas Miric 2018-09-23 07:51:15 +02:00
commit a248b80561
48 changed files with 98 additions and 96 deletions

View File

@ -448,7 +448,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
#endif
case FLIGHT_LOG_FIELD_CONDITION_RSSI:
return rxConfig()->rssi_channel > 0 || featureIsEnabled(FEATURE_RSSI_ADC);
return isRssiConfigured();
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return blackboxConfig()->p_ratio != 1;

View File

@ -30,9 +30,8 @@
#include "usb_io.h"
#include "sdcard.h"
#ifdef USE_USB_DETECT
static IO_t usbDetectPin = IO_NONE;
static IO_t usbDetectPin;
#endif
void usbCableDetectDeinit(void)
@ -47,9 +46,6 @@ void usbCableDetectDeinit(void)
void usbCableDetectInit(void)
{
#ifdef USE_USB_DETECT
#ifndef USB_DETECT_PIN
#define USB_DETECT_PIN NONE
#endif
usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN));
IOInit(usbDetectPin, OWNER_USB_DETECT, 0);

View File

@ -3840,6 +3840,9 @@ const cliResourceValue_t resourceTable[] = {
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
#endif
DEFW( OWNER_GYRO_CS, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, csnTag, 2 ),
#ifdef USE_USB_DETECT
DEFS( OWNER_USB_DETECT, PG_USB_CONFIG, usbDev_t, detectPin ),
#endif
};
#undef DEFS

View File

@ -20,28 +20,20 @@
#include "platform.h"
#if defined(USE_USB_ADVANCED_PROFILES)
#ifdef USE_VCP
#include "drivers/io.h"
#include "pg/pg_ids.h"
#include "usb.h"
#if !defined(USB_MSC_BUTTON_PIN)
#define USB_MSC_BUTTON_PIN NONE
#endif
#if defined(USE_USB_MSC_BUTTON_IPU)
#define MSC_BUTTON_IPU true
#else
#define MSC_BUTTON_IPU false
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(usbDev_t, usbDevConfig, PG_USB_CONFIG, 0);
PG_RESET_TEMPLATE(usbDev_t, usbDevConfig,
.type = DEFAULT,
.mscButtonPin = IO_TAG(USB_MSC_BUTTON_PIN),
.mscButtonUsePullup = MSC_BUTTON_IPU,
.detectPin = IO_TAG(USB_DETECT_PIN),
);
#endif

View File

@ -33,6 +33,7 @@ typedef struct usbDev_s {
uint8_t type;
ioTag_t mscButtonPin;
uint8_t mscButtonUsePullup;
ioTag_t detectPin;
} usbDev_t;
PG_DECLARE(usbDev_t, usbDevConfig);

View File

@ -697,3 +697,8 @@ uint16_t rxGetRefreshRate(void)
{
return rxRuntimeConfig.rxRefreshRate;
}
bool isRssiConfigured(void)
{
return rssiSource != RSSI_SOURCE_NONE;
}

View File

@ -166,6 +166,7 @@ void setRssiMsp(uint8_t newMspRssi);
void updateRSSI(timeUs_t currentTimeUs);
uint16_t getRssi(void);
uint8_t getRssiPercent(void);
bool isRssiConfigured(void);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);

View File

@ -71,7 +71,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3

View File

@ -156,7 +156,7 @@
#define USE_ADC
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_GPIO_PIN PC2
#define RSSI_ADC_PIN PC2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View File

@ -83,7 +83,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
//SerialRX
#define USE_UART2

View File

@ -80,7 +80,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3

View File

@ -37,6 +37,8 @@
#include "hardware_revision.h"
#define UART1_INVERTER PC9
void targetPreInit(void)
{
switch (hardwareRevision) {

View File

@ -41,9 +41,7 @@
#define BEEPER_INVERTED
#define INVERTER_PIN_UART6 PB15
//#define INVERTER_PIN_UART1 PC9
#define UART1_INVERTER PC9
//#define INVERTER_PIN_UART1 PC9 // Polarity depends on revision; handled in config.c
// MPU6500 interrupt
#define USE_EXTI

View File

@ -64,7 +64,6 @@
#define USE_GYRO_MPU6050
//#define L3GD20_SPI SPI1
//#define L3GD20_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOE
//#define L3GD20_CS_GPIO GPIOE
//#define L3GD20_CS_PIN PE3

View File

@ -93,7 +93,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -80,7 +80,6 @@
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3

View File

@ -62,7 +62,6 @@
//#define USE_UART1
//#define UART1_RX_PIN PA10
//#define UART1_TX_PIN PA9
//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
/* RX1 */
#define USE_UART2

View File

@ -82,7 +82,6 @@
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PD6

View File

@ -80,7 +80,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -110,7 +110,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -98,14 +98,6 @@
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#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 WS2811_TIMER_GPIO_AF GPIO_AF_6
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -133,8 +133,6 @@
#define UART1_TX_PIN PA9
#endif
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10

View File

@ -0,0 +1,42 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#ifdef USE_TARGET_CONFIG
#include "config_helper.h"
#include "io/serial.h"
#define ESC_SENSOR_UART SERIAL_PORT_USART7
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ ESC_SENSOR_UART, FUNCTION_ESC_SENSOR },
};
void targetConfiguration(void)
{
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
}
#endif

View File

@ -20,7 +20,7 @@
#pragma once
//#define USE_TARGET_CONFIG
#define USE_TARGET_CONFIG
#ifdef KAKUTEF7V2
#define TARGET_BOARD_IDENTIFIER "KT76"
@ -168,7 +168,6 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_UART SERIAL_PORT_USART6
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define ESC_SENSOR_UART SERIAL_PORT_USART7
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -113,7 +113,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -71,7 +71,6 @@
#define USE_RX_SPI
#define RX_SPI_INSTANCE SPI3
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
#define RX_SCK_PIN SPI3_SCK_PIN
#define RX_MISO_PIN SPI3_MISO_PIN

View File

@ -108,8 +108,6 @@
#define USE_RX_SPI
#define RX_SPI_INSTANCE SPI1
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
@ -142,7 +140,7 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0
#define ESCSERIAL_TIMER_TX_PIN PB9 // Motor 6, can't use escserial for hexa
#define DEFAULT_FEATURES (FEATURE_AIRMODE | FEATURE_TELEMETRY)

View File

@ -76,7 +76,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3
@ -139,7 +138,7 @@
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
// Reserved pins, not connected
//#define RSSI_ADC_GPIO_PIN PC2
//#define RSSI_ADC_PIN PC2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -84,7 +84,7 @@
#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, SOFTSERIAL1, SOFTSERIAL2
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PPM
#define ESCSERIAL_TIMER_TX_PIN PB10
#define USE_SPI
#define USE_SPI_DEVICE_1

View File

@ -146,7 +146,7 @@
#define USE_ADC
#define VBAT_ADC_PIN PA3
#define CURRENT_METER_ADC_PIN PC0
#define RSSI_ADC_GPIO_PIN PC3
#define RSSI_ADC_PIN PC3
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View File

@ -153,7 +153,7 @@
#define USE_ADC
#define VBAT_ADC_PIN PA3
#define CURRENT_METER_ADC_PIN PC0
#define RSSI_ADC_GPIO_PIN PC3
#define RSSI_ADC_PIN PC3
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View File

@ -29,9 +29,14 @@
#include "io/serial.h"
#ifdef FPVM_BETAFLIGHTF7
#define ESC_SENSOR_UART SERIAL_PORT_USART1
#elif defined(OMNIBUSF7V2)
#define ESC_SENSOR_UART SERIAL_PORT_USART7
#endif
static targetSerialPortFunction_t targetSerialPortFunction[] = {
#if defined(OMNIBUSF7V2) && defined(ESC_SENSOR_UART)
// OMNIBUS F7 V2 has an option to connect UART7_RX to ESC telemetry
#ifdef ESC_SENSOR_UART
{ ESC_SENSOR_UART, FUNCTION_ESC_SENSOR },
#else
{ SERIAL_PORT_NONE, FUNCTION_NONE },

View File

@ -237,12 +237,10 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define SERIALRX_UART SERIAL_PORT_USART6
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define ESC_SENSOR_UART SERIAL_PORT_USART1
#else
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SERIALRX_UART SERIAL_PORT_USART2
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define ESC_SENSOR_UART SERIAL_PORT_USART7
#endif
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -69,7 +69,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PA3

View File

@ -194,7 +194,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -128,7 +128,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -115,12 +115,10 @@
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_9
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC

View File

@ -138,10 +138,6 @@
#define DEFIO_NO_PORTS // suppress 'no pins defined' warning
#define WS2811_DMA_TC_FLAG (void *)1
#define WS2811_DMA_HANDLER_IDENTIFER 0
// belows are internal stuff
extern uint32_t SystemCoreClock;

View File

@ -83,7 +83,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View File

@ -169,15 +169,6 @@
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC0
#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 WS2811_TIMER_GPIO_AF GPIO_AF_6
#define USE_TRANSPONDER
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View File

@ -82,7 +82,7 @@
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART4, USART6
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define ESCSERIAL_TIMER_TX_PIN PB9
//SPI
#define USE_SPI
@ -108,7 +108,6 @@
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC2

View File

@ -115,13 +115,6 @@
#define CURRENT_METER_SCALE_DEFAULT (0.005 * 0.001 * 30000) * 1000 * 10 * (CURRENT_TARGET_CPU_VOLTAGE / 3.3)
#define CURRENT_METER_OFFSET_DEFAULT 0
#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_SERIAL
#define DEFAULT_FEATURES ( FEATURE_TELEMETRY )
#define USE_TARGET_CONFIG

View File

@ -38,12 +38,13 @@
#define GYRO_1_SPI_INSTANCE SPI1
// TODO
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
#define GYRO_1_ALIGN CW180_DEG
#define ACC_1_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PE0
#define USE_GYRO_EXTI
#define GYRO_1_EXTI_PIN PE0
#define USE_MPU_DATA_READY_SIGNAL
#define USE_MAG
@ -82,7 +83,6 @@
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART2
#define UART2_RX_PIN PD6
@ -100,7 +100,7 @@
// TODO
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define ESCSERIAL_TIMER_TX_PIN PA2
#define USE_SPI
#define USE_SPI_DEVICE_1

View File

@ -89,7 +89,7 @@
#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART3, USART4, USART6
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define ESCSERIAL_TIMER_TX_PIN PB9
//SPI
#define USE_SPI
@ -111,7 +111,6 @@
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC1
//#define RSSI_ADC_PIN PC2
#define CURRENT_METER_ADC_PIN PC2

View File

@ -124,7 +124,7 @@
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define USE_ADC
#define RSSI_ADC_GPIO_PIN PC0
#define RSSI_ADC_PIN PC0
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 150

View File

@ -40,11 +40,11 @@
#define SPI1_MOSI_PIN PA7
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO_EXTI
#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
// ICM 20689
#define GYRO_1_CS_PIN PA4
#define GYRO_1_SPI_INSTANCE SPI1
@ -126,7 +126,7 @@
// *************** ADC *****************************
#define USE_ADC
#define ADC1_DMA_STREAM DMA2_Stream0
#define RSSI_ADC_GPIO_PIN PC0
#define RSSI_ADC_PIN PC0
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 235

View File

@ -257,3 +257,15 @@
#else
#define MAX_GYRODEV_COUNT 1
#endif
#ifdef USE_VCP
#ifndef USB_DETECT_PIN
#define USB_DETECT_PIN NONE
#endif
#ifndef USB_MSC_BUTTON_PIN
#define USB_MSC_BUTTON_PIN NONE
#endif
#if !defined(MSC_BUTTON_IPU)
#define MSC_BUTTON_IPU true
#endif
#endif

View File

@ -398,5 +398,6 @@ portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunctio
failsafePhase_e failsafePhase(void) {return FAILSAFE_IDLE;}
bool rxAreFlightChannelsValid(void) {return false;}
bool rxIsReceivingSignal(void) {return false;}
bool isRssiConfigured(void) {return false;}
}