mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 08:15:26 +03:00
Merge remote-tracking branch 'origin/development' into failsafe-stage1-mods
This commit is contained in:
commit
6802606724
53 changed files with 498 additions and 283 deletions
|
@ -63,6 +63,8 @@ elif [ $TARGET ] ; then
|
|||
else
|
||||
make -j2 $MAKEFILE
|
||||
fi
|
||||
elif [ $GOAL ] ; then
|
||||
make V=0 $GOAL
|
||||
else
|
||||
# No target specified, build all with very low verbosity.
|
||||
make V=0 all
|
||||
|
|
26
.travis.yml
26
.travis.yml
|
@ -1,16 +1,9 @@
|
|||
env:
|
||||
# Specify the main Mafile supported goals.
|
||||
- GOAL=test
|
||||
- GOAL=all
|
||||
# - TARGET=CC3D
|
||||
# - TARGET=CJMCU
|
||||
# - TARGET=NAZE
|
||||
# - TARGET=STM32F3DISCOVERY
|
||||
# - TARGET=RMDO
|
||||
# - TARGET=SPRACINGF3
|
||||
# - TARGET=SPRACINGF3EVO
|
||||
# - TARGET=SPARKY
|
||||
# - TARGET=FURYF3
|
||||
# - TARGET=RCEXPLORERF3
|
||||
# - TARGET=REVO
|
||||
|
||||
|
||||
# use new docker environment
|
||||
sudo: false
|
||||
|
||||
|
@ -28,12 +21,17 @@ addons:
|
|||
language: cpp
|
||||
compiler: clang
|
||||
|
||||
before_install: ./install-toolchain.sh
|
||||
before_install:
|
||||
|
||||
install:
|
||||
- export PATH=$PATH:$PWD/gcc-arm-none-eabi-6_2-2016q4/bin
|
||||
- ./install-toolchain.sh
|
||||
- export TOOLCHAINPATH=$PWD/gcc-arm-none-eabi-6_2-2016q4/bin
|
||||
|
||||
before_script:
|
||||
- $TOOLCHAINPATH/arm-none-eabi-gcc --version
|
||||
- clang --version
|
||||
- clang++ --version
|
||||
|
||||
before_script: arm-none-eabi-gcc --version
|
||||
script: ./.travis.sh
|
||||
|
||||
cache:
|
||||
|
|
34
Makefile
34
Makefile
|
@ -506,18 +506,18 @@ COMMON_SRC = \
|
|||
drivers/stack_check.c \
|
||||
drivers/system.c \
|
||||
drivers/timer.c \
|
||||
fc/cli.c \
|
||||
fc/config.c \
|
||||
fc/controlrate_profile.c \
|
||||
fc/fc_core.c \
|
||||
fc/fc_init.c \
|
||||
fc/fc_tasks.c \
|
||||
fc/fc_hardfaults.c \
|
||||
fc/fc_msp.c \
|
||||
fc/mw.c \
|
||||
fc/rc_adjustments.c \
|
||||
fc/rc_controls.c \
|
||||
fc/rc_curves.c \
|
||||
fc/runtime_config.c \
|
||||
fc/serial_cli.c \
|
||||
flight/failsafe.c \
|
||||
flight/hil.c \
|
||||
flight/imu.c \
|
||||
|
@ -571,16 +571,10 @@ HIGHEND_SRC = \
|
|||
cms/cms_menu_misc.c \
|
||||
cms/cms_menu_osd.c \
|
||||
common/colorconversion.c \
|
||||
common/gps_conversion.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sonar_srf10.c \
|
||||
flight/navigation_rewrite.c \
|
||||
flight/navigation_rewrite_multicopter.c \
|
||||
flight/navigation_rewrite_fixedwing.c \
|
||||
flight/navigation_rewrite_fw_launch.c \
|
||||
flight/navigation_rewrite_pos_estimator.c \
|
||||
flight/navigation_rewrite_geo.c \
|
||||
flight/gps_conversion.c \
|
||||
io/dashboard.c \
|
||||
io/displayport_max7456.c \
|
||||
io/displayport_msp.c \
|
||||
|
@ -592,6 +586,12 @@ HIGHEND_SRC = \
|
|||
io/gps_i2cnav.c \
|
||||
io/ledstrip.c \
|
||||
io/osd.c \
|
||||
navigation/navigation.c \
|
||||
navigation/navigation_fixedwing.c \
|
||||
navigation/navigation_fw_launch.c \
|
||||
navigation/navigation_geo.c \
|
||||
navigation/navigation_multicopter.c \
|
||||
navigation/navigation_pos_estimator.c \
|
||||
sensors/barometer.c \
|
||||
sensors/pitotmeter.c \
|
||||
sensors/rangefinder.c \
|
||||
|
@ -743,9 +743,15 @@ VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
|||
#
|
||||
|
||||
# Tool names
|
||||
CC = arm-none-eabi-gcc
|
||||
ifneq ($(TOOLCHAINPATH),)
|
||||
CROSS_CC = $(TOOLCHAINPATH)/arm-none-eabi-gcc
|
||||
OBJCOPY = $(TOOLCHAINPATH)/arm-none-eabi-objcopy
|
||||
SIZE = $(TOOLCHAINPATH)/arm-none-eabi-size
|
||||
else
|
||||
CROSS_CC = arm-none-eabi-gcc
|
||||
OBJCOPY = arm-none-eabi-objcopy
|
||||
SIZE = arm-none-eabi-size
|
||||
endif
|
||||
|
||||
#
|
||||
# Tool options.
|
||||
|
@ -838,25 +844,25 @@ $(TARGET_BIN): $(TARGET_ELF)
|
|||
|
||||
$(TARGET_ELF): $(TARGET_OBJS)
|
||||
$(V1) echo Linking $(TARGET)
|
||||
$(V1) $(CC) -o $@ $^ $(LDFLAGS)
|
||||
$(V1) $(CROSS_CC) -o $@ $^ $(LDFLAGS)
|
||||
$(V0) $(SIZE) $(TARGET_ELF)
|
||||
|
||||
# Compile
|
||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.c
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo %% $(notdir $<) "$(STDOUT)"
|
||||
$(V1) $(CC) -c -o $@ $(CFLAGS) $<
|
||||
$(V1) $(CROSS_CC) -c -o $@ $(CFLAGS) $<
|
||||
|
||||
# Assemble
|
||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.s
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo %% $(notdir $<) "$(STDOUT)"
|
||||
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
|
||||
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||
|
||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.S
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo %% $(notdir $<) "$(STDOUT)"
|
||||
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
|
||||
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||
|
||||
|
||||
## all : Build all valid targets
|
||||
|
|
|
@ -23,6 +23,10 @@
|
|||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
@ -31,32 +35,29 @@
|
|||
#include "common/encoding.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
|
@ -64,24 +65,23 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#ifdef ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
|
||||
|
|
|
@ -19,16 +19,21 @@
|
|||
#include <stdarg.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/encoding.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/streambuf.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
|
@ -42,17 +47,18 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -61,25 +67,20 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/msp.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/flashfs.h"
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
|
||||
|
||||
|
|
|
@ -35,12 +35,13 @@
|
|||
#include "common/axis.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
|
||||
|
|
|
@ -91,28 +91,27 @@ void initEEPROM(void)
|
|||
BUILD_BUG_ON(sizeof(configRecord_t) != 6);
|
||||
}
|
||||
|
||||
static uint8_t updateChecksum(uint8_t chk, const void *data, uint32_t length)
|
||||
static uint16_t updateCRC(uint16_t crc, const void *data, uint32_t length)
|
||||
{
|
||||
const uint8_t *p = (const uint8_t *)data;
|
||||
const uint8_t *pend = p + length;
|
||||
|
||||
for (; p != pend; p++) {
|
||||
chk ^= *p;
|
||||
crc = crc16_ccitt(crc, *p);
|
||||
}
|
||||
return chk;
|
||||
return crc;
|
||||
}
|
||||
|
||||
// Scan the EEPROM config. Returns true if the config is valid.
|
||||
bool isEEPROMContentValid(void)
|
||||
{
|
||||
uint8_t chk = 0;
|
||||
const uint8_t *p = &__config_start;
|
||||
const configHeader_t *header = (const configHeader_t *)p;
|
||||
|
||||
if (header->format != EEPROM_CONF_VERSION) {
|
||||
return false;
|
||||
}
|
||||
chk = updateChecksum(chk, header, sizeof(*header));
|
||||
uint16_t crc = updateCRC(0, header, sizeof(*header));
|
||||
p += sizeof(*header);
|
||||
|
||||
for (;;) {
|
||||
|
@ -128,19 +127,18 @@ bool isEEPROMContentValid(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
chk = updateChecksum(chk, p, record->size);
|
||||
crc = updateCRC(crc, p, record->size);
|
||||
|
||||
p += record->size;
|
||||
}
|
||||
|
||||
const configFooter_t *footer = (const configFooter_t *)p;
|
||||
chk = updateChecksum(chk, footer, sizeof(*footer));
|
||||
crc = updateCRC(crc, footer, sizeof(*footer));
|
||||
p += sizeof(*footer);
|
||||
chk = ~chk;
|
||||
const uint8_t checkSum = *p;
|
||||
const uint16_t checkSum = *(uint16_t *)p;
|
||||
p += sizeof(checkSum);
|
||||
eepromConfigSize = p - &__config_start;
|
||||
return chk == checkSum;
|
||||
return crc == checkSum;
|
||||
}
|
||||
|
||||
uint16_t getEEPROMConfigSize(void)
|
||||
|
@ -204,14 +202,13 @@ static bool writeSettingsToEEPROM(void)
|
|||
config_streamer_init(&streamer);
|
||||
|
||||
config_streamer_start(&streamer, (uintptr_t)&__config_start, &__config_end - &__config_start);
|
||||
uint8_t chk = 0;
|
||||
|
||||
configHeader_t header = {
|
||||
.format = EEPROM_CONF_VERSION,
|
||||
};
|
||||
|
||||
config_streamer_write(&streamer, (uint8_t *)&header, sizeof(header));
|
||||
chk = updateChecksum(chk, (uint8_t *)&header, sizeof(header));
|
||||
uint16_t crc = updateCRC(0, (uint8_t *)&header, sizeof(header));
|
||||
PG_FOREACH(reg) {
|
||||
const uint16_t regSize = pgSize(reg);
|
||||
configRecord_t record = {
|
||||
|
@ -225,9 +222,9 @@ static bool writeSettingsToEEPROM(void)
|
|||
// write the only instance
|
||||
record.flags |= CR_CLASSICATION_SYSTEM;
|
||||
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
|
||||
chk = updateChecksum(chk, (uint8_t *)&record, sizeof(record));
|
||||
crc = updateCRC(crc, (uint8_t *)&record, sizeof(record));
|
||||
config_streamer_write(&streamer, reg->address, regSize);
|
||||
chk = updateChecksum(chk, reg->address, regSize);
|
||||
crc = updateCRC(crc, reg->address, regSize);
|
||||
} else {
|
||||
// write one instance for each profile
|
||||
for (uint8_t profileIndex = 0; profileIndex < MAX_PROFILE_COUNT; profileIndex++) {
|
||||
|
@ -235,10 +232,10 @@ static bool writeSettingsToEEPROM(void)
|
|||
|
||||
record.flags |= ((profileIndex + 1) & CR_CLASSIFICATION_MASK);
|
||||
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
|
||||
chk = updateChecksum(chk, (uint8_t *)&record, sizeof(record));
|
||||
crc = updateCRC(crc, (uint8_t *)&record, sizeof(record));
|
||||
const uint8_t *address = reg->address + (regSize * profileIndex);
|
||||
config_streamer_write(&streamer, address, regSize);
|
||||
chk = updateChecksum(chk, address, regSize);
|
||||
crc = updateCRC(crc, address, regSize);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -248,11 +245,10 @@ static bool writeSettingsToEEPROM(void)
|
|||
};
|
||||
|
||||
config_streamer_write(&streamer, (uint8_t *)&footer, sizeof(footer));
|
||||
chk = updateChecksum(chk, (uint8_t *)&footer, sizeof(footer));
|
||||
crc = updateCRC(crc, (uint8_t *)&footer, sizeof(footer));
|
||||
|
||||
// append checksum now
|
||||
chk = ~chk;
|
||||
config_streamer_write(&streamer, &chk, sizeof(chk));
|
||||
config_streamer_write(&streamer, (uint8_t *)&crc, sizeof(crc));
|
||||
|
||||
config_streamer_flush(&streamer);
|
||||
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "accgyro.h"
|
||||
|
||||
bool fakeAccDetect(accDev_t *acc);
|
||||
void fakeAccSet(int16_t x, int16_t y, int16_t z);
|
||||
|
||||
|
|
|
@ -65,17 +65,16 @@ extern uint8_t __config_end;
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "fc/cli.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_adjustments.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/serial_cli.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -88,6 +87,8 @@ extern uint8_t __config_end;
|
|||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
|
@ -22,6 +22,7 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -62,7 +63,6 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -71,7 +71,7 @@
|
|||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#ifndef DEFAULT_RX_FEATURE
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
|
||||
|
@ -429,6 +429,8 @@ static void activateConfig(void)
|
|||
activateControlRateConfig();
|
||||
|
||||
resetAdjustmentStates();
|
||||
|
||||
useRcControlsConfig();
|
||||
|
||||
failsafeReset();
|
||||
|
||||
|
|
|
@ -45,13 +45,13 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "fc/cli.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_adjustments.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/serial_cli.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/dashboard.h"
|
||||
|
@ -63,6 +63,8 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
|
@ -74,8 +76,8 @@
|
|||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
|
@ -67,11 +67,11 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
||||
#include "fc/cli.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/fc_msp.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/serial_cli.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -87,6 +87,8 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
|
@ -110,7 +112,6 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -53,7 +53,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/hil.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -73,6 +72,8 @@
|
|||
#include "msp/msp_protocol.h"
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
|
|
|
@ -33,13 +33,13 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/stack_check.h"
|
||||
|
||||
#include "fc/cli.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/fc_msp.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/mw.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/serial_cli.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
|
|
|
@ -37,18 +37,19 @@
|
|||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/mw.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
|
|
|
@ -39,9 +39,10 @@
|
|||
#include "fc/controlrate_profile.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
/*
|
||||
|
|
|
@ -21,11 +21,12 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#ifdef HIL
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -40,13 +41,13 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/hil.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#ifdef HIL
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
bool hilActive = false;
|
||||
hilIncomingStateData_t hilToFC;
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
|
@ -35,6 +36,8 @@
|
|||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -50,9 +53,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
//#define MIXER_DEBUG
|
||||
|
||||
|
|
|
@ -39,10 +39,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -31,9 +31,10 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/config_reset.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
@ -41,6 +42,8 @@
|
|||
|
||||
#include "io/gimbal.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -56,9 +59,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
||||
extern const mixer_t mixers[];
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/dashboard.h"
|
||||
#include "io/displayport_oled.h"
|
||||
|
@ -54,6 +53,8 @@
|
|||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
|
@ -34,18 +35,19 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/hil.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/hil.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
|
||||
#define GPS_I2C_POLL_RATE_HZ 20 // Poll I2C GPS at this rate
|
||||
|
||||
bool gpsDetectI2CNAV(void)
|
||||
|
|
|
@ -29,22 +29,21 @@
|
|||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
|
||||
#define NAZA_MAX_PAYLOAD_SIZE 256
|
||||
|
||||
|
|
|
@ -28,22 +28,21 @@
|
|||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
/* This is a light implementation of a GPS frame decoding
|
||||
This should work with most of modern GPS devices configured to output 5 frames.
|
||||
It assumes there are some NMEA GGA frames to decode on the serial bus
|
||||
|
|
|
@ -31,21 +31,21 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
//#define GPS_PROTO_UBLOX_NEO7PLUS
|
||||
#define GPS_VERSION_DETECTION_TIMEOUT_MS 300
|
||||
|
|
|
@ -27,11 +27,14 @@
|
|||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/typeconversion.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
|
@ -39,14 +42,25 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/barometer.h"
|
||||
|
@ -56,24 +70,8 @@
|
|||
#include "sensors/sensors.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
extern uint16_t rssi; // FIXME dependency on mw.c
|
||||
|
||||
|
|
|
@ -68,10 +68,11 @@
|
|||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "fc/serial_cli.h"
|
||||
#include "fc/cli.h"
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
|
|
|
@ -34,21 +34,23 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Compatibility for home position
|
|
@ -39,14 +39,15 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
// If we are going slower than NAV_FW_MIN_VEL_SPEED_BOOST - boost throttle to fight against the wind
|
||||
#define NAV_FW_THROTTLE_SPEED_BOOST_GAIN 1.5f
|
||||
#define NAV_FW_MIN_VEL_SPEED_BOOST 700.0f // 7 m/s
|
|
@ -30,6 +30,8 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
@ -47,14 +49,13 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
typedef struct FixedWingLaunchState_s {
|
|
@ -36,12 +36,14 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
#if defined(NAV_AUTO_MAG_DECLINATION)
|
||||
/* Declination calculation code from PX4 project */
|
||||
/* set this always to the sampling in degrees for the table below */
|
|
@ -43,11 +43,13 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Altitude controller for multicopter aircraft
|
||||
*-----------------------------------------------------------*/
|
|
@ -40,12 +40,13 @@
|
|||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
|
@ -22,6 +22,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
@ -65,9 +67,9 @@
|
|||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
gyro_t gyro; // gyro access functions
|
||||
gyro_t gyro; // gyro sensor object
|
||||
|
||||
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
|
||||
STATIC_UNIT_TESTED int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
|
||||
|
||||
static uint16_t calibratingG = 0;
|
||||
|
||||
|
@ -99,6 +101,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
|||
.gyro_soft_notch_cutoff_2 = 1
|
||||
);
|
||||
|
||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050)
|
||||
static const extiConfig_t *selectMPUIntExtiConfig(void)
|
||||
{
|
||||
#if defined(MPU_INT_EXTI)
|
||||
|
@ -110,8 +113,9 @@ static const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
return NULL;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
static bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig)
|
||||
STATIC_UNIT_TESTED bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig)
|
||||
{
|
||||
dev->mpuIntExtiConfig = extiConfig;
|
||||
|
||||
|
@ -228,6 +232,8 @@ bool gyroInit(void)
|
|||
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
|
||||
mpuDetect(&gyro.dev);
|
||||
mpuReset = gyro.dev.mpuConfiguration.reset;
|
||||
#else
|
||||
const extiConfig_t *extiConfig = NULL;
|
||||
#endif
|
||||
|
||||
if (!gyroDetect(&gyro.dev, extiConfig)) {
|
||||
|
@ -310,7 +316,7 @@ static bool isOnFirstGyroCalibrationCycle(void)
|
|||
return calibratingG == CALIBRATING_GYRO_CYCLES;
|
||||
}
|
||||
|
||||
static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThreshold)
|
||||
STATIC_UNIT_TESTED void performGyroCalibration(uint8_t gyroMovementCalibrationThreshold)
|
||||
{
|
||||
static int32_t g[3];
|
||||
static stdev_t var[3];
|
||||
|
@ -363,7 +369,7 @@ void gyroUpdate(void)
|
|||
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
|
||||
|
||||
if (!gyroIsCalibrationComplete()) {
|
||||
performAcclerationCalibration(gyroConfig()->gyroMovementCalibrationThreshold);
|
||||
performGyroCalibration(gyroConfig()->gyroMovementCalibrationThreshold);
|
||||
}
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
|
|
|
@ -31,29 +31,30 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/frsky.h"
|
||||
|
|
|
@ -73,15 +73,16 @@
|
|||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/hott.h"
|
||||
|
||||
|
|
|
@ -32,20 +32,20 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/ibus.h"
|
||||
|
||||
#include "fc/mw.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
/*
|
||||
* iBus Telemetry is a half-duplex serial protocol. It shares 1 line for
|
||||
|
|
|
@ -47,36 +47,37 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/ltm.h"
|
||||
|
||||
|
||||
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
||||
#define LTM_CYCLETIME 100
|
||||
|
||||
|
|
|
@ -30,47 +30,46 @@
|
|||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/mavlink.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/mw.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
// mavlink library uses unnames unions that's causes GCC to complain if -Wpedantic is used
|
||||
// until this is resolved in mavlink library - ignore -Wpedantic for mavlink code
|
||||
|
|
|
@ -15,32 +15,34 @@
|
|||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/smartport.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
enum
|
||||
{
|
||||
|
|
|
@ -192,24 +192,24 @@ $(OBJECT_DIR)/maths_unittest : \
|
|||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : \
|
||||
$(USER_DIR)/flight/gps_conversion.c \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(OBJECT_DIR)/common/gps_conversion.o : \
|
||||
$(USER_DIR)/common/gps_conversion.c \
|
||||
$(USER_DIR)/common/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/gps_conversion.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o : \
|
||||
$(TEST_DIR)/gps_conversion_unittest.cc \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(USER_DIR)/common/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest : \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/common/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
|
@ -236,7 +236,7 @@ $(OBJECT_DIR)/telemetry_hott_unittest.o : \
|
|||
$(OBJECT_DIR)/telemetry_hott_unittest : \
|
||||
$(OBJECT_DIR)/telemetry/hott.o \
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/common/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
|
@ -577,6 +577,61 @@ $(OBJECT_DIR)/alignsensor_unittest : \
|
|||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/build/debug.o : \
|
||||
$(USER_DIR)/build/debug.c \
|
||||
$(USER_DIR)/build/debug.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/build/debug.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/drivers/gyro_sync.o : \
|
||||
$(USER_DIR)/drivers/gyro_sync.c \
|
||||
$(USER_DIR)/drivers/gyro_sync.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/gyro_sync.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/drivers/accgyro_fake.o : \
|
||||
$(USER_DIR)/drivers/accgyro_fake.c \
|
||||
$(USER_DIR)/drivers/accgyro_fake.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/accgyro_fake.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/sensors/gyro.o : \
|
||||
$(USER_DIR)/sensors/gyro.c \
|
||||
$(USER_DIR)/sensors/gyro.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/gyro.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/sensor_gyro_unittest.o : \
|
||||
$(TEST_DIR)/sensor_gyro_unittest.cc \
|
||||
$(USER_DIR)/sensors/gyro.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/sensor_gyro_unittest.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/sensor_gyro_unittest : \
|
||||
$(OBJECT_DIR)/build/debug.o \
|
||||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/common/filter.o \
|
||||
$(OBJECT_DIR)/drivers/gyro_sync.o \
|
||||
$(OBJECT_DIR)/drivers/accgyro_fake.o \
|
||||
$(OBJECT_DIR)/sensors/gyro.o \
|
||||
$(OBJECT_DIR)/sensors/boardalignment.o \
|
||||
$(OBJECT_DIR)/sensor_gyro_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
test: $(TESTS:%=test-%)
|
||||
|
||||
test-%: $(OBJECT_DIR)/%
|
||||
|
|
|
@ -37,6 +37,12 @@ typedef struct
|
|||
void* test;
|
||||
} TIM_TypeDef;
|
||||
|
||||
typedef enum {
|
||||
EXTI_Trigger_Rising = 0x08,
|
||||
EXTI_Trigger_Falling = 0x0C,
|
||||
EXTI_Trigger_Rising_Falling = 0x10
|
||||
} EXTITrigger_TypeDef;
|
||||
|
||||
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||
|
||||
typedef enum {TEST_IRQ = 0 } IRQn_Type;
|
||||
|
|
117
src/test/unit/sensor_gyro_unittest.cc
Normal file
117
src/test/unit/sensor_gyro_unittest.cc
Normal file
|
@ -0,0 +1,117 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <limits.h>
|
||||
#include <algorithm>
|
||||
|
||||
extern "C" {
|
||||
#include <platform.h>
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/utils.h"
|
||||
#include "drivers/accgyro_fake.h"
|
||||
#include "drivers/logging_codes.h"
|
||||
#include "io/beeper.h"
|
||||
#include "scheduler/scheduler.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
STATIC_UNIT_TESTED bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig);
|
||||
STATIC_UNIT_TESTED void performGyroCalibration(uint8_t gyroMovementCalibrationThreshold);
|
||||
extern int32_t gyroZero[XYZ_AXIS_COUNT];
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
TEST(SensorGyro, Detect)
|
||||
{
|
||||
const bool detected = gyroDetect(&gyro.dev, NULL);
|
||||
EXPECT_EQ(true, detected);
|
||||
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
|
||||
}
|
||||
|
||||
TEST(SensorGyro, Init)
|
||||
{
|
||||
gyroInit();
|
||||
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
|
||||
}
|
||||
|
||||
TEST(SensorGyro, Read)
|
||||
{
|
||||
gyroInit();
|
||||
fakeGyroSet(5, 6, 7);
|
||||
const bool read = gyro.dev.read(&gyro.dev);
|
||||
EXPECT_EQ(true, read);
|
||||
EXPECT_EQ(5, gyro.dev.gyroADCRaw[X]);
|
||||
EXPECT_EQ(6, gyro.dev.gyroADCRaw[Y]);
|
||||
EXPECT_EQ(7, gyro.dev.gyroADCRaw[Z]);
|
||||
}
|
||||
|
||||
TEST(SensorGyro, Calibrate)
|
||||
{
|
||||
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
||||
gyroInit();
|
||||
fakeGyroSet(5, 6, 7);
|
||||
const bool read = gyro.dev.read(&gyro.dev);
|
||||
EXPECT_EQ(true, read);
|
||||
gyro.gyroADC[X] = gyro.dev.gyroADCRaw[X];
|
||||
gyro.gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
|
||||
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
|
||||
EXPECT_EQ(5, gyro.gyroADC[X]);
|
||||
EXPECT_EQ(6, gyro.gyroADC[Y]);
|
||||
EXPECT_EQ(7, gyro.gyroADC[Z]);
|
||||
static const int gyroMovementCalibrationThreshold = 32;
|
||||
gyroZero[X] = 8;
|
||||
gyroZero[Y] = 9;
|
||||
gyroZero[Z] = 10;
|
||||
performGyroCalibration(gyroMovementCalibrationThreshold);
|
||||
EXPECT_EQ(0, gyroZero[X]);
|
||||
EXPECT_EQ(0, gyroZero[Y]);
|
||||
EXPECT_EQ(0, gyroZero[Z]);
|
||||
EXPECT_EQ(false, gyroIsCalibrationComplete());
|
||||
while (!gyroIsCalibrationComplete()) {
|
||||
performGyroCalibration(gyroMovementCalibrationThreshold);
|
||||
gyro.gyroADC[X] = gyro.dev.gyroADCRaw[X];
|
||||
gyro.gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
|
||||
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
|
||||
}
|
||||
EXPECT_EQ(5, gyroZero[X]);
|
||||
EXPECT_EQ(6, gyroZero[Y]);
|
||||
EXPECT_EQ(7, gyroZero[Z]);
|
||||
}
|
||||
|
||||
|
||||
// STUBS
|
||||
|
||||
extern "C" {
|
||||
|
||||
uint32_t micros(void) {return 0;}
|
||||
void beeper(beeperMode_e) {}
|
||||
uint8_t detectedSensors[] = { GYRO_NONE, ACC_NONE };
|
||||
void addBootlogEvent6(bootLogEventCode_e eventCode, uint16_t eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4)
|
||||
{UNUSED(eventCode);UNUSED(eventFlags);UNUSED(param1);UNUSED(param2);UNUSED(param3);UNUSED(param4);}
|
||||
timeDelta_t getGyroUpdateRate(void) {return gyro.targetLooptime;}
|
||||
void sensorsSet(uint32_t) {}
|
||||
void schedulerResetTaskStatistics(cfTaskId_e) {}
|
||||
}
|
|
@ -34,6 +34,7 @@
|
|||
#define LED_STRIP
|
||||
#define USE_SERVOS
|
||||
#define TRANSPONDER
|
||||
#define USE_FAKE_GYRO
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
|
|
|
@ -27,6 +27,7 @@ extern "C" {
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
@ -44,7 +45,6 @@ extern "C" {
|
|||
#include "telemetry/hott.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue