mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
Merge branch 'master' into serial-cleanup
Conflicts: src/main/telemetry/hott.c
This commit is contained in:
commit
dca984ff88
10 changed files with 47 additions and 36 deletions
14
.travis.yml
14
.travis.yml
|
@ -1,7 +1,7 @@
|
||||||
env:
|
env:
|
||||||
- RUNTESTS=True
|
- RUNTESTS=True
|
||||||
- TARGET=CC3D
|
- TARGET=CC3D
|
||||||
- TARGET=CC3D OPBL=yes
|
- TARGET=CC3D OPBL=yes
|
||||||
- TARGET=CHEBUZZF3
|
- TARGET=CHEBUZZF3
|
||||||
- TARGET=CJMCU
|
- TARGET=CJMCU
|
||||||
- TARGET=EUSTM32F103RC
|
- TARGET=EUSTM32F103RC
|
||||||
|
@ -17,8 +17,16 @@ env:
|
||||||
# We use cpp for unit tests, and c for the main project.
|
# We use cpp for unit tests, and c for the main project.
|
||||||
language: cpp
|
language: cpp
|
||||||
compiler: clang
|
compiler: clang
|
||||||
before_install: sudo add-apt-repository -y ppa:terry.guo/gcc-arm-embedded && sudo apt-get update
|
|
||||||
install: sudo apt-get install build-essential gcc-arm-none-eabi git
|
before_install:
|
||||||
|
- sudo apt-get update
|
||||||
|
- wget "https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q3-update/+download/gcc-arm-none-eabi-4_8-2014q3-20140805-linux.tar.bz2"
|
||||||
|
|
||||||
|
install:
|
||||||
|
- sudo apt-get install build-essential git libc6-i386
|
||||||
|
- tar -xf gcc-arm-none-eabi-4_8-2014q3-20140805-linux.tar.bz2
|
||||||
|
- export PATH=$PATH:$PWD/gcc-arm-none-eabi-4_8-2014q3/bin
|
||||||
|
|
||||||
before_script: arm-none-eabi-gcc --version
|
before_script: arm-none-eabi-gcc --version
|
||||||
script: ./.travis.sh
|
script: ./.travis.sh
|
||||||
|
|
||||||
|
|
3
Makefile
3
Makefile
|
@ -374,6 +374,7 @@ endif
|
||||||
|
|
||||||
ifeq ($(OPBL),yes)
|
ifeq ($(OPBL),yes)
|
||||||
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
||||||
|
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k_opbl.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k_opbl.ld
|
||||||
.DEFAULT_GOAL := binary
|
.DEFAULT_GOAL := binary
|
||||||
else
|
else
|
||||||
|
@ -430,6 +431,8 @@ CC3D_SRC = \
|
||||||
drivers/system_stm32f10x.c \
|
drivers/system_stm32f10x.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
drivers/timer_stm32f10x.c \
|
drivers/timer_stm32f10x.c \
|
||||||
|
drivers/flash_m25p16.c \
|
||||||
|
io/flashfs.c \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC) \
|
$(COMMON_SRC) \
|
||||||
$(VCP_SRC)
|
$(VCP_SRC)
|
||||||
|
|
|
@ -121,9 +121,9 @@ tubing instead.
|
||||||

|

|
||||||
|
|
||||||
### Onboard dataflash storage
|
### Onboard dataflash storage
|
||||||
The full version of the Naze32 has an onboard "m25p16" 2 megayte dataflash storage chip which can be used to store
|
The full version of the Naze32 and the CC3D have an onboard "m25p16" 2 megayte dataflash storage chip which can be used
|
||||||
flight logs instead of using an OpenLog. This is the small chip at the base of the Naze32's direction arrow.
|
to store flight logs instead of using an OpenLog. This is a small chip with 8 fat legs, which can be found at the base
|
||||||
This chip is not present on the "Acro" version of the Naze32.
|
of the Naze32's direction arrow. This chip is not present on the "Acro" version of the Naze32.
|
||||||
|
|
||||||
## Enabling the Blackbox (CLI)
|
## Enabling the Blackbox (CLI)
|
||||||
In the [Cleanflight Configurator][] , enter the CLI tab. Enable the Blackbox feature by typing in `feature BLACKBOX` and
|
In the [Cleanflight Configurator][] , enter the CLI tab. Enable the Blackbox feature by typing in `feature BLACKBOX` and
|
||||||
|
|
|
@ -237,7 +237,7 @@ bool spiInit(SPI_TypeDef *instance)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_SPI_DEVICE_2
|
#ifdef USE_SPI_DEVICE_2
|
||||||
if (instance == SPI1) {
|
if (instance == SPI2) {
|
||||||
initSpi2();
|
initSpi2();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -270,7 +270,9 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
||||||
firstPeakAngle = currentAngle;
|
firstPeakAngle = currentAngle;
|
||||||
targetAngleAtPeak = targetAngle;
|
targetAngleAtPeak = targetAngle;
|
||||||
|
|
||||||
|
#ifdef DEBUG_AUTOTUNE
|
||||||
debug[3] = DEGREES_TO_DECIDEGREES(firstPeakAngle);
|
debug[3] = DEGREES_TO_DECIDEGREES(firstPeakAngle);
|
||||||
|
#endif
|
||||||
|
|
||||||
} else if (firstPeakAngle > 0) {
|
} else if (firstPeakAngle > 0) {
|
||||||
switch (cycle) {
|
switch (cycle) {
|
||||||
|
@ -320,7 +322,9 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
||||||
|
|
||||||
if (currentAngle < secondPeakAngle) {
|
if (currentAngle < secondPeakAngle) {
|
||||||
secondPeakAngle = currentAngle;
|
secondPeakAngle = currentAngle;
|
||||||
|
#ifdef DEBUG_AUTOTUNE
|
||||||
debug[3] = DEGREES_TO_DECIDEGREES(secondPeakAngle);
|
debug[3] = DEGREES_TO_DECIDEGREES(secondPeakAngle);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
float oscillationAmplitude = firstPeakAngle - secondPeakAngle;
|
float oscillationAmplitude = firstPeakAngle - secondPeakAngle;
|
||||||
|
@ -395,9 +399,11 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef DEBUG_AUTOTUNE
|
||||||
if (angleIndex == AI_ROLL) {
|
if (angleIndex == AI_ROLL) {
|
||||||
debug[0] += 100;
|
debug[0] += 100;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
updateTargetAngle();
|
updateTargetAngle();
|
||||||
|
|
||||||
|
|
|
@ -392,7 +392,7 @@ void init(void)
|
||||||
m25p16_init();
|
m25p16_init();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef SPRACINGF3
|
#if defined(SPRACINGF3) || defined(CC3D)
|
||||||
m25p16_init();
|
m25p16_init();
|
||||||
#endif
|
#endif
|
||||||
flashfsInit();
|
flashfsInit();
|
||||||
|
|
|
@ -50,7 +50,7 @@
|
||||||
#define SBUS_TIME_NEEDED_PER_FRAME 3000
|
#define SBUS_TIME_NEEDED_PER_FRAME 3000
|
||||||
|
|
||||||
#ifndef CJMCU
|
#ifndef CJMCU
|
||||||
#define DEBUG_SBUS_PACKETS
|
//#define DEBUG_SBUS_PACKETS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEBUG_SBUS_PACKETS
|
#ifdef DEBUG_SBUS_PACKETS
|
||||||
|
|
|
@ -35,6 +35,13 @@
|
||||||
#define MPU6000_CS_PIN GPIO_Pin_4
|
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
|
#define M25P16_CS_GPIO GPIOB
|
||||||
|
#define M25P16_CS_PIN GPIO_Pin_12
|
||||||
|
#define M25P16_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
|
#define USE_FLASHFS
|
||||||
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
|
@ -97,7 +104,6 @@
|
||||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||||
|
|
||||||
|
|
||||||
#define GPS
|
#define GPS
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define LED_STRIP_TIMER TIM3
|
#define LED_STRIP_TIMER TIM3
|
||||||
|
@ -108,6 +114,10 @@
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
#define USE_SERVOS
|
#define USE_SERVOS
|
||||||
|
|
||||||
|
#if defined(OPBL)
|
||||||
|
#undef AUTOTUNE // disabled for OPBL build due to code size.
|
||||||
|
#endif
|
||||||
|
|
||||||
#define SPEKTRUM_BIND
|
#define SPEKTRUM_BIND
|
||||||
// USART3, PB11 (Flexport)
|
// USART3, PB11 (Flexport)
|
||||||
#define BIND_PORT GPIOB
|
#define BIND_PORT GPIOB
|
||||||
|
|
|
@ -113,8 +113,6 @@ static portSharing_e hottPortSharing;
|
||||||
static HOTT_GPS_MSG_t hottGPSMessage;
|
static HOTT_GPS_MSG_t hottGPSMessage;
|
||||||
static HOTT_EAM_MSG_t hottEAMMessage;
|
static HOTT_EAM_MSG_t hottEAMMessage;
|
||||||
|
|
||||||
static bool useSoftserialRxFailureWorkaround = false;
|
|
||||||
|
|
||||||
static void initialiseEAMMessage(HOTT_EAM_MSG_t *msg, size_t size)
|
static void initialiseEAMMessage(HOTT_EAM_MSG_t *msg, size_t size)
|
||||||
{
|
{
|
||||||
memset(msg, 0, size);
|
memset(msg, 0, size);
|
||||||
|
@ -280,16 +278,6 @@ void configureHoTTTelemetryPort(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_SOFTSERIAL1
|
|
||||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL1) {
|
|
||||||
useSoftserialRxFailureWorkaround = true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#ifdef USE_SOFTSERIAL2
|
|
||||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL2) {
|
|
||||||
useSoftserialRxFailureWorkaround = true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
hottTelemetryEnabled = true;
|
hottTelemetryEnabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -372,18 +360,6 @@ static void hottCheckSerialData(uint32_t currentMicros)
|
||||||
|
|
||||||
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
|
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
|
||||||
|
|
||||||
if (useSoftserialRxFailureWorkaround) {
|
|
||||||
// FIXME The 0x80 is being read as 0x00 - softserial timing/syncronisation problem somewhere.
|
|
||||||
if (!bytesWaiting) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t incomingByte = serialRead(hottPort);
|
|
||||||
processBinaryModeRequest(incomingByte);
|
|
||||||
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (bytesWaiting <= 1) {
|
if (bytesWaiting <= 1) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -410,7 +386,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
|
||||||
uint8_t requestId = serialRead(hottPort);
|
uint8_t requestId = serialRead(hottPort);
|
||||||
uint8_t address = serialRead(hottPort);
|
uint8_t address = serialRead(hottPort);
|
||||||
|
|
||||||
if (requestId == HOTT_BINARY_MODE_REQUEST_ID) {
|
if ((requestId == 0) || (requestId == HOTT_BINARY_MODE_REQUEST_ID) || (address == HOTT_TELEMETRY_NO_SENSOR_ID)) {
|
||||||
processBinaryModeRequest(address);
|
processBinaryModeRequest(address);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -190,7 +190,7 @@ void serialSetMode(serialPort_t *instance, portMode_t mode) {
|
||||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, baudRate_e baudRateIndex, portMode_t mode, serialInversion_e inversion) {
|
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, baudRate_e baudRateIndex, portMode_t mode, serialInversion_e inversion) {
|
||||||
UNUSED(identifier);
|
UNUSED(identifier);
|
||||||
UNUSED(functionMask);
|
UNUSED(functionMask);
|
||||||
UNUSED(baudRate);
|
UNUSED(baudRateIndex);
|
||||||
UNUSED(callback);
|
UNUSED(callback);
|
||||||
UNUSED(mode);
|
UNUSED(mode);
|
||||||
UNUSED(inversion);
|
UNUSED(inversion);
|
||||||
|
@ -213,5 +213,13 @@ bool sensors(uint32_t mask) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool determineNewTelemetryEnabledState(portSharing_e) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e) {
|
||||||
|
return PORTSHARING_NOT_SHARED;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue