1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Merge branch 'master' into master

This commit is contained in:
c3n 2019-04-20 15:22:28 +02:00 committed by GitHub
commit 66f5c6e5db
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
111 changed files with 3306 additions and 623 deletions

View file

@ -17,17 +17,6 @@ All subsequent rules exclude F3 based targets:
3. For changes to existing targets, the change needs to be applied to both the 'legacy' format target definition in `src/main/target/` and a new Unified Target config in `unified_targets/configs/`. If no Unified Target configuration for the target exists, a new Unified Target configuration will have to be created and submitted alongside the proposed change.
## Important: Feature freeze / release candidate phase for Betaflight 4.0
From 01 Mar 2019 until the release of Betaflight 4.0.0 (scheduled for 01 Apr 2019), the project is in a 'feature freeze / release candidate' phase. This means:
1. Pull requests can still be submitted as normal. Comments / discussions will probably be slower than normal due to shifted priorities;
2. If your pull request is a fix for an existing bug, or an update for a single target that has a low risk of side effect for other targets, it will be reviewed, and if accepted merged into `master` for the 4.0 release;
3. All other pull requests will be scheduled for 4.1, and discussed / reviewed / merged into `master` after 4.0.0 has been released. Please keep in mind that this potentially means that you will have to rebase your changes if they are broken by bugfixes made for 4.0.
## Important considerations when opening a pull request:
1. Pull requests will only be accepted if they are opened against the `master` branch. Pull requests opened against other branches without prior consent from the maintainers will be closed;

140
HGLRCF405.config Normal file
View file

@ -0,0 +1,140 @@
# Betaflight / STM32F405 (S405) 4.0.0 Apr 3 2019 / 14:30:44 (22b9f3453) MSP API: 1.41
board_name HGLRCF405
manufacturer_id HGLR
# resources
resource BEEPER 1 B04
resource MOTOR 1 B00
resource MOTOR 2 B01
resource MOTOR 3 A03
resource MOTOR 4 B05
resource PPM 1 B08
resource LED_STRIP 1 B06
resource SERIAL_TX 1 A09
resource SERIAL_TX 2 A02
resource SERIAL_TX 3 B10
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 3 B11
resource SERIAL_RX 4 A01
resource SERIAL_RX 6 C07
resource I2C_SCL 1 B08
resource I2C_SDA 1 B09
resource LED 1 A08
resource SPI_SCK 1 A05
resource SPI_SCK 2 B13
resource SPI_SCK 3 C10
resource SPI_MISO 1 A06
resource SPI_MISO 2 B14
resource SPI_MISO 3 C11
resource SPI_MOSI 1 A07
resource SPI_MOSI 2 B15
resource SPI_MOSI 3 C12
resource ESCSERIAL 1 B08
resource CAMERA_CONTROL 1 B07
resource ADC_BATT 1 C02
resource ADC_RSSI 1 A00
resource ADC_CURR 1 C01
resource BARO_CS 1 B03
resource FLASH_CS 1 B12
resource OSD_CS 1 A15
resource GYRO_EXTI 1 C04
resource GYRO_CS 1 A04
resource GYRO_CS 2 C14
# timer
timer B00 1
timer B01 1
timer A03 0
timer B05 0
timer C08 1
timer C09 1
timer B06 0
timer B08 1
timer C06 1
timer C07 1
timer A09 0
timer A10 0
timer A01 1
timer A02 2
# dma
dma ADC 2 1
# ADC 2: DMA2 Stream 3 Channel 1
dma pin B00 0
# pin B00: DMA1 Stream 7 Channel 5
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin A03 1
# pin A03: DMA1 Stream 6 Channel 3
dma pin B05 0
# pin B05: DMA1 Stream 5 Channel 5
dma pin C08 0
# pin C08: DMA2 Stream 2 Channel 0
dma pin C09 0
# pin C09: DMA2 Stream 7 Channel 7
dma pin B06 0
# pin B06: DMA1 Stream 0 Channel 2
dma pin C06 0
# pin C06: DMA2 Stream 2 Channel 0
dma pin C07 0
# pin C07: DMA2 Stream 2 Channel 0
dma pin A09 0
# pin A09: DMA2 Stream 6 Channel 0
dma pin A10 0
# pin A10: DMA2 Stream 6 Channel 0
dma pin A01 0
# pin A01: DMA1 Stream 4 Channel 6
# master
set gyro_to_use = FIRST
set align_mag = DEFAULT
set mag_bustype = I2C
set mag_i2c_device = 1
set mag_i2c_address = 0
set mag_spi_device = 0
set baro_bustype = SPI
set baro_spi_device = 3
set baro_i2c_device = 0
set baro_i2c_address = 0
set rx_spi_bus = 0
set rx_spi_led_inversion = OFF
set adc_device = 2
set blackbox_device = SPIFLASH
set dshot_burst = OFF
set current_meter = ADC
set battery_meter = ADC
set ibata_scale = 400
set beeper_inversion = ON
set beeper_od = OFF
set beeper_frequency = 0
set sdcard_detect_inverted = OFF
set sdcard_mode = OFF
set sdcard_spi_bus = 0
set system_hse_mhz = 8
set max7456_clock = DEFAULT
set max7456_spi_bus = 3
set max7456_preinit_opu = OFF
set cc2500_spi_chip_detect = ON
set led_inversion = 0
set dashboard_i2c_bus = 1
set dashboard_i2c_addr = 60
set usb_msc_pin_pullup = ON
set flash_spi_bus = 2
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_i2cBus = 0
set gyro_1_i2c_address = 0
set gyro_1_sensor_align = CW180
set gyro_2_bustype = SPI
set gyro_2_spibus = 1
set gyro_2_i2cBus = 0
set gyro_2_i2c_address = 0
set gyro_2_sensor_align = CW0
set i2c1_pullup = OFF
set i2c1_overclock = ON
set i2c2_pullup = OFF
set i2c2_overclock = ON
set i2c3_pullup = OFF
set i2c3_overclock = ON

View file

@ -41,33 +41,11 @@ For this reason, and because the effort required to remove features from STM32F3
This does not mean that it won't be possible to use these flight controllers after this point in time - they will still work fine when used with the last release of 4.0, just as there are thousands of users who are still enjoying their STM32F1 based flight controllers with Betaflight 3.2.5. We will also strive to keep these versions supported in new releases of configurator, so that users still using these flight controllers will be able to configure them with the same configurator that they use to configure their STM32F4 and STM32F7 based boards.
### Betaflight 4.0
As you might have learned from the [Betaflight GitHub page](https://github.com/betaflight/betaflight), our next release will be 4.0. Betaflight 4.0 will be the culmination of years of work that started in 2016 with the introduction of remappable resources, and it will drastically change the way how Betaflight is built and distributed. To you as the user, not much in how you download and install the Betaflight firmware will change, but you will get some noticeable improvements:
- well have to spend less time on maintaining and releasing the firmware, meaning that well have more time to work on new and exciting features;
- manufacturers will have an easy way to release custom configurations for all of their boards and ready-to-fly (including RX setup and tuning) craft based on original Betaflight firmware - you will no longer be stuck on using old firmware, or recreating your configuration from scratch;
- the tinkerers amongst you will be able to share Betaflight firmware with your home built improvements amongst your friends without having to build and distribute separate targets for everybodys board.
*(These changes are planned for F4 and F7, F3s flash space limitations mean we wont be able to fit all of this in.)*
We are almost there with the implementation of these changes, but since they are quite complex, and getting almost there doesnt buy us much, we have decided that we need to take more time to complete them, make sure the way users can use the firmware still works as expected, and properly test the new firmware. For this reason we have decided to **postpone the planned release date for Betaflight to 01 April 2019**. We will keep doing monthly releases of Betaflight 3.5 with bugfixes and new / updated targets in the meantime.
To get the latest update from us, you can now also visit our webpage at <https://betaflight.com/>.
In addition to the drastic changes mentioned above, Betaflight 4.0 will have a number of other exciting new features and improvements:
- yet again improved flight performance;
- 'Launch control' mode;
- switchable profiles for the OSD layout.
## Events
| Date | Event |
| - | - |
| 01 March 2019 | Start of feature freeze / Release Candidate window for Betaflight 4.0 |
| 01 April 2019 | Planned [release](https://github.com/betaflight/betaflight/milestone/20) date for Betaflight 4.0 |
| 01 September 2019 | Planned [release](https://github.com/betaflight/betaflight/milestone/30) date for Betaflight 4.1 |
## Features

View file

@ -1,4 +1,4 @@
# Board - Elin F405
# Board - Elin F722
## Hardware Features
* MCU

View file

@ -0,0 +1,96 @@
# Board - FLYWOOF411
This board use the STM32F411CEU6 microcontroller and have the following features:
* The 16M byte SPI flash for data logging
* USB VCP and boot select button on board(for DFU)
* Stable voltage regulation,9V/1.5A DCDC BEC for VTX/camera etc.And could select 5v/9v with pad
* Serial LED interface(LED_STRIP)
* VBAT/CURR/RSSI sensors input
* Suppose IRC Tramp/smart audio/FPV Camera Control/FPORT/telemetry
* Supports SBus, Spektrum1024/2048, PPM. No external inverters required (built-in).
* Supports I2C device extend(baro/compass/OLED etc)
* Supports GPS
### All uarts have pad on board
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | -----| -----| ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PB7 | PB6 | FOR SBUS IN(inverter build in) |
| 2 | USART2 | PA3 | PA2| FOR VTX SM/IRC ETC |
### I2C with GPS port together.Use for BARO or compass etc
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | I2C1 | SDA | PB9 | with GPS outlet
| 2 | I2C1 | SCL | PB8 | with GPS outlet
### Buzzer/LED output
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | LED0 | LED | PC13 |
| 2 | BEEPER | BEE | PC14 |
### VBAT input with 1/10 divider ratio,Current signal input,Analog/digit RSSI input
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ----------| ------| ------------------------------------------------------------------------------------- |
| 1 | ADC1 | VBAT | PA0 | DMA2_Stream0
| 2 | ADC1 | CURR | PA1 | DMA2_Stream0
| 3 | ADC1 | RSSI | PB1 | DMA2_Stream0
### 8 Outputs, 1 PPM input
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ----------| ------| ------------------------------------------------------------------------------------- |
| 1 | TIM9_CH1 | PPM | PA2 | PPM
| 2 | TIM1_CH1 | OUPUT1 | PA8 | DMA2_Stream1
| 3 | TIM1_CH2 | OUPUT2 | PA9 | DMA2_Stream2
| 4 | TIM1_CH3 | OUPUT3 | PA10 | DMA2_Stream6
| 5 | TIM3_CH3 | OUPUT4 | PB0 | DMA1_Stream7
| 6 | TIM3_CH1 | OUPUT5 | PB4 | DMA1_Stream4
| 7 | TIM3_CH4 | ANY | PB1 | DMA1_Stream2
| 8 | TIM5_CH4 | ANY | PA3 | DMA1_Stream3
| 9 | TIM2_CH3 | CAM_C | PB10 | DMA1_Stream1
| 10 | TIM2_CH4 | LED | PB11 | DMA1_Stream6
### Gyro & ACC ICM20689
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI1 | SCK | PA5 |
| 2 | SPI1 | MISO | PA6 |
| 3 | SPI1 | MOSI | PA7 |
| 4 | SPI1 | CS | PA4 |
### OSD MAX7456
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI3 | SCK | PB13 |
| 2 | SPI3 | MISO | PB14 |
| 3 | SPI3 | MOSI | PB15 |
| 4 | SPI3 | CS | PB12 |
### 16Mbyte flash
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI3 | SCK | PB13 |
| 2 | SPI3 | MISO | PB14 |
| 3 | SPI3 | MOSI | PB15 |
| 4 | SPI3 | CS | PB2 |
### SWD
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | SWCLK | PAD |
| 2 | Ground | PAD |
| 3 | SWDIO | PAD |
| 4 | 3V3 | PAD |
* FLYWOO TECH

View file

@ -4,7 +4,7 @@ This is the new Nano FC from Airbot! With added features in comparison to the pr
## Features
* ICM20602 Gyro connected via SPI
* Onboard Barometer
* FPC port for Frsky RX
* STM32F405
* 16MByte of Flash connected via SPI
* 3-6s Lipo capable
@ -29,3 +29,8 @@ This is the new Nano FC from Airbot! With added features in comparison to the pr
| WS2812B LED | LED | | PA15 | |
| Buzzer | BZ-/BZ+ | | PC5 | |
| UART4 | RX3/TX3 | | PC11/10 | |
## Pinmap
![O4N7 Top](images/OMNIBUSF4NANOV7-TopSide.png)
![O4N7 Bottom](images/OMNIBUSF4NANOV7-BottomSide.png)

View file

@ -0,0 +1,101 @@
# Board - RUSHCORE7
The RUSHCORE7 described here:
This board use the STM32F722RET6 microcontroller and have the following features:
* High-performance and DSP with FPU, ARM Cortex-M7 MCU with 512 Kbytes Flash
* 216 MHz CPU,462 DMIPS/2.14 DMIPS/MHz (Dhrystone 2.1) and DSP instructions, Art Accelerator, L1 cache, SDRAM
* Support MPU6000 or ICM20602
* OSD on board
* The 16M byte SPI flash on board for data logging
* USB VCP and boot button on board(for DFU)
* BEC 5v/2A on board
* Serial LED (LED_STRIP)
* VBAT/CURR/RSSI sensors input
* Suppose IRC Tramp/smart audio/FPV Camera Control/FPORT/telemetry
* Supports SBus, Spektrum1024/2048, PPM etc
* Supports I2C device extend(baro/compass/OLED etc)
* Supports GPS
* More about: www.rushfpv.com
### Uarts
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | -----| -----| ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PB7 | PB6 | |
| 2 | USART2 | PA3 | PA2 | FOR SBUS IN(inverter build in)/PPM |
| 3 | USART3 | PC11 | PC10| |
| 4 | USART4 | PA1 | PA0 | PA0 FOR RSSI/FPORT/TEL etc |
| 5 | USART5 | PD2 | PC12| PC12 TRAMP/smart audio |
### I2C
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | I2C1 | SDA | PB9 |
| 2 | I2C1 | SCL | PB8 |
### Buzzer/LED output
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | LED0 | LED | PC13 |On board
| 2 | Buzzer | BEE | PB1 |
### VBAT input with 1/10 divider ratio,Current signal input,Analog/digit RSSI input
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ----------| ------| ------------------------------------------------------------------------------------- |
| 1 | ADC1 | VBAT | PC1 |
| 2 | ADC1 | CURR | PC3 |
| 3 | ADC1 | RSSI | PA0 |
### 9 Outputs
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ----------| ------| ------------------------------------------------------------------------------------- |
| 1 | TIM2_CH3 | PPM | PA2 | PPM/SBUS
| 2 | TIM8_CH3 | OUPUT1 | PC8 | DMA
| 3 | TIM8_CH1 | OUPUT2 | PC6 | DMA
| 4 | TIM8_CH4 | OUPUT3 | PC9 | DMA
| 5 | TIM8_CH2 | OUPUT4 | PC7 | DMA
| 6 | TIM1_CH1 | OUPUT5 | PA8 | DMA
| 7 | TIM1_CH2 | OUPUT6 | PA9 | DMA
| 8 | TIM2_CH4 | PWM | PB11 | DMA LED_STRIP
| 9 | TIM3_CH3 | PWM | PB0 | FPV Camera Control(FCAM)
### Gyro & ACC ,support ICM20602 and MPU6000
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI1 | SCK | PA5 | MPU6000 & ICM20602
| 2 | SPI1 | MISO | PA6 | MPU6000 & ICM20602
| 3 | SPI1 | MOSI | PA7 | MPU6000 & ICM20602
| 4 | SPI1 | CS | PA4 | MPU6000 & ICM20602
| 5 | SPI1 | INT | PC4 | MPU6000 & ICM20602
### OSD MAX7456
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI2 | SCK | PB13 |
| 2 | SPI2 | MISO | PB14 |
| 3 | SPI2 | MOSI | PB15 |
| 4 | SPI2 | CS | PB12 |
### 16Mbyte flash
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI3 | SCK | PB3 |
| 2 | SPI3 | MISO | PB4 |
| 3 | SPI3 | MOSI | PB5 |
| 4 | SPI3 | CS | PC15 |
### SWD
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | SWCLK | PAD |
| 2 | Ground | PAD |
| 3 | SWDIO | PAD |
| 4 | 3V3 | PAD |

View file

@ -0,0 +1,49 @@
### Specifications
- Processor: STM32F405 (F4 processor)
- Gyro: MPU6000
- Loop: 8k/8k
- Input: 2-6S (Max 28V)
- Regulator: Filtered 5V 3A
- Receiver: 3.3V or 5V selectable. Inverted and non-inverted selectable receiver input
- Connectors: 8 pin JST-SH main connector. 2x 3 pin JST-SH Addressable LED connectors (mirrored output)
- Telemetry: Current Sensor and ESC Telemetry Input
- Blackbox: 128Mbit flash (16Megabytes)
- Motor: 4 pwm motor outputs with D-Shot and Multishot support
- Mounting: M3 30.5x30.5mm holes with soft mounting
- Dimensions: 37x37mm
- Weight: 7.5g
- Camera: Filtered 5V output
### Features
- Direct mounting for Unify Pro (5V), Unify Nano, Unify Pro Nano32 (Nano VTXs use adapter board included)
- Direct mounting for TBS CrossFire Nano RX, TBS CrossFire Nano Diversity RX, FR Sky XM+, and FR Sky R9m Mini (R9m Mini Adapter Included From Tiny's LEDs)
- Header holes for direct receiver installation.
- Built in camera control via single wire (analog only)
- Built in BetaFlight OSD
- Buzzer: Dedicated pads for 5V (100mA max) buzzers
- Onboard addressable LED
- Built in Tinys LEDs RealPit VTX power switch (selectable between ON-OFF-Remote)
- Receiver can be powered on via USB (VTX stays off)
- SmartAudio: Selectable between internal (FC controlled) and external (receiver).
### UART info
- UART1: Receiver (FrSky, Spektrum, Crossfire, etc)
- UART3: SmartAudio (or any other desired output if SmartAudio is selected to pull signal from the “external” pad, designated RX SA on the top of the FC)
- UART6: ESC Telemetry (if applicable).
### Top
![Top](images/SYNERGYF4-top.png)
### Bottom
![Bottom](images/SYNERGYF4-bottom.png)
### Photo
![Main](images/SYNERGYF4-main.jpg)
`*** The flight controller does not include a receiver or VTX. The picture is for illustration only!`
### Installation
- Video: https://www.facebook.com/kevinslee106/videos/10156338569116234
### Where to get
- WhitenoiseFPV: https://whitenoisefpv.com/products/synergyf4
- Tiny's LEDs: https://tinysleds.com/products/synergy-f4-flight-controller

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 67 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 39 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

View file

@ -46,6 +46,7 @@ COMMON_SRC = \
fc/hardfaults.c \
fc/tasks.c \
fc/runtime_config.c \
fc/stats.c \
io/beeper.c \
io/piniobox.c \
io/serial.c \
@ -122,6 +123,7 @@ COMMON_SRC = \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \
@ -301,6 +303,7 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \

View file

@ -40,7 +40,59 @@ UNSUPPORTED_TARGETS := \
CC3D_OPBL \
CJMCU \
MICROSCISKY \
NAZE
NAZE \
AIORACERF3 \
AIR32 \
AIRHEROF3 \
ALIENFLIGHTF3 \
BEEBRAIN_V2D \
BEEBRAIN_V2F \
BEESTORM \
BETAFLIGHTF3 \
CHEBUZZF3 \
COLIBRI_RACE \
CRAZYBEEF3DX \
CRAZYBEEF3FR \
CRAZYBEEF3FS \
DOGE EACHIF3 \
FF_ACROWHOOPSP \
FF_KOMBINI \
FF_PIKOBLX \
FF_RADIANCE \
FLIP32F3OSD \
FRSKYF3 \
FURYF3 \
FURYF3OSD \
IMPULSERCF3 \
IRCFUSIONF3 \
IRCSYNERGYF3 \
ISHAPEDF3 \
KISSCC \
KISSFC \
LUMBAF3 \
LUXV2_RACE \
LUX_RACE \
MIDELICF3 \
MOTOLAB \
MULTIFLITEPICO \
OMNIBUS \
RACEBASE \
RCEXPLORERF3 \
RG_SSD_F3 \
RMDO \
SINGULARITY \
SIRINFPV \
SPARKY \
SPRACINGF3 \
SPRACINGF3EVO \
SPRACINGF3MINI \
SPRACINGF3MQ \
SPRACINGF3NEO \
STM32F3DISCOVERY \
TINYBEEF3 \
TINYFISH \
X_RACERSPI \
ZCOREF3
SUPPORTED_TARGETS := $(filter-out $(UNSUPPORTED_TARGETS), $(VALID_TARGETS))

View file

@ -85,4 +85,6 @@ const char * const debugModeNames[DEBUG_COUNT] = {
"D_MIN",
"AC_CORRECTION",
"AC_ERROR",
"DUAL_GYRO_SCALED",
"DSHOT_RPM_ERRORS",
};

View file

@ -101,6 +101,8 @@ typedef enum {
DEBUG_D_MIN,
DEBUG_AC_CORRECTION,
DEBUG_AC_ERROR,
DEBUG_DUAL_GYRO_SCALED,
DEBUG_DSHOT_RPM_ERRORS,
DEBUG_COUNT
} debugType_e;

View file

@ -24,7 +24,7 @@
#define FC_FIRMWARE_NAME "Betaflight"
#define FC_VERSION_MAJOR 4 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 0 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_MINOR 1 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL)

View file

@ -52,6 +52,7 @@ extern uint8_t __config_end;
#include "common/color.h"
#include "common/maths.h"
#include "common/printf.h"
#include "common/printf_serial.h"
#include "common/strtol.h"
#include "common/time.h"
#include "common/typeconversion.h"
@ -74,6 +75,7 @@ extern uint8_t __config_end;
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/light_led.h"
#include "drivers/pwm_output.h"
#include "drivers/rangefinder/rangefinder_hcsr04.h"
#include "drivers/sdcard.h"
#include "drivers/sensor.h"
@ -537,6 +539,10 @@ static void printValuePointer(const clivalue_t *var, const void *valuePointer, b
} else {
cliPrintf("OFF");
}
break;
case MODE_STRING:
cliPrintf("%s", (char *)valuePointer);
break;
}
if (valueIsCorrupted) {
@ -755,7 +761,6 @@ static void cliSetVar(const clivalue_t *var, const uint32_t value)
}
*(uint32_t *)ptr = workValue;
break;
}
} else {
switch (var->type & VALUE_TYPE_MASK) {
@ -3949,6 +3954,19 @@ static uint8_t getWordLength(char *bufBegin, char *bufEnd)
return bufEnd - bufBegin;
}
uint16_t cliGetSettingIndex(char *name, uint8_t length)
{
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const char *settingName = valueTable[i].name;
// ensure exact match when setting to prevent setting variables with shorter names
if (strncasecmp(name, settingName, strlen(settingName)) == 0 && length == strlen(settingName)) {
return i;
}
}
return valueTableEntryCount;
}
STATIC_UNIT_TESTED void cliSet(char *cmdline)
{
const uint32_t len = strlen(cmdline);
@ -3972,11 +3990,12 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
eqptr++;
eqptr = skipSpace(eqptr);
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const clivalue_t *val = &valueTable[i];
// ensure exact match when setting to prevent setting variables with shorter names
if (strncasecmp(cmdline, val->name, strlen(val->name)) == 0 && variableNameLength == strlen(val->name)) {
const uint16_t index = cliGetSettingIndex(cmdline, variableNameLength);
if (index >= valueTableEntryCount) {
cliPrintErrorLinef("INVALID NAME");
return;
}
const clivalue_t *val = &valueTable[index];
bool valueChanged = false;
int16_t value = 0;
@ -4091,7 +4110,26 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
valueChanged = true;
break;
case MODE_STRING: {
char *valPtr = eqptr;
valPtr = skipSpace(valPtr);
const unsigned int len = strlen(valPtr);
const uint8_t min = val->config.string.minlength;
const uint8_t max = val->config.string.maxlength;
const bool updatable = ((val->config.string.flags & STRING_FLAGS_WRITEONCE) == 0 ||
strlen((char *)cliGetValuePointer(val)) == 0 ||
strncmp(valPtr, (char *)cliGetValuePointer(val), len) == 0);
if (updatable && len > 0 && len <= max) {
memset((char *)cliGetValuePointer(val), 0, max);
if (len >= min && strncmp(valPtr, emptyName, len)) {
strncpy((char *)cliGetValuePointer(val), valPtr, len);
}
valueChanged = true;
}
}
break;
}
if (valueChanged) {
@ -4103,9 +4141,6 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
}
return;
}
}
cliPrintErrorLinef("INVALID NAME");
} else {
// no equals, check for matching variables.
cliGet(cmdline);
@ -4232,28 +4267,6 @@ static void cliStatus(char *cmdline)
cliPrintf(" %s", armingDisableFlagNames[bitpos]);
}
cliPrintLinefeed();
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
if (useDshotTelemetry) {
cliPrintLinef("Dshot reads: %u", readDoneCount);
cliPrintLinef("Dshot invalid pkts: %u", dshotInvalidPacketCount);
extern uint32_t setDirectionMicros;
cliPrintLinef("Dshot irq micros: %u", setDirectionMicros);
for (int i = 0; i<getMotorCount(); i++) {
cliPrintLinef( "Dshot RPM Motor %u: %u", i, (int)getDshotTelemetry(i));
}
bool proshot = (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000);
int modulo = proshot ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
int len = proshot ? 8 : DSHOT_TELEMETRY_INPUT_LEN;
for (int i=0; i<len; i++) {
cliPrintf("%u ", (int)inputBuffer[i]);
}
cliPrintLinefeed();
for (int i=1; i<len; i+=2) {
cliPrintf("%u ", (int)(inputBuffer[i] + modulo - inputBuffer[i-1]) % modulo);
}
cliPrintLinefeed();
}
#endif
}
#if defined(USE_TASK_STATISTICS)
@ -5307,6 +5320,57 @@ static void cliTimer(char *cmdline)
}
#endif
#ifdef USE_DSHOT_TELEMETRY
static void cliDshotTelemetryInfo(char *cmdline)
{
UNUSED(cmdline);
if (useDshotTelemetry) {
cliPrintLinef("Dshot reads: %u", readDoneCount);
cliPrintLinef("Dshot invalid pkts: %u", dshotInvalidPacketCount);
extern uint32_t setDirectionMicros;
cliPrintLinef("Dshot irq micros: %u", setDirectionMicros);
cliPrintLinefeed();
#ifdef USE_DSHOT_TELEMETRY_STATS
cliPrintLine("Motor RPM Invalid");
cliPrintLine("===== ===== =======");
#else
cliPrintLine("Motor RPM");
cliPrintLine("===== =====");
#endif
for (uint8_t i = 0; i < getMotorCount(); i++) {
cliPrintf("%5d %5d ", i, (int)getDshotTelemetry(i));
#ifdef USE_DSHOT_TELEMETRY_STATS
if (isDshotMotorTelemetryActive(i)) {
const int calcPercent = getDshotTelemetryMotorInvalidPercent(i);
cliPrintLinef("%3d.%02d%%", calcPercent / 100, calcPercent % 100);
} else {
cliPrintLine("NO DATA");
}
#else
cliPrintLinefeed();
#endif
}
cliPrintLinefeed();
const bool proshot = (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000);
const int modulo = proshot ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
const int len = proshot ? 8 : DSHOT_TELEMETRY_INPUT_LEN;
for (int i = 0; i < len; i++) {
cliPrintf("%u ", (int)inputBuffer[i]);
}
cliPrintLinefeed();
for (int i = 1; i < len; i+=2) {
cliPrintf("%u ", (int)(inputBuffer[i] + modulo - inputBuffer[i-1]) % modulo);
}
cliPrintLinefeed();
} else {
cliPrintLine("Dshot telemetry not enabled");
}
}
#endif
static void printConfig(char *cmdline, bool doDiff)
{
dumpFlags_t dumpMask = DUMP_MASTER;
@ -5637,6 +5701,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma),
#endif
#endif
#ifdef USE_DSHOT_TELEMETRY
CLI_COMMAND_DEF("dshot_telemetry_info", "disply dshot telemetry info and stats", NULL, cliDshotTelemetryInfo),
#endif
#ifdef USE_DSHOT
CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
#endif
@ -5648,7 +5715,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
CLI_COMMAND_DEF("feature", "configure features",
"list\r\n"
"\t<+|->[name]", cliFeature),
"\t<->[name]", cliFeature),
#ifdef USE_FLASHFS
CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
@ -5736,7 +5803,11 @@ const clicmd_t cmdTable[] = {
#endif
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
#ifdef USE_VTX_CONTROL
CLI_COMMAND_DEF("vtx", "vtx channels on switch", "<index> <aux> <band> <channel> <power> <start> <end>", cliVtx),
#ifdef MINIMAL_CLI
CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
#else
CLI_COMMAND_DEF("vtx", "vtx channels on switch", "<index> <aux_channel> <vtx_band> <vtx_channel> <vtx_power> <start_range> <end_range>", cliVtx),
#endif
#endif
#ifdef USE_VTX_TABLE
CLI_COMMAND_DEF("vtxtable", "vtx frequency able", "<band> <bandname> <bandletter> <freq> ... <freq>\r\n", cliVtxTable),

View file

@ -87,6 +87,8 @@
#include "pg/usb.h"
#include "pg/sdio.h"
#include "pg/rcdevice.h"
#include "pg/stats.h"
#include "pg/board.h"
#include "rx/rx.h"
#include "rx/cc2500_frsky_common.h"
@ -150,7 +152,7 @@ static const char * const lookupTableOffOn[] = {
};
static const char * const lookupTableCrashRecovery[] = {
"OFF", "ON" ,"BEEP"
"OFF", "ON" ,"BEEP", "DISARM"
};
static const char * const lookupTableUnit[] = {
@ -605,7 +607,7 @@ const clivalue_t valueTable[] = {
{ "dyn_notch_range", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DYNAMIC_FILTER_RANGE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_range) },
{ "dyn_notch_width_percent", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_width_percent) },
{ "dyn_notch_q", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_q) },
{ "dyn_notch_min_hz", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 100, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_min_hz) },
{ "dyn_notch_min_hz", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 60, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_min_hz) },
#endif
#ifdef USE_DYN_LPF
{ "dyn_lpf_gyro_min_hz", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_lpf_gyro_min_hz) },
@ -874,6 +876,8 @@ const clivalue_t valueTable[] = {
{ "gps_rescue_angle", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, angle) },
{ "gps_rescue_initial_alt", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 20, 100 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, initialAltitudeM) },
{ "gps_rescue_descent_dist", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 30, 500 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, descentDistanceM) },
{ "gps_rescue_landing_alt", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 3, 10 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, targetLandingAltitudeM) },
{ "gps_rescue_landing_dist", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 5, 15 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, targetLandingDistanceM) },
{ "gps_rescue_ground_speed", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 30, 3000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, rescueGroundspeed) },
{ "gps_rescue_throttle_p", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 500 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleP) },
{ "gps_rescue_throttle_i", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 500 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleI) },
@ -932,9 +936,6 @@ const clivalue_t valueTable[] = {
{ "crash_recovery", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRASH_RECOVERY }, PG_PID_PROFILE, offsetof(pidProfile_t, crash_recovery) },
{ "iterm_rotation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_rotation) },
#if defined(USE_SMART_FEEDFORWARD)
{ "smart_feedforward", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, smart_feedforward) },
#endif
#if defined(USE_ITERM_RELAX)
{ "iterm_relax", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax) },
{ "iterm_relax_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax_type) },
@ -1123,8 +1124,15 @@ const clivalue_t valueTable[] = {
#endif
{ "osd_warn_no_gps_rescue", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_UNAVAILABLE, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
{ "osd_warn_gps_rescue_disabled", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_DISABLED, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
{ "osd_warn_rssi", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_RSSI, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
#ifdef USE_RX_LINK_QUALITY_INFO
{ "osd_warn_link_quality", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_LINK_QUALITY, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
#endif
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
#ifdef USE_RX_LINK_QUALITY_INFO
{ "osd_link_quality_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, link_quality_alarm) },
#endif
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
{ "osd_esc_temp_alarm", VAR_INT8 | MASTER_VALUE, .config.minmax = { INT8_MIN, INT8_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, esc_temp_alarm) },
@ -1415,6 +1423,18 @@ const clivalue_t valueTable[] = {
{ "flysky_spi_tx_id", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, txId) },
{ "flysky_spi_rf_channels", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 16, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, rfChannelMap) },
#endif
#ifdef USE_PERSISTENT_STATS
{ "stats", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_enabled) },
{ "stats_total_flights", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_flights) },
{ "stats_total_time_s", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_time_s) },
{ "stats_total_dist_m", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_dist_m) },
#endif
{ "name", VAR_UINT8 | MASTER_VALUE | MODE_STRING, .config.string = { 1, MAX_NAME_LENGTH, STRING_FLAGS_NONE }, PG_PILOT_CONFIG, offsetof(pilotConfig_t, name) },
#ifdef USE_OSD
{ "display_name", VAR_UINT8 | MASTER_VALUE | MODE_STRING, .config.string = { 1, MAX_NAME_LENGTH, STRING_FLAGS_NONE }, PG_PILOT_CONFIG, offsetof(pilotConfig_t, displayName) },
#endif
};
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);

View file

@ -160,17 +160,18 @@ typedef enum {
PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
HARDWARE_VALUE = (3 << VALUE_SECTION_OFFSET), // Part of the master section, but used for the hardware definition
// value mode, bits 5-6
// value mode, bits 5-7
MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
MODE_LOOKUP = (1 << VALUE_MODE_OFFSET),
MODE_ARRAY = (2 << VALUE_MODE_OFFSET),
MODE_BITSET = (3 << VALUE_MODE_OFFSET)
MODE_BITSET = (3 << VALUE_MODE_OFFSET),
MODE_STRING = (4 << VALUE_MODE_OFFSET),
} cliValueFlag_e;
#define VALUE_TYPE_MASK (0x07)
#define VALUE_SECTION_MASK (0x18)
#define VALUE_MODE_MASK (0x60)
#define VALUE_MODE_MASK (0xE0)
typedef struct cliMinMaxConfig_s {
const int16_t min;
@ -190,11 +191,21 @@ typedef struct cliArrayLengthConfig_s {
const uint8_t length;
} cliArrayLengthConfig_t;
typedef struct cliStringLengthConfig_s {
const uint8_t minlength;
const uint8_t maxlength;
const uint8_t flags;
} cliStringLengthConfig_t;
#define STRING_FLAGS_NONE (0)
#define STRING_FLAGS_WRITEONCE (1 << 0)
typedef union {
cliLookupTableConfig_t lookup; // used for MODE_LOOKUP excl. VAR_UINT32
cliMinMaxConfig_t minmax; // used for MODE_DIRECT with signed parameters
cliMinMaxUnsignedConfig_t minmaxUnsigned; // used for MODE_DIRECT with unsigned parameters
cliArrayLengthConfig_t array; // used for MODE_ARRAY
cliStringLengthConfig_t string; // used for MODE_STRING
uint8_t bitpos; // used for MODE_BITSET
uint32_t u32Max; // used for MODE_DIRECT with VAR_UINT32
} cliValueConfig_t;

View file

@ -364,7 +364,7 @@ static int cmsDrawMenuItemValue(displayPort_t *pDisplay, char *buff, uint8_t row
return cnt;
}
static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t row, bool selectedRow, uint8_t flags)
static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t row, bool selectedRow, uint8_t *flags)
{
#define CMS_DRAW_BUFFER_LEN 12
#define CMS_NUM_FIELD_LEN 5
@ -383,20 +383,20 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
switch (p->type) {
case OME_String:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_DRAW_BUFFER_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_Submenu:
case OME_Funcall:
if (IS_PRINTVALUE(flags)) {
if (IS_PRINTVALUE(*flags)) {
buff[0]= 0x0;
if ((p->type == OME_Submenu) && p->func && (flags & OPTSTRING)) {
if ((p->type == OME_Submenu) && p->func && (*flags & OPTSTRING)) {
// Special case of sub menu entry with optional value display.
@ -407,12 +407,12 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
row = smallScreen ? row - 1 : row;
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, strlen(buff));
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_Bool:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
if (*((uint8_t *)(p->data))) {
strcpy(buff, "YES");
} else {
@ -420,23 +420,23 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
}
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, 3);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_TAB:
if (IS_PRINTVALUE(flags)) {
if (IS_PRINTVALUE(*flags)) {
OSD_TAB_t *ptr = p->data;
char * str = (char *)ptr->names[*ptr->val];
strncpy(buff, str, CMS_DRAW_BUFFER_LEN);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_DRAW_BUFFER_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
#ifdef USE_OSD
case OME_VISIBLE:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
uint16_t *val = (uint16_t *)p->data;
bool cursorBlink = millis() % (2 * CMS_CURSOR_BLINK_DELAY_MS) < CMS_CURSOR_BLINK_DELAY_MS;
for (unsigned x = 1; x < OSD_PROFILE_COUNT + 1; x++) {
@ -455,61 +455,61 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
}
}
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, 3);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
#endif
case OME_UINT8:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
OSD_UINT8_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_NUM_FIELD_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_INT8:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
OSD_INT8_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_NUM_FIELD_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_UINT16:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
OSD_UINT16_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_NUM_FIELD_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_INT16:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
OSD_UINT16_t *ptr = p->data;
itoa(*ptr->val, buff, 10);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_NUM_FIELD_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_FLOAT:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
OSD_FLOAT_t *ptr = p->data;
cmsFormatFloat(*ptr->val * ptr->multipler, buff);
cnt = cmsDrawMenuItemValue(pDisplay, buff, row, CMS_NUM_FIELD_LEN);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
case OME_Label:
if (IS_PRINTVALUE(flags) && p->data) {
if (IS_PRINTVALUE(*flags) && p->data) {
// A label with optional string, immediately following text
cnt = displayWrite(pDisplay, leftMenuColumn + 1 + (uint8_t)strlen(p->text), row, p->data);
CLR_PRINTVALUE(flags);
CLR_PRINTVALUE(*flags);
}
break;
@ -609,7 +609,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
if (IS_PRINTVALUE(runtimeEntryFlags[i])) {
bool selectedRow = i == currentCtx.cursorRow;
room -= cmsDrawMenuEntry(pDisplay, p, top + i * linesPerMenuItem, selectedRow, runtimeEntryFlags[i]);
room -= cmsDrawMenuEntry(pDisplay, p, top + i * linesPerMenuItem, selectedRow, &runtimeEntryFlags[i]);
if (room < 30)
return;
}

View file

@ -31,6 +31,10 @@
#include "cms/cms_types.h"
#include "cms/cms_menu_failsafe.h"
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cms/cms_menu_gps_rescue.h"
#endif
#include "config/feature.h"
#include "fc/config.h"
@ -73,6 +77,9 @@ static const OSD_Entry cmsx_menuFailsafeEntries[] =
{ "GUARD TIME", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_delay, 0, 200, 1, 100 }, 0 },
{ "STAGE 2 DELAY", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_off_delay, 0, 200, 1, 100 }, 0 },
{ "STAGE 2 THROTTLE", OME_UINT16, NULL, &(OSD_UINT16_t) { &failsafeConfig_failsafe_throttle, PWM_PULSE_MIN, PWM_PULSE_MAX, 1 }, 0 },
#ifdef USE_CMS_GPS_RESCUE_MENU
{ "GPS RESCUE", OME_Submenu, cmsMenuChange, &cmsx_menuGpsRescue, 0},
#endif
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};

View file

@ -0,0 +1,183 @@
/*
* 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 <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_gps_rescue.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/gps_rescue.h"
static uint16_t gpsRescueConfig_angle; //degrees
static uint16_t gpsRescueConfig_initialAltitudeM; //meters
static uint16_t gpsRescueConfig_descentDistanceM; //meters
static uint16_t gpsRescueConfig_rescueGroundspeed; // centimeters per second
static uint16_t gpsRescueConfig_throttleMin;
static uint16_t gpsRescueConfig_throttleMax;
static uint16_t gpsRescueConfig_throttleHover;
static uint8_t gpsRescueConfig_minSats;
static uint16_t gpsRescueConfig_minRescueDth; //meters
static uint8_t gpsRescueConfig_allowArmingWithoutFix;
static uint16_t gpsRescueConfig_throttleP, gpsRescueConfig_throttleI, gpsRescueConfig_throttleD;
static uint16_t gpsRescueConfig_velP, gpsRescueConfig_velI, gpsRescueConfig_velD;
static uint16_t gpsRescueConfig_yawP;
static long cms_menuGpsRescuePidOnEnter(void)
{
gpsRescueConfig_throttleP = gpsRescueConfig()->throttleP;
gpsRescueConfig_throttleI = gpsRescueConfig()->throttleI;
gpsRescueConfig_throttleD = gpsRescueConfig()->throttleD;
gpsRescueConfig_yawP = gpsRescueConfig()->yawP;
gpsRescueConfig_velP = gpsRescueConfig()->velP;
gpsRescueConfig_velI = gpsRescueConfig()->velI;
gpsRescueConfig_velD = gpsRescueConfig()->velD;
return 0;
}
static long cms_menuGpsRescuePidOnExit(const OSD_Entry *self)
{
UNUSED(self);
gpsRescueConfigMutable()->throttleP = gpsRescueConfig_throttleP;
gpsRescueConfigMutable()->throttleI = gpsRescueConfig_throttleI;
gpsRescueConfigMutable()->throttleD = gpsRescueConfig_throttleD;
gpsRescueConfigMutable()->yawP = gpsRescueConfig_yawP;
gpsRescueConfigMutable()->velP = gpsRescueConfig_velP;
gpsRescueConfigMutable()->velI = gpsRescueConfig_velI;
gpsRescueConfigMutable()->velD = gpsRescueConfig_velD;
return 0;
}
const OSD_Entry cms_menuGpsRescuePidEntries[] =
{
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL, 0},
{ "THROTTLE P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleP, 0, 500, 1 }, 0 },
{ "THROTTLE I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleI, 0, 500, 1 }, 0 },
{ "THROTTLE D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleD, 0, 500, 1 }, 0 },
{ "YAW P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_yawP, 0, 500, 1 }, 0 },
{ "VELOCITY P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velP, 0, 500, 1 }, 0 },
{ "VELOCITY I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velI, 0, 500, 1 }, 0 },
{ "VELOCITY D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velD, 0, 500, 1 }, 0 },
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cms_menuGpsRescuePid = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRPID",
.GUARD_type = OME_MENU,
#endif
.onEnter = cms_menuGpsRescuePidOnEnter,
.onExit = cms_menuGpsRescuePidOnExit,
.entries = cms_menuGpsRescuePidEntries,
};
static long cmsx_menuGpsRescueOnEnter(void)
{
gpsRescueConfig_angle = gpsRescueConfig()->angle;
gpsRescueConfig_initialAltitudeM = gpsRescueConfig()->initialAltitudeM;
gpsRescueConfig_descentDistanceM = gpsRescueConfig()->descentDistanceM;
gpsRescueConfig_rescueGroundspeed = gpsRescueConfig()->rescueGroundspeed;
gpsRescueConfig_throttleMin = gpsRescueConfig()->throttleMin ;
gpsRescueConfig_throttleMax = gpsRescueConfig()->throttleMax;
gpsRescueConfig_throttleHover = gpsRescueConfig()->throttleHover;
gpsRescueConfig_minSats = gpsRescueConfig()->minSats;
gpsRescueConfig_minRescueDth = gpsRescueConfig()->minRescueDth;
gpsRescueConfig_allowArmingWithoutFix = gpsRescueConfig()->allowArmingWithoutFix;
return 0;
}
static long cmsx_menuGpsRescueOnExit(const OSD_Entry *self)
{
UNUSED(self);
gpsRescueConfigMutable()->angle = gpsRescueConfig_angle;
gpsRescueConfigMutable()->initialAltitudeM = gpsRescueConfig_initialAltitudeM;
gpsRescueConfigMutable()->descentDistanceM = gpsRescueConfig_descentDistanceM;
gpsRescueConfigMutable()->rescueGroundspeed = gpsRescueConfig_rescueGroundspeed;
gpsRescueConfigMutable()->throttleMin = gpsRescueConfig_throttleMin;
gpsRescueConfigMutable()->throttleMax = gpsRescueConfig_throttleMax;
gpsRescueConfigMutable()->throttleHover = gpsRescueConfig_throttleHover;
gpsRescueConfigMutable()->minSats = gpsRescueConfig_minSats;
gpsRescueConfigMutable()->minRescueDth = gpsRescueConfig_minRescueDth;
gpsRescueConfigMutable()->allowArmingWithoutFix = gpsRescueConfig_allowArmingWithoutFix;
return 0;
}
const OSD_Entry cmsx_menuGpsRescueEntries[] =
{
{"--- GPS RESCUE ---", OME_Label, NULL, NULL, 0},
{ "ANGLE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_angle, 0, 200 ,1 }, 0 },
{ "MIN DIST HOME M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_minRescueDth, 50, 1000 ,1 }, 0 },
{ "INITAL ALT M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_initialAltitudeM, 20, 100, 1 }, 0 },
{ "DESCENT DIST M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descentDistanceM, 30, 500, 1 }, 0 },
{ "GROUND SPEED C/M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_rescueGroundspeed, 30, 3000, 1 }, 0 },
{ "THROTTLE MIN", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMin, 1000, 2000, 1 }, 0 },
{ "THROTTLE MAX", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMax, 1000, 2000, 1 }, 0 },
{ "THROTTLE HOV", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleHover, 1000, 2000, 1 }, 0 },
{ "ARM WITHOUT FIX", OME_Bool, NULL, &gpsRescueConfig_allowArmingWithoutFix, 0 },
{ "MIN SATELITES", OME_UINT8, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 }, 0 },
{ "GPS RESCUE PID", OME_Submenu, cmsMenuChange, &cms_menuGpsRescuePid, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuGpsRescue = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRES",
.GUARD_type = OME_MENU,
#endif
.onEnter = cmsx_menuGpsRescueOnEnter,
.onExit = cmsx_menuGpsRescueOnExit,
.entries = cmsx_menuGpsRescueEntries,
};
#endif

View file

@ -0,0 +1,23 @@
/*
* 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/>.
*/
#pragma once
extern CMS_Menu cmsx_menuGpsRescue;

View file

@ -38,24 +38,17 @@
#include "build/build_config.h"
#include "common/utils.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "printf.h"
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#include "typeconversion.h"
#endif
static serialPort_t *printfSerialPort;
#ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT
typedef void (*putcf) (void *, char);
static putcf stdout_putf;
static void *stdout_putp;
putcf stdout_putf;
void *stdout_putp;
// print bf, padded from left to at least n characters.
// padding is zero ('0') if z!=0, space (' ') otherwise
@ -166,16 +159,6 @@ void init_printf(void *putp, void (*putf) (void *, char))
stdout_putp = putp;
}
int tfp_printf(const char *fmt, ...)
{
va_list va;
va_start(va, fmt);
int written = tfp_format(stdout_putp, stdout_putf, fmt, va);
va_end(va);
while (!isSerialTransmitBufferEmpty(printfSerialPort));
return written;
}
static void putcp(void *p, char c)
{
*(*((char **) p))++ = c;
@ -192,36 +175,5 @@ int tfp_sprintf(char *s, const char *fmt, ...)
return written;
}
#endif // REQUIRE_CC_ARM_PRINTF_SUPPORT
static void _putc(void *p, char c)
{
UNUSED(p);
serialWrite(printfSerialPort, c);
}
void printfSupportInit(void)
{
init_printf(NULL, _putc);
}
#else
// keil/armcc version
int fputc(int c, FILE *f)
{
// let DMA catch up a bit when using set or dump, we're too fast.
while (!isSerialTransmitBufferEmpty(printfSerialPort));
serialWrite(printfSerialPort, c);
return c;
}
void printfSupportInit(void)
{
// Nothing to do
}
#endif
void setPrintfSerialPort(serialPort_t *serialPort)
{
printfSerialPort = serialPort;
}

View file

@ -106,14 +106,11 @@ regs Kusti, 23.10.2004
#include <stdarg.h>
typedef void (*putcf) (void *, char);
extern putcf stdout_putf;
extern void *stdout_putp;
void init_printf(void *putp, void (*putf) (void *, char));
// Disabling this, in favour of tfp_format to be used in cli.c
//int tfp_printf(const char *fmt, ...);
int tfp_sprintf(char *s, const char *fmt, ...);
int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list va);
struct serialPort_s;
void setPrintfSerialPort(struct serialPort_s *serialPort);
void printfSupportInit(void);

View file

@ -0,0 +1,86 @@
/*
* 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 <stdarg.h>
#include <stdlib.h>
#include "platform.h"
#include "common/printf.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "printf_serial.h"
#ifdef SERIAL_PORT_COUNT
static serialPort_t *printfSerialPort;
void setPrintfSerialPort(serialPort_t *serialPort)
{
printfSerialPort = serialPort;
}
#ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT
int tfp_printf(const char *fmt, ...)
{
va_list va;
va_start(va, fmt);
int written = tfp_format(stdout_putp, stdout_putf, fmt, va);
va_end(va);
while (!isSerialTransmitBufferEmpty(printfSerialPort));
return written;
}
static void _putc(void *p, char c)
{
UNUSED(p);
serialWrite(printfSerialPort, c);
}
void printfSerialInit(void)
{
init_printf(NULL, _putc);
}
#else // REQUIRE_CC_ARM_PRINTF_SUPPORT
// keil/armcc version
int fputc(int c, FILE *f)
{
// let DMA catch up a bit when using set or dump, we're too fast.
while (!isSerialTransmitBufferEmpty(printfSerialPort));
serialWrite(printfSerialPort, c);
return c;
}
void printfSerialInit(void)
{
// Nothing to do
}
#endif
#endif // SERIAL_PORT_COUNT

View file

@ -0,0 +1,27 @@
/*
* 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/>.
*/
struct serialPort_s;
void printfSerialInit(void);
void setPrintfSerialPort(struct serialPort_s *serialPort);
int tfp_printf(const char *fmt, ...);

View file

@ -23,7 +23,7 @@
#include <stdint.h>
#include <stdbool.h>
#define EEPROM_CONF_VERSION 171
#define EEPROM_CONF_VERSION 172
bool isEEPROMVersionValid(void);
bool isEEPROMStructureValid(void);

View file

@ -222,7 +222,8 @@ static gyroSpiDetectFn_t gyroSpiDetectFnTable[] = {
static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
SPI_TypeDef *instance = spiInstanceByDevice(SPI_CFG_TO_DEV(config->spiBus));
if (!instance) {
if (!instance || !config->csnTag) {
return false;
}
spiBusSetInstance(&gyro->bus, instance);
@ -242,10 +243,13 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
sensor = (gyroSpiDetectFnTable[index])(&gyro->bus);
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
return true;
}
}
// Detection failed, disable CS pin again
spiPreinitByTag(config->csnTag);
return false;
@ -261,13 +265,13 @@ void mpuPreInit(const struct gyroDeviceConfig_s *config)
#endif
}
void mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
bool mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
// MPU datasheet specifies 30ms.
delay(35);
if (config->bustype == BUSTYPE_NONE) {
return;
return false;
}
if (config->bustype == BUSTYPE_GYRO_AUTO) {
@ -291,7 +295,7 @@ void mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
inquiryResult &= MPU_INQUIRY_MASK;
if (ack && inquiryResult == MPUx0x0_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_3050;
return;
return true;
}
sig &= MPU_INQUIRY_MASK;
@ -301,14 +305,17 @@ void mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
} else if (sig == MPU6500_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_65xx_I2C;
}
return;
return true;
}
}
#endif
#ifdef USE_SPI_GYRO
gyro->bus.bustype = BUSTYPE_SPI;
detectSPISensorsAndUpdateDetectionResult(gyro, config);
return detectSPISensorsAndUpdateDetectionResult(gyro, config);
#else
return false;
#endif
}

View file

@ -218,7 +218,7 @@ void mpuGyroInit(struct gyroDev_s *gyro);
bool mpuGyroRead(struct gyroDev_s *gyro);
bool mpuGyroReadSPI(struct gyroDev_s *gyro);
void mpuPreInit(const struct gyroDeviceConfig_s *config);
void mpuDetect(struct gyroDev_s *gyro, const struct gyroDeviceConfig_s *config);
bool mpuDetect(struct gyroDev_s *gyro, const struct gyroDeviceConfig_s *config);
uint8_t mpuGyroDLPF(struct gyroDev_s *gyro);
uint8_t mpuGyroReadRegister(const busDevice_t *bus, uint8_t reg);

View file

@ -47,7 +47,6 @@
static void mpu6000AccAndGyroInit(gyroDev_t *gyro);
static bool mpuSpi6000InitDone = false;
// Bits
@ -171,10 +170,6 @@ uint8_t mpu6000SpiDetect(const busDevice_t *bus)
static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
{
if (mpuSpi6000InitDone) {
return;
}
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
// Device Reset
@ -218,8 +213,6 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST);
delayMicroseconds(1);
mpuSpi6000InitDone = true;
}
bool mpu6000SpiAccDetect(accDev_t *acc)

View file

@ -49,7 +49,6 @@
static void mpu9250AccAndGyroInit(gyroDev_t *gyro);
static bool mpuSpi9250InitDone = false;
bool mpu9250SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{
@ -120,10 +119,6 @@ bool mpu9250SpiWriteRegisterVerify(const busDevice_t *bus, uint8_t reg, uint8_t
static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
if (mpuSpi9250InitDone) {
return;
}
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed for writing to slow registers
mpu9250SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
@ -145,8 +140,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
#endif
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST);
mpuSpi9250InitDone = true; //init done
}
uint8_t mpu9250SpiDetect(const busDevice_t *bus)

View file

@ -38,8 +38,15 @@ void mcoInit(const mcoConfig_t *mcoConfig)
if (mcoConfig->enabled[1]) {
IO_t io = IOGetByTag(DEFIO_TAG_E(PC9));
IOInit(io, OWNER_MCO, 2);
#if defined(STM32F7)
HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLI2SCLK, RCC_MCODIV_4);
IOConfigGPIOAF(io, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL), GPIO_AF0_MCO);
#elif defined(STM32F40_41xxx) || defined(STM32F411xE) || defined(STM32F446xx)
RCC_MCO2Config(RCC_MCO2Source_PLLI2SCLK, RCC_MCO2Div_4);
IOConfigGPIOAF(io, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL), GPIO_AF_MCO);
#else
#error Unsupported MCU
#endif
}
}
#endif

View file

@ -46,14 +46,24 @@ FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer;
#define DSHOT_BEEP_DELAY_US 100000
#define DSHOT_MAX_COMMANDS 3
typedef enum {
DSHOT_COMMAND_STATE_IDLEWAIT, // waiting for motors to go idle
DSHOT_COMMAND_STATE_STARTDELAY, // initial delay period before a sequence of commands
DSHOT_COMMAND_STATE_ACTIVE, // actively sending the command (with optional repeated output)
DSHOT_COMMAND_STATE_POSTDELAY // delay period after the command has been sent
} dshotCommandState_e;
typedef struct dshotCommandControl_s {
timeUs_t nextCommandAtUs;
dshotCommandState_e state;
uint32_t nextCommandCycleDelay;
timeUs_t delayAfterCommandUs;
bool waitingForIdle;
uint8_t repeats;
uint8_t command[MAX_SUPPORTED_MOTORS];
} dshotCommandControl_t;
static timeUs_t dshotCommandPidLoopTimeUs = 125; // default to 8KHz (125us) loop to prevent possible div/0
// gets set to the actual value when the PID loop is initialized
static dshotCommandControl_t commandQueue[DSHOT_MAX_COMMANDS + 1];
static uint8_t commandQueueHead;
static uint8_t commandQueueTail;
@ -189,6 +199,11 @@ static uint8_t loadDmaBufferProshot(uint32_t *dmaBuffer, int stride, uint16_t pa
return PROSHOT_DMA_BUFFER_SIZE;
}
void setDshotPidLoopTime(uint32_t pidLoopTime)
{
dshotCommandPidLoopTimeUs = pidLoopTime;
}
#endif
void pwmWriteMotor(uint8_t index, float value)
@ -450,24 +465,49 @@ FAST_CODE bool pwmDshotCommandIsQueued(void)
return commandQueueHead != commandQueueTail;
}
static FAST_CODE bool isLastDshotCommand(void)
{
return ((commandQueueTail + 1) % (DSHOT_MAX_COMMANDS + 1) == commandQueueHead);
}
FAST_CODE bool pwmDshotCommandIsProcessing(void)
{
if (!pwmDshotCommandIsQueued()) {
return false;
}
dshotCommandControl_t* command = &commandQueue[commandQueueTail];
return command->nextCommandAtUs && !command->waitingForIdle && command->repeats > 0;
const bool commandIsProcessing = command->state == DSHOT_COMMAND_STATE_STARTDELAY
|| command->state == DSHOT_COMMAND_STATE_ACTIVE
|| (command->state == DSHOT_COMMAND_STATE_POSTDELAY && !isLastDshotCommand());
return commandIsProcessing;
}
FAST_CODE void pwmDshotCommandQueueUpdate(void)
static FAST_CODE bool pwmDshotCommandQueueUpdate(void)
{
if (!pwmDshotCommandIsQueued()) {
return;
}
dshotCommandControl_t* command = &commandQueue[commandQueueTail];
if (!command->nextCommandAtUs && !command->waitingForIdle && !command->repeats) {
if (pwmDshotCommandIsQueued()) {
commandQueueTail = (commandQueueTail + 1) % (DSHOT_MAX_COMMANDS + 1);
if (pwmDshotCommandIsQueued()) {
// There is another command in the queue so update it so it's ready to output in
// sequence. It can go directly to the DSHOT_COMMAND_STATE_ACTIVE state and bypass
// the DSHOT_COMMAND_STATE_IDLEWAIT and DSHOT_COMMAND_STATE_STARTDELAY states.
dshotCommandControl_t* nextCommand = &commandQueue[commandQueueTail];
nextCommand->state = DSHOT_COMMAND_STATE_ACTIVE;
nextCommand->nextCommandCycleDelay = 0;
return true;
}
}
return false;
}
static FAST_CODE uint32_t dshotCommandCyclesFromTime(timeUs_t delayUs)
{
// Find the minimum number of motor output cycles needed to
// provide at least delayUs time delay
uint32_t ret = delayUs / dshotCommandPidLoopTimeUs;
if (delayUs % dshotCommandPidLoopTimeUs) {
ret++;
}
return ret;
}
static dshotCommandControl_t* addCommand()
@ -484,8 +524,6 @@ static dshotCommandControl_t* addCommand()
void pwmWriteDshotCommand(uint8_t index, uint8_t motorCount, uint8_t command, bool blocking)
{
timeUs_t timeNowUs = micros();
if (!isMotorProtocolDshot() || (command > DSHOT_MAX_COMMAND) || pwmDshotCommandQueueFull()) {
return;
}
@ -541,7 +579,6 @@ void pwmWriteDshotCommand(uint8_t index, uint8_t motorCount, uint8_t command, bo
dshotCommandControl_t *commandControl = addCommand();
if (commandControl) {
commandControl->repeats = repeats;
commandControl->nextCommandAtUs = timeNowUs + DSHOT_INITIAL_DELAY_US;
commandControl->delayAfterCommandUs = delayAfterCommandUs;
for (unsigned i = 0; i < motorCount; i++) {
if (index == i || index == ALL_MOTORS) {
@ -550,7 +587,14 @@ void pwmWriteDshotCommand(uint8_t index, uint8_t motorCount, uint8_t command, bo
commandControl->command[i] = DSHOT_CMD_MOTOR_STOP;
}
}
commandControl->waitingForIdle = !allMotorsAreIdle(motorCount);
if (allMotorsAreIdle(motorCount)) {
// we can skip the motors idle wait state
commandControl->state = DSHOT_COMMAND_STATE_STARTDELAY;
commandControl->nextCommandCycleDelay = dshotCommandCyclesFromTime(DSHOT_INITIAL_DELAY_US);
} else {
commandControl->state = DSHOT_COMMAND_STATE_STARTDELAY;
commandControl->nextCommandCycleDelay = 0; // will be set after idle wait completes
}
}
}
}
@ -560,38 +604,58 @@ uint8_t pwmGetDshotCommand(uint8_t index)
return commandQueue[commandQueueTail].command[index];
}
// This function is used to synchronize the dshot command output timing with
// the normal motor output timing tied to the PID loop frequency. A "true" result
// allows the motor output to be sent, "false" means delay until next loop. So take
// the example of a dshot command that needs to repeat 10 times at 1ms intervals.
// If we have a 8KHz PID loop we'll end up sending the dshot command every 8th motor output.
FAST_CODE_NOINLINE bool pwmDshotCommandOutputIsEnabled(uint8_t motorCount)
{
timeUs_t timeNowUs = micros();
dshotCommandControl_t* command = &commandQueue[commandQueueTail];
if (pwmDshotCommandIsQueued()) {
if (command->waitingForIdle) {
switch (command->state) {
case DSHOT_COMMAND_STATE_IDLEWAIT:
if (allMotorsAreIdle(motorCount)) {
command->nextCommandAtUs = timeNowUs + DSHOT_INITIAL_DELAY_US;
command->waitingForIdle = false;
command->state = DSHOT_COMMAND_STATE_STARTDELAY;
command->nextCommandCycleDelay = dshotCommandCyclesFromTime(DSHOT_INITIAL_DELAY_US);
}
// Send normal motor output while waiting for motors to go idle
return true;
break;
case DSHOT_COMMAND_STATE_STARTDELAY:
if (command->nextCommandCycleDelay-- > 1) {
return false; // Delay motor output until the start of the command seequence
}
command->state = DSHOT_COMMAND_STATE_ACTIVE;
command->nextCommandCycleDelay = 0; // first iteration of the repeat happens now
FALLTHROUGH;
case DSHOT_COMMAND_STATE_ACTIVE:
if (command->nextCommandCycleDelay-- > 1) {
return false; // Delay motor output until the next command repeat
}
if (cmpTimeUs(timeNowUs, command->nextCommandAtUs) < 0) {
//Skip motor update because it isn't time yet for a new command
command->repeats--;
if (command->repeats) {
command->nextCommandCycleDelay = dshotCommandCyclesFromTime(DSHOT_COMMAND_DELAY_US);
} else {
command->state = DSHOT_COMMAND_STATE_POSTDELAY;
command->nextCommandCycleDelay = dshotCommandCyclesFromTime(command->delayAfterCommandUs);
if (!isLastDshotCommand() && command->nextCommandCycleDelay > 0) {
// Account for the 1 extra motor output loop between commands.
// Otherwise the inter-command delay will be DSHOT_COMMAND_DELAY_US + 1 loop.
command->nextCommandCycleDelay--;
}
}
break;
case DSHOT_COMMAND_STATE_POSTDELAY:
if (command->nextCommandCycleDelay-- > 1) {
return false; // Delay motor output until the end of the post-command delay
}
if (pwmDshotCommandQueueUpdate()) {
// Will be true if the command queue is not empty and we
// want to wait for the next command to start in sequence.
return false;
}
//Timed motor update happening with dshot command
if (command->repeats > 0) {
command->repeats--;
if (command->repeats > 0) {
command->nextCommandAtUs = timeNowUs + DSHOT_COMMAND_DELAY_US;
} else {
command->nextCommandAtUs = timeNowUs + command->delayAfterCommandUs;
}
} else {
command->nextCommandAtUs = 0;
}
return true;

View file

@ -122,6 +122,22 @@ typedef enum {
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
#define PROSHOT_DMA_BUFFER_SIZE 6 /* resolution + frame reset (2us) */
#ifdef USE_DSHOT_TELEMETRY
#ifdef USE_DSHOT_TELEMETRY_STATS
#define DSHOT_TELEMETRY_QUALITY_WINDOW 1 // capture a rolling 1 second of packet stats
#define DSHOT_TELEMETRY_QUALITY_BUCKET_MS 100 // determines the granularity of the stats and the overall number of rolling buckets
#define DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT (DSHOT_TELEMETRY_QUALITY_WINDOW * 1000 / DSHOT_TELEMETRY_QUALITY_BUCKET_MS)
typedef struct dshotTelemetryQuality_s {
uint32_t packetCountSum;
uint32_t invalidCountSum;
uint32_t packetCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
uint32_t invalidCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
uint8_t lastBucketIndex;
} dshotTelemetryQuality_t;
#endif // USE_DSHOT_TELEMETRY_STATS
#endif // USE_DSHOT_TELEMETRY
typedef struct {
TIM_TypeDef *timer;
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
@ -153,6 +169,9 @@ typedef struct {
uint16_t dshotTelemetryValue;
timeDelta_t dshotTelemetryDeadtimeUs;
bool dshotTelemetryActive;
#ifdef USE_DSHOT_TELEMETRY_STATS
dshotTelemetryQuality_t dshotTelemetryQuality;
#endif
#ifdef USE_HAL_DRIVER
LL_TIM_OC_InitTypeDef ocInitStruct;
LL_TIM_IC_InitTypeDef icInitStruct;
@ -254,13 +273,16 @@ bool pwmStartDshotMotorUpdate(uint8_t motorCount);
#endif
void pwmCompleteDshotMotorUpdate(uint8_t motorCount);
void pwmDshotCommandQueueUpdate(void);
bool pwmDshotCommandIsQueued(void);
bool pwmDshotCommandIsProcessing(void);
uint8_t pwmGetDshotCommand(uint8_t index);
bool pwmDshotCommandOutputIsEnabled(uint8_t motorCount);
uint16_t getDshotTelemetry(uint8_t index);
bool isDshotMotorTelemetryActive(uint8_t motorIndex);
void setDshotPidLoopTime(uint32_t pidLoopTime);
#ifdef USE_DSHOT_TELEMETRY_STATS
int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex);
#endif
#endif

View file

@ -169,7 +169,6 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
dmaMotorTimers[i].timerDmaSources = 0;
}
}
pwmDshotCommandQueueUpdate();
}
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
@ -220,9 +219,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
#define DMAINIT dmaInitStruct
#endif
dmaStream_t *dmaRef;
dmaStream_t *dmaRef = NULL;
#if defined(STM32F4)
uint32_t dmaChannel;
uint32_t dmaChannel = 0;
#endif
#if defined(USE_DMA_SPEC)
const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByTimer(timerHardware);

View file

@ -153,7 +153,6 @@ FAST_CODE void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
dmaMotorTimers[i].timerDmaSources = 0;
}
}
pwmDshotCommandQueueUpdate();
}
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
@ -204,8 +203,8 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
#define DMAINIT dmaInitStruct
#endif
DMA_Stream_TypeDef *dmaRef;
uint32_t dmaChannel;
DMA_Stream_TypeDef *dmaRef = NULL;
uint32_t dmaChannel = 0;
#if defined(USE_DMA_SPEC)
const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByTimer(timerHardware);
@ -290,7 +289,7 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
motor->icInitStruct.ICFilter = 0; //2;
#endif
uint32_t channel;
uint32_t channel = 0;
switch (timerHardware->channel) {
case TIM_CHANNEL_1: channel = LL_TIM_CHANNEL_CH1; break;
case TIM_CHANNEL_2: channel = LL_TIM_CHANNEL_CH2; break;

View file

@ -202,12 +202,34 @@ FAST_CODE void pwmDshotSetDirectionOutput(
);
#ifdef USE_DSHOT_TELEMETRY
#ifdef USE_DSHOT_TELEMETRY_STATS
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs)
{
uint8_t statsBucketIndex = (currentTimeMs / DSHOT_TELEMETRY_QUALITY_BUCKET_MS) % DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT;
if (statsBucketIndex != qualityStats->lastBucketIndex) {
qualityStats->packetCountSum -= qualityStats->packetCountArray[statsBucketIndex];
qualityStats->invalidCountSum -= qualityStats->invalidCountArray[statsBucketIndex];
qualityStats->packetCountArray[statsBucketIndex] = 0;
qualityStats->invalidCountArray[statsBucketIndex] = 0;
qualityStats->lastBucketIndex = statsBucketIndex;
}
qualityStats->packetCountSum++;
qualityStats->packetCountArray[statsBucketIndex]++;
if (!packetValid) {
qualityStats->invalidCountSum++;
qualityStats->invalidCountArray[statsBucketIndex]++;
}
}
#endif // USE_DSHOT_TELEMETRY_STATS
bool pwmStartDshotMotorUpdate(uint8_t motorCount)
{
if (!useDshotTelemetry) {
return true;
}
#ifdef USE_DSHOT_TELEMETRY_STATS
const timeMs_t currentTimeMs = millis();
#endif
for (int i = 0; i < motorCount; i++) {
if (dmaMotors[i].hasTelemetry) {
#ifdef STM32F7
@ -223,12 +245,18 @@ bool pwmStartDshotMotorUpdate(uint8_t motorCount)
value = decodeDshotPacket(dmaMotors[i].dmaBuffer);
}
}
#ifdef USE_DSHOT_TELEMETRY_STATS
bool validTelemetryPacket = false;
#endif
if (value != 0xffff) {
dmaMotors[i].dshotTelemetryValue = value;
dmaMotors[i].dshotTelemetryActive = true;
if (i < 4) {
DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, value);
}
#ifdef USE_DSHOT_TELEMETRY_STATS
validTelemetryPacket = true;
#endif
} else {
dshotInvalidPacketCount++;
if (i == 0) {
@ -236,6 +264,9 @@ bool pwmStartDshotMotorUpdate(uint8_t motorCount)
}
}
dmaMotors[i].hasTelemetry = false;
#ifdef USE_DSHOT_TELEMETRY_STATS
updateDshotTelemetryQuality(&dmaMotors[i].dshotTelemetryQuality, validTelemetryPacket, currentTimeMs);
#endif
} else {
timeDelta_t usSinceInput = cmpTimeUs(micros(), dmaMotors[i].timer->inputDirectionStampUs);
if (usSinceInput >= 0 && usSinceInput < dmaMotors[i].dshotTelemetryDeadtimeUs) {
@ -258,5 +289,22 @@ bool isDshotMotorTelemetryActive(uint8_t motorIndex)
return dmaMotors[motorIndex].dshotTelemetryActive;
}
#endif
#endif
#ifdef USE_DSHOT_TELEMETRY_STATS
int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex)
{
int16_t invalidPercent = 0;
if (dmaMotors[motorIndex].dshotTelemetryActive) {
const uint32_t totalCount = dmaMotors[motorIndex].dshotTelemetryQuality.packetCountSum;
const uint32_t invalidCount = dmaMotors[motorIndex].dshotTelemetryQuality.invalidCountSum;
if (totalCount > 0) {
invalidPercent = lrintf(invalidCount * 10000.0f / totalCount);
}
} else {
invalidPercent = 10000; // 100.00%
}
return invalidPercent;
}
#endif // USE_DSHOT_TELEMETRY_STATS
#endif // USE_DSHOT_TELEMETRY
#endif // USE_DSHOT

View file

@ -20,6 +20,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
@ -204,3 +205,22 @@ void failureMode(failureMode_e mode)
systemResetToBootloader();
#endif
}
void initialiseMemorySections(void)
{
#ifdef USE_ITCM_RAM
/* Load functions into ITCM RAM */
extern uint8_t tcm_code_start;
extern uint8_t tcm_code_end;
extern uint8_t tcm_code;
memcpy(&tcm_code_start, &tcm_code, (size_t) (&tcm_code_end - &tcm_code_start));
#endif
#ifdef USE_FAST_RAM
/* Load FAST_RAM variable intializers into DTCM RAM */
extern uint8_t _sfastram_data;
extern uint8_t _efastram_data;
extern uint8_t _sfastram_idata;
memcpy(&_sfastram_data, &_sfastram_idata, (size_t) (&_efastram_data - &_sfastram_data));
#endif
}

View file

@ -52,6 +52,8 @@ void checkForBootLoaderRequest(void);
bool isMPUSoftReset(void);
void cycleCounterInit(void);
void initialiseMemorySections(void);
void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz

View file

@ -52,6 +52,8 @@
#include "io/serial.h"
#include "io/gps.h"
#include "osd/osd.h"
#include "pg/beeper.h"
#include "pg/beeper_dev.h"
#include "pg/rx.h"
@ -67,6 +69,8 @@
#include "scheduler/scheduler.h"
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
pidProfile_t *currentPidProfile;
#ifndef RX_SPI_DEFAULT_PROTOCOL
@ -201,10 +205,6 @@ static void validateAndFixConfig(void)
if (pidProfilesMutable(i)->dyn_lpf_dterm_min_hz > pidProfilesMutable(i)->dyn_lpf_dterm_max_hz) {
pidProfilesMutable(i)->dyn_lpf_dterm_min_hz = 0;
}
if (pidProfilesMutable(i)->dyn_lpf_dterm_min_hz > 0) {
pidProfilesMutable(i)->dterm_lowpass_hz = 0;
}
#endif
if (pidProfilesMutable(i)->motor_output_limit > 100 || pidProfilesMutable(i)->motor_output_limit == 0) {
@ -465,6 +465,16 @@ static void validateAndFixConfig(void)
}
#endif
#if defined(USE_OSD)
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
const uint16_t t = osdConfig()->timers[i];
if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
osdConfigMutable()->timers[i] = osdTimerDefault[i];
}
}
#endif
#if defined(TARGET_VALIDATECONFIG)
targetValidateConfiguration();
#endif
@ -491,10 +501,6 @@ void validateAndFixGyroConfig(void)
if (gyroConfig()->dyn_lpf_gyro_min_hz > gyroConfig()->dyn_lpf_gyro_max_hz) {
gyroConfigMutable()->dyn_lpf_gyro_min_hz = 0;
}
if (gyroConfig()->dyn_lpf_gyro_min_hz > 0) {
gyroConfigMutable()->gyro_lowpass_hz = 0;
}
#endif
if (gyroConfig()->gyro_hardware_lpf == GYRO_HARDWARE_LPF_1KHZ_SAMPLE) {
@ -627,6 +633,7 @@ static void ValidateAndWriteConfigToEEPROM(bool setConfigured)
writeConfigToEEPROM();
resumeRxPwmPpmSignal();
configIsDirty = false;
}
void writeEEPROM(void)
@ -666,6 +673,16 @@ void saveConfigAndNotify(void)
beeperConfirmationBeeps(1);
}
void setConfigDirty(void)
{
configIsDirty = true;
}
bool isConfigDirty(void)
{
return configIsDirty;
}
void changePidProfileFromCellCount(uint8_t cellCount)
{
if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {

View file

@ -63,6 +63,9 @@ void ensureEEPROMStructureIsValid(void);
void saveConfigAndNotify(void);
void validateAndFixGyroConfig(void);
void setConfigDirty(void);
bool isConfigDirty(void);
uint8_t getCurrentPidProfileIndex(void);
void changePidProfile(uint8_t pidProfileIndex);
void changePidProfileFromCellCount(uint8_t cellCount);

View file

@ -65,6 +65,7 @@
#include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "fc/stats.h"
#include "msp/msp_serial.h"
@ -318,11 +319,12 @@ void updateArmingStatus(void)
&& !flight3DConfig()->switched_mode3d
&& !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_THROTTLE));
#ifdef USE_RUNAWAY_TAKEOFF
if (!IS_RC_MODE_ACTIVE(BOXARM)) {
#ifdef USE_RUNAWAY_TAKEOFF
unsetArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF);
}
#endif
unsetArmingDisabled(ARMING_DISABLED_CRASH_DETECTED);
}
// If arming is disabled and the ARM switch is on
if (isArmingDisabled()
@ -370,8 +372,12 @@ void disarm(void)
#endif
flipOverAfterCrashActive = false;
#ifdef USE_PERSISTENT_STATS
statsOnDisarm();
#endif
// if ARMING_DISABLED_RUNAWAY_TAKEOFF is set then we want to play it's beep pattern instead
if (!(getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF)) {
if (!(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
beeper(BEEPER_DISARMING); // emit disarm tone
}
}
@ -484,6 +490,10 @@ void tryArm(void)
beeper(BEEPER_ARMING);
#endif
#ifdef USE_PERSISTENT_STATS
statsOnArm();
#endif
#ifdef USE_RUNAWAY_TAKEOFF
runawayTakeoffDeactivateUs = 0;
runawayTakeoffAccumulatedUs = 0;
@ -974,6 +984,11 @@ bool processRx(timeUs_t currentTimeUs)
pidSetAntiGravityState(IS_RC_MODE_ACTIVE(BOXANTIGRAVITY) || featureIsEnabled(FEATURE_ANTI_GRAVITY));
#ifdef USE_PERSISTENT_STATS
/* allow the stats collector to do periodic tasks */
statsOnLoop();
#endif
return true;
}
@ -1089,6 +1104,15 @@ static FAST_CODE void subTaskMotorUpdate(timeUs_t currentTimeUs)
writeMotors();
#ifdef USE_DSHOT_TELEMETRY_STATS
if (debugMode == DEBUG_DSHOT_RPM_ERRORS && useDshotTelemetry) {
const uint8_t motorCount = MIN(getMotorCount(), 4);
for (uint8_t i = 0; i < motorCount; i++) {
debug[i] = getDshotTelemetryMotorInvalidPercent(i);
}
}
#endif
DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime);
}

View file

@ -32,7 +32,7 @@
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
#include "common/printf.h"
#include "common/printf_serial.h"
#include "config/config_eeprom.h"
#include "config/feature.h"
@ -226,22 +226,6 @@ dispatchEntry_t activateDshotTelemetryEntry =
void init(void)
{
#ifdef USE_ITCM_RAM
/* Load functions into ITCM RAM */
extern uint8_t tcm_code_start;
extern uint8_t tcm_code_end;
extern uint8_t tcm_code;
memcpy(&tcm_code_start, &tcm_code, (size_t) (&tcm_code_end - &tcm_code_start));
#endif
#ifdef USE_FAST_RAM
/* Load FAST_RAM variable intializers into DTCM RAM */
extern uint8_t _sfastram_data;
extern uint8_t _efastram_data;
extern uint8_t _sfastram_idata;
memcpy(&_sfastram_data, &_sfastram_idata, (size_t) (&_efastram_data - &_sfastram_data));
#endif
#ifdef USE_HAL_DRIVER
HAL_Init();
#endif
@ -262,7 +246,9 @@ void init(void)
}
#endif
printfSupportInit();
#ifdef SERIAL_PORT_COUNT
printfSerialInit();
#endif
systemInit();

View file

@ -470,6 +470,7 @@ static int applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t a
break;
};
setConfigDirty();
return newValue;
}
@ -635,6 +636,7 @@ static int applyAbsoluteAdjustment(controlRateConfig_t *controlRateConfig, adjus
break;
};
setConfigDirty();
return newValue;
}
@ -694,6 +696,7 @@ static uint8_t applySelectAdjustment(adjustmentFunction_e adjustmentFunction, ui
beeperConfirmationBeeps(beeps);
}
setConfigDirty();
return position;
}

View file

@ -208,6 +208,7 @@ void processRcStickPositions()
// before they're able to rearm
unsetArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF);
#endif
unsetArmingDisabled(ARMING_DISABLED_CRASH_DETECTED);
}
}
return;
@ -230,7 +231,7 @@ void processRcStickPositions()
resetTryingToArm();
}
if (ARMING_FLAG(ARMED) || doNotRepeat || rcDelayMs <= STICK_DELAY_MS || (getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF)) {
if (ARMING_FLAG(ARMED) || doNotRepeat || rcDelayMs <= STICK_DELAY_MS || (getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
return;
}
doNotRepeat = true;

View file

@ -40,6 +40,7 @@ const char *armingDisableFlagNames[]= {
"BADRX",
"BOXFAILSAFE",
"RUNAWAY",
"CRASH",
"THROTTLE",
"ANGLE",
"BOOTGRACE",

View file

@ -46,21 +46,22 @@ typedef enum {
ARMING_DISABLED_BAD_RX_RECOVERY = (1 << 3),
ARMING_DISABLED_BOXFAILSAFE = (1 << 4),
ARMING_DISABLED_RUNAWAY_TAKEOFF = (1 << 5),
ARMING_DISABLED_THROTTLE = (1 << 6),
ARMING_DISABLED_ANGLE = (1 << 7),
ARMING_DISABLED_BOOT_GRACE_TIME = (1 << 8),
ARMING_DISABLED_NOPREARM = (1 << 9),
ARMING_DISABLED_LOAD = (1 << 10),
ARMING_DISABLED_CALIBRATING = (1 << 11),
ARMING_DISABLED_CLI = (1 << 12),
ARMING_DISABLED_CMS_MENU = (1 << 13),
ARMING_DISABLED_BST = (1 << 14),
ARMING_DISABLED_MSP = (1 << 15),
ARMING_DISABLED_PARALYZE = (1 << 16),
ARMING_DISABLED_GPS = (1 << 17),
ARMING_DISABLED_RESC = (1 << 18),
ARMING_DISABLED_RPMFILTER = (1 << 19),
ARMING_DISABLED_ARM_SWITCH = (1 << 20), // Needs to be the last element, since it's always activated if one of the others is active when arming
ARMING_DISABLED_CRASH_DETECTED = (1 << 6),
ARMING_DISABLED_THROTTLE = (1 << 7),
ARMING_DISABLED_ANGLE = (1 << 8),
ARMING_DISABLED_BOOT_GRACE_TIME = (1 << 9),
ARMING_DISABLED_NOPREARM = (1 << 10),
ARMING_DISABLED_LOAD = (1 << 11),
ARMING_DISABLED_CALIBRATING = (1 << 12),
ARMING_DISABLED_CLI = (1 << 13),
ARMING_DISABLED_CMS_MENU = (1 << 14),
ARMING_DISABLED_BST = (1 << 15),
ARMING_DISABLED_MSP = (1 << 16),
ARMING_DISABLED_PARALYZE = (1 << 17),
ARMING_DISABLED_GPS = (1 << 18),
ARMING_DISABLED_RESC = (1 << 19),
ARMING_DISABLED_RPMFILTER = (1 << 20),
ARMING_DISABLED_ARM_SWITCH = (1 << 21), // Needs to be the last element, since it's always activated if one of the others is active when arming
} armingDisableFlags_e;
#define ARMING_DISABLE_FLAGS_COUNT (LOG2(ARMING_DISABLED_ARM_SWITCH) + 1)

76
src/main/fc/stats.c Normal file
View file

@ -0,0 +1,76 @@
#include "platform.h"
#ifdef USE_PERSISTENT_STATS
#include "drivers/time.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "fc/stats.h"
#include "io/beeper.h"
#include "io/gps.h"
#include "pg/stats.h"
#define MIN_FLIGHT_TIME_TO_RECORD_STATS_S 10 //prevent recording stats for that short "flights" [s]
#define STATS_SAVE_DELAY_MS 500 //let disarming complete and save stats after this time
static timeMs_t arm_millis;
static uint32_t arm_distance_cm;
static timeMs_t save_pending_millis; // 0 = none
#ifdef USE_GPS
#define DISTANCE_FLOWN_CM (GPS_distanceFlownInCm)
#else
#define DISTANCE_FLOWN_CM (0)
#endif
void statsOnArm(void)
{
arm_millis = millis();
arm_distance_cm = DISTANCE_FLOWN_CM;
}
void statsOnDisarm(void)
{
if (statsConfig()->stats_enabled) {
uint32_t dt = (millis() - arm_millis) / 1000;
if (dt >= MIN_FLIGHT_TIME_TO_RECORD_STATS_S) {
statsConfigMutable()->stats_total_flights += 1; //arm/flight counter
statsConfigMutable()->stats_total_time_s += dt; //[s]
statsConfigMutable()->stats_total_dist_m += (DISTANCE_FLOWN_CM - arm_distance_cm) / 100; //[m]
/* signal that stats need to be saved but don't execute time consuming flash operation
now - let the disarming process complete and then execute the actual save */
save_pending_millis = millis();
}
}
}
void statsOnLoop(void)
{
/* check for pending flash write */
if (save_pending_millis && millis()-save_pending_millis > STATS_SAVE_DELAY_MS) {
if (ARMING_FLAG(ARMED)) {
/* re-armed - don't save! */
}
else {
if (isConfigDirty()) {
/* There are some adjustments made in the configuration and we don't want
to implicitly save it... We can't currently save part of the configuration,
so we simply don't execute the stats save operation at all. This will result
in missing stats update *if* rc-adjustments were made during the flight. */
}
else {
writeEEPROM();
/* repeat disarming beep indicating the stats save is complete */
beeper(BEEPER_DISARMING);
}
}
save_pending_millis = 0;
}
}
#endif

4
src/main/fc/stats.h Normal file
View file

@ -0,0 +1,4 @@
void statsOnArm(void);
void statsOnDisarm(void);
void statsOnLoop(void);

View file

@ -238,10 +238,6 @@ void fcTasksInit(void)
const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || featureIsEnabled(FEATURE_OSD);
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
#ifdef USE_TRANSPONDER
setTaskEnabled(TASK_TRANSPONDER, featureIsEnabled(FEATURE_TRANSPONDER));
#endif
#ifdef STACK_CHECK
setTaskEnabled(TASK_STACK_CHECK, true);
#endif

View file

@ -118,6 +118,7 @@ typedef struct {
#define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate
#define GPS_RESCUE_RATE_SCALE_DEGREES 45 // Scale the commanded yaw rate when the error is less then this angle
#define GPS_RESCUE_SLOWDOWN_DISTANCE_M 200 // distance from home to start decreasing speed
PG_REGISTER_WITH_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 1);
@ -140,7 +141,9 @@ PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig,
.minSats = 8,
.minRescueDth = 100,
.allowArmingWithoutFix = false,
.useMag = true
.useMag = true,
.targetLandingAltitudeM = 5,
.targetLandingDistanceM = 10,
);
static uint16_t rescueThrottle;
@ -470,7 +473,10 @@ static bool checkGPSRescueIsAvailable(void)
*/
void updateGPSRescueState(void)
{
static uint16_t descentDistance;
static uint16_t newDescentDistanceM;
static float_t lineSlope;
static float_t lineOffsetM;
static int32_t newSpeed;
if (!FLIGHT_MODE(GPS_RESCUE_MODE)) {
rescueStop();
@ -513,13 +519,18 @@ void updateGPSRescueState(void)
// When not in failsafe mode: leave it up to the sanity check setting.
}
newSpeed = gpsRescueConfig()->rescueGroundspeed;
//set new descent distance if actual distance to home is lower
if (rescueState.sensor.distanceToHomeM < gpsRescueConfig()->descentDistanceM) {
descentDistance = rescueState.sensor.distanceToHomeM - 5;
newDescentDistanceM = rescueState.sensor.distanceToHomeM - 5;
} else {
descentDistance = gpsRescueConfig()->descentDistanceM;
newDescentDistanceM = gpsRescueConfig()->descentDistanceM;
}
//Calculate angular coefficient and offset for equation of line from 2 points needed for RESCUE_LANDING_APPROACH
lineSlope = ((float)gpsRescueConfig()->initialAltitudeM - gpsRescueConfig()->targetLandingAltitudeM) / (newDescentDistanceM - gpsRescueConfig()->targetLandingDistanceM);
lineOffsetM = gpsRescueConfig()->initialAltitudeM - lineSlope * newDescentDistanceM;
rescueState.phase = RESCUE_ATTAIN_ALT;
FALLTHROUGH;
case RESCUE_ATTAIN_ALT:
@ -535,7 +546,7 @@ void updateGPSRescueState(void)
rescueState.intent.maxAngleDeg = 15;
break;
case RESCUE_CROSSTRACK:
if (rescueState.sensor.distanceToHomeM < descentDistance) {
if (rescueState.sensor.distanceToHomeM <= newDescentDistanceM) {
rescueState.phase = RESCUE_LANDING_APPROACH;
}
@ -549,19 +560,23 @@ void updateGPSRescueState(void)
break;
case RESCUE_LANDING_APPROACH:
// We are getting close to home in the XY plane, get Z where it needs to be to move to landing phase
if (rescueState.sensor.distanceToHomeM < 10 && rescueState.sensor.currentAltitudeCm <= 1000) {
if (rescueState.sensor.distanceToHomeM <= gpsRescueConfig()->targetLandingDistanceM && rescueState.sensor.currentAltitudeCm <= gpsRescueConfig()->targetLandingAltitudeM * 100) {
rescueState.phase = RESCUE_LANDING;
}
// Only allow new altitude and new speed to be equal or lower than the current values (to prevent parabolic movement on overshoot)
const int32_t newAlt = gpsRescueConfig()->initialAltitudeM * 100 * rescueState.sensor.distanceToHomeM / descentDistance;
const int32_t newSpeed = gpsRescueConfig()->rescueGroundspeed * rescueState.sensor.distanceToHomeM / descentDistance;
const int32_t newAlt = (lineSlope * rescueState.sensor.distanceToHomeM + lineOffsetM) * 100;
// Start to decrease proportionally the quad's speed when the distance to home is less or equal than GPS_RESCUE_SLOWDOWN_DISTANCE_M
if (rescueState.sensor.distanceToHomeM <= GPS_RESCUE_SLOWDOWN_DISTANCE_M) {
newSpeed = gpsRescueConfig()->rescueGroundspeed * rescueState.sensor.distanceToHomeM / GPS_RESCUE_SLOWDOWN_DISTANCE_M;
}
rescueState.intent.targetAltitudeCm = constrain(newAlt, 100, rescueState.intent.targetAltitudeCm);
rescueState.intent.targetGroundspeed = constrain(newSpeed, 100, rescueState.intent.targetGroundspeed);
rescueState.intent.crosstrack = true;
rescueState.intent.minAngleDeg = 10;
rescueState.intent.maxAngleDeg = 20;
rescueState.intent.maxAngleDeg = gpsRescueConfig()->angle;
break;
case RESCUE_LANDING:
// We have reached the XYZ envelope to be considered at "home". We need to land gently and check our accelerometer for abnormal data.

View file

@ -25,7 +25,7 @@ typedef struct gpsRescue_s {
uint16_t angle; //degrees
uint16_t initialAltitudeM; //meters
uint16_t descentDistanceM; //meters
uint16_t rescueGroundspeed; // centimeters per second
uint16_t rescueGroundspeed; //centimeters per second
uint16_t throttleP, throttleI, throttleD;
uint16_t yawP;
uint16_t throttleMin;
@ -37,6 +37,8 @@ typedef struct gpsRescue_s {
uint8_t sanityChecks;
uint8_t allowArmingWithoutFix;
uint8_t useMag;
uint16_t targetLandingAltitudeM; //meters
uint16_t targetLandingDistanceM; //meters
} gpsRescueConfig_t;
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);

View file

@ -34,6 +34,7 @@
#include "config/config_reset.h"
#include "drivers/pwm_output.h"
#include "drivers/sound_beeper.h"
#include "drivers/time.h"
@ -127,7 +128,7 @@ static FAST_RAM_ZERO_INIT float airmodeThrottleOffsetLimit;
#define LAUNCH_CONTROL_YAW_ITERM_LIMIT 50 // yaw iterm windup limit when launch mode is "FULL" (all axes)
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, PID_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 9);
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, PID_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 10);
void resetPidProfile(pidProfile_t *pidProfile)
{
@ -168,7 +169,6 @@ void resetPidProfile(pidProfile_t *pidProfile)
.throttle_boost = 5,
.throttle_boost_cutoff = 15,
.iterm_rotation = false,
.smart_feedforward = false,
.iterm_relax = ITERM_RELAX_RP,
.iterm_relax_cutoff = ITERM_RELAX_CUTOFF_DEFAULT,
.iterm_relax_type = ITERM_RELAX_SETPOINT,
@ -181,10 +181,13 @@ void resetPidProfile(pidProfile_t *pidProfile)
.abs_control_error_limit = 20,
.abs_control_cutoff = 11,
.antiGravityMode = ANTI_GRAVITY_SMOOTH,
.dterm_lowpass_hz = 100, // dual PT1 filtering ON by default
.dterm_lowpass2_hz = 200, // second Dterm LPF ON by default
.dterm_filter_type = FILTER_PT1,
.dterm_filter2_type = FILTER_PT1,
.dterm_lowpass_hz = 150, // NOTE: dynamic lpf is enabled by default so this setting is actually
// overridden and the static lowpass 1 is disabled. We can't set this
// value to 0 otherwise Configurator versions 10.4 and earlier will also
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
.dterm_lowpass2_hz = 150, // second Dterm LPF ON by default
.dterm_filter_type = FILTER_BIQUAD,
.dterm_filter2_type = FILTER_BIQUAD,
.dyn_lpf_dterm_min_hz = 150,
.dyn_lpf_dterm_max_hz = 250,
.launchControlMode = LAUNCH_CONTROL_MODE_NORMAL,
@ -202,12 +205,6 @@ void resetPidProfile(pidProfile_t *pidProfile)
.auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY,
.transient_throttle_limit = 15,
);
#ifdef USE_DYN_LPF
pidProfile->dterm_lowpass_hz = 0;
pidProfile->dterm_lowpass2_hz = 150;
pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_filter2_type = FILTER_BIQUAD;
#endif
#ifndef USE_D_MIN
pidProfile->pid[PID_ROLL].D = 30;
pidProfile->pid[PID_PITCH].D = 32;
@ -226,6 +223,9 @@ static void pidSetTargetLooptime(uint32_t pidLooptime)
targetPidLooptime = pidLooptime;
dT = targetPidLooptime * 1e-6f;
pidFrequency = 1.0f / dT;
#ifdef USE_DSHOT
setDshotPidLoopTime(targetPidLooptime);
#endif
}
static FAST_RAM float itermAccelerator = 1.0f;
@ -503,10 +503,6 @@ pt1Filter_t throttleLpf;
#endif
static FAST_RAM_ZERO_INIT bool itermRotation;
#if defined(USE_SMART_FEEDFORWARD)
static FAST_RAM_ZERO_INIT bool smartFeedforward;
#endif
#ifdef USE_LAUNCH_CONTROL
static FAST_RAM_ZERO_INIT uint8_t launchControlMode;
static FAST_RAM_ZERO_INIT uint8_t launchControlAngleLimit;
@ -621,10 +617,6 @@ void pidInitConfig(const pidProfile_t *pidProfile)
antiGravityOsdCutoff += ((itermAcceleratorGain - 1000) / 1000.0f) * 0.25f;
}
#if defined(USE_SMART_FEEDFORWARD)
smartFeedforward = pidProfile->smart_feedforward;
#endif
#if defined(USE_ITERM_RELAX)
itermRelax = pidProfile->iterm_relax;
itermRelaxType = pidProfile->iterm_relax_type;
@ -889,9 +881,14 @@ static void detectAndSetCrashRecovery(
&& fabsf(delta) > crashDtermThreshold
&& fabsf(errorRate) > crashGyroThreshold
&& fabsf(getSetpointRate(axis)) < crashSetpointThreshold) {
if (crash_recovery == PID_CRASH_RECOVERY_DISARM) {
setArmingDisabled(ARMING_DISABLED_CRASH_DETECTED);
disarm();
} else {
inCrashRecoveryMode = true;
crashDetectedAtUs = currentTimeUs;
}
}
if (inCrashRecoveryMode && cmpTimeUs(currentTimeUs, crashDetectedAtUs) < crashTimeDelayUs && (fabsf(errorRate) < crashGyroThreshold
|| fabsf(getSetpointRate(axis)) > crashSetpointThreshold)) {
inCrashRecoveryMode = false;
@ -1059,21 +1056,6 @@ float FAST_CODE applyRcSmoothingDerivativeFilter(int axis, float pidSetpointDelt
}
#endif // USE_RC_SMOOTHING_FILTER
#ifdef USE_SMART_FEEDFORWARD
void FAST_CODE applySmartFeedforward(int axis)
{
if (smartFeedforward) {
if (pidData[axis].P * pidData[axis].F > 0) {
if (fabsf(pidData[axis].F) > fabsf(pidData[axis].P)) {
pidData[axis].P = 0;
} else {
pidData[axis].F = 0;
}
}
}
}
#endif // USE_SMART_FEEDFORWARD
#if defined(USE_ITERM_RELAX)
#if defined(USE_ABSOLUTE_CONTROL)
STATIC_UNIT_TESTED void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPidSetpoint, float *itermErrorRate)
@ -1430,10 +1412,6 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
// no transition if feedForwardTransition == 0
float transition = feedForwardTransition > 0 ? MIN(1.f, getRcDeflectionAbs(axis) * feedForwardTransition) : 1;
pidData[axis].F = feedforwardGain * transition * pidSetpointDelta * pidFrequency;
#if defined(USE_SMART_FEEDFORWARD)
applySmartFeedforward(axis);
#endif
} else {
pidData[axis].F = 0;
}

View file

@ -71,7 +71,8 @@ typedef enum {
typedef enum {
PID_CRASH_RECOVERY_OFF = 0,
PID_CRASH_RECOVERY_ON,
PID_CRASH_RECOVERY_BEEP
PID_CRASH_RECOVERY_BEEP,
PID_CRASH_RECOVERY_DISARM,
} pidCrashRecovery_e;
typedef struct pidf_s {
@ -139,7 +140,6 @@ typedef struct pidProfile_s {
uint8_t throttle_boost; // how much should throttle be boosted during transient changes 0-100, 100 adds 10x hpf filtered throttle
uint8_t throttle_boost_cutoff; // Which cutoff frequency to use for throttle boost. higher cutoffs keep the boost on for shorter. Specified in hz.
uint8_t iterm_rotation; // rotates iterm to translate world errors to local coordinate system
uint8_t smart_feedforward; // takes only the larger of P and the D weight feed forward term if they have the same sign.
uint8_t iterm_relax_type; // Specifies type of relax algorithm
uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
uint8_t iterm_relax; // Enable iterm suppression during stick input

View file

@ -89,7 +89,7 @@ static void rcdeviceCameraControlProcess(void)
// avoid display wifi page when arming, in the next firmware(>2.0) of rcsplit we have change the wifi page logic:
// when the wifi was turn on it won't turn off the analog video output,
// and just put a wifi indicator on the right top of the video output. here is for the old split firmware
if (!ARMING_FLAG(ARMED) && ((getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF) == 0)) {
if (!ARMING_FLAG(ARMED) && !(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN;
}
}
@ -102,7 +102,7 @@ static void rcdeviceCameraControlProcess(void)
case BOXCAMERA3:
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)) {
// avoid change camera mode when arming
if (!ARMING_FLAG(ARMED) && ((getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF) == 0)) {
if (!ARMING_FLAG(ARMED) && !(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE;
}
}
@ -236,7 +236,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
}
#endif
if (ARMING_FLAG(ARMED) || getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF) {
if (ARMING_FLAG(ARMED) || (getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
return;
}

View file

@ -275,6 +275,9 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
if (portConfig->functionMask & FUNCTION_MSP) {
mspPortCount++;
} else if (portConfig->identifier == SERIAL_PORT_USB_VCP) {
// Require MSP to be enabled for the VCP port
return false;
}
uint8_t bitCount = BITCOUNT(portConfig->functionMask);

View file

@ -296,9 +296,9 @@ static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uin
static int emfat_find_log(emfat_entry_t *entry, int maxCount)
{
uint32_t limit = flashfsIdentifyStartOfFreeSpace();
uint32_t lastOffset = 0;
uint32_t currOffset = 0;
int limit = flashfsIdentifyStartOfFreeSpace();
int lastOffset = 0;
int currOffset = 0;
int fileNumber = 0;
uint8_t buffer[18];
int logCount = 0;

View file

@ -1008,6 +1008,11 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU8(dst, currentControlRateProfile->throttle_limit_type);
sbufWriteU8(dst, currentControlRateProfile->throttle_limit_percent);
// added in 1.42
sbufWriteU16(dst, currentControlRateProfile->rate_limit[FD_ROLL]);
sbufWriteU16(dst, currentControlRateProfile->rate_limit[FD_PITCH]);
sbufWriteU16(dst, currentControlRateProfile->rate_limit[FD_YAW]);
break;
case MSP_PID:
@ -1357,13 +1362,12 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU8(dst, compassConfig()->mag_align);
// API 1.41 - Add multi-gyro indicator, selected gyro, and support for separate gyro 1 & 2 alignment
sbufWriteU8(dst, getGyroDetectionFlags());
#ifdef USE_MULTI_GYRO
sbufWriteU8(dst, 1); // USE_MULTI_GYRO
sbufWriteU8(dst, gyroConfig()->gyro_to_use);
sbufWriteU8(dst, gyroDeviceConfig(0)->align);
sbufWriteU8(dst, gyroDeviceConfig(1)->align);
#else
sbufWriteU8(dst, 0);
sbufWriteU8(dst, GYRO_CONFIG_USE_GYRO_1);
sbufWriteU8(dst, gyroDeviceConfig(0)->align);
sbufWriteU8(dst, ALIGN_DEFAULT);
@ -1441,11 +1445,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU16(dst, currentPidProfile->itermAcceleratorGain);
sbufWriteU16(dst, 0); // was currentPidProfile->dtermSetpointWeight
sbufWriteU8(dst, currentPidProfile->iterm_rotation);
#if defined(USE_SMART_FEEDFORWARD)
sbufWriteU8(dst, currentPidProfile->smart_feedforward);
#else
sbufWriteU8(dst, 0);
#endif
#if defined(USE_ITERM_RELAX)
sbufWriteU8(dst, currentPidProfile->iterm_relax);
sbufWriteU8(dst, currentPidProfile->iterm_relax_type);
@ -1859,6 +1859,13 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
currentControlRateProfile->throttle_limit_percent = sbufReadU8(src);
}
// version 1.42
if (sbufBytesRemaining(src) >= 6) {
currentControlRateProfile->rate_limit[FD_ROLL] = sbufReadU16(src);
currentControlRateProfile->rate_limit[FD_PITCH] = sbufReadU16(src);
currentControlRateProfile->rate_limit[FD_YAW] = sbufReadU16(src);
}
initRcProcessing();
} else {
return MSP_RESULT_ERROR;
@ -2114,11 +2121,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
if (sbufBytesRemaining(src) >= 14) {
// Added in MSP API 1.40
currentPidProfile->iterm_rotation = sbufReadU8(src);
#if defined(USE_SMART_FEEDFORWARD)
currentPidProfile->smart_feedforward = sbufReadU8(src);
#else
sbufReadU8(src);
#endif
#if defined(USE_ITERM_RELAX)
currentPidProfile->iterm_relax = sbufReadU8(src);
currentPidProfile->iterm_relax_type = sbufReadU8(src);

View file

@ -62,7 +62,7 @@
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 41 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_MINOR 42 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_LENGTH 2

View file

@ -93,7 +93,8 @@
const char * const osdTimerSourceNames[] = {
"ON TIME ",
"TOTAL ARM",
"LAST ARM "
"LAST ARM ",
"ON/ARM "
};
// Things in both OSD and CMS
@ -120,6 +121,7 @@ static uint8_t osdProfile = 1;
static displayPort_t *osdDisplayPort;
static bool suppressStatsDisplay = false;
static uint8_t osdStatsRowCount = 0;
#ifdef USE_ESC_SENSOR
escSensorData_t *osdEscDataCombined;
@ -197,6 +199,11 @@ static void osdDrawElements(timeUs_t currentTimeUs)
osdDrawActiveElements(osdDisplayPort, currentTimeUs);
}
const uint16_t osdTimerDefault[OSD_TIMER_COUNT] = {
OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10),
OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10)
};
void pgResetFn_osdConfig(osdConfig_t *osdConfig)
{
// Position elements near centre of screen and disabled by default
@ -233,13 +240,17 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
for (int i=0; i < OSD_WARNING_COUNT; i++) {
osdWarnSetState(i, true);
}
// turn off RSSI & Link Quality warnings by default
osdWarnSetState(OSD_WARNING_RSSI, false);
osdWarnSetState(OSD_WARNING_LINK_QUALITY, false);
osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10);
osdConfig->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10);
osdConfig->timers[OSD_TIMER_1] = osdTimerDefault[OSD_TIMER_1];
osdConfig->timers[OSD_TIMER_2] = osdTimerDefault[OSD_TIMER_2];
osdConfig->overlay_radio_mode = 2;
osdConfig->rssi_alarm = 20;
osdConfig->link_quality_alarm = 80;
osdConfig->cap_alarm = 2200;
osdConfig->alt_alarm = 100; // meters or feet depend on configuration
osdConfig->esc_temp_alarm = ESC_TEMP_ALARM_OFF; // off by default
@ -462,13 +473,26 @@ static bool isSomeStatEnabled(void)
// on the stats screen will have to be more beneficial than the hassle of not matching exactly to the
// configurator list.
static void osdShowStats(uint16_t endBatteryVoltage)
static uint8_t osdShowStats(uint16_t endBatteryVoltage, int statsRowCount)
{
uint8_t top = 2;
uint8_t top = 0;
char buff[OSD_ELEMENT_BUFFER_LENGTH];
bool displayLabel = false;
displayClearScreen(osdDisplayPort);
// if statsRowCount is 0 then we're running an initial analysis of the active stats items
if (statsRowCount > 0) {
const int availableRows = osdDisplayPort->rows;
int displayRows = MIN(statsRowCount, availableRows);
if (statsRowCount < availableRows) {
displayLabel = true;
displayRows++;
}
top = (availableRows - displayRows) / 2; // center the stats vertically
}
if (displayLabel) {
displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
}
if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) {
bool success = false;
@ -541,8 +565,7 @@ static void osdShowStats(uint16_t endBatteryVoltage)
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
if (osdStatGetState(OSD_STAT_MAX_CURRENT)) {
itoa(stats.max_current, buff, 10);
strcat(buff, "A");
tfp_sprintf(buff, "%d%c", stats.max_current, SYM_AMP);
osdDisplayStatisticLabel(top++, "MAX CURRENT", buff);
}
@ -603,6 +626,22 @@ static void osdShowStats(uint16_t endBatteryVoltage)
}
}
#endif
return top;
}
static void osdRefreshStats(uint16_t endBatteryVoltage)
{
displayClearScreen(osdDisplayPort);
if (osdStatsRowCount == 0) {
// No stats row count has been set yet.
// Go through the logic one time to determine how many stats are actually displayed.
osdStatsRowCount = osdShowStats(endBatteryVoltage, 0);
// Then clear the screen and commence with normal stats display which will
// determine if the heading should be displayed and also center the content vertically.
displayClearScreen(osdDisplayPort);
}
osdShowStats(endBatteryVoltage, osdStatsRowCount);
}
static void osdShowArmed(void)
@ -629,11 +668,12 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
resumeRefreshAt = currentTimeUs + (REFRESH_1S / 2);
} else if (isSomeStatEnabled()
&& !suppressStatsDisplay
&& (!(getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF)
&& (!(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))
|| !VISIBLE(osdConfig()->item_pos[OSD_WARNINGS]))) { // suppress stats if runaway takeoff triggered disarm and WARNINGS element is visible
osdStatsEnabled = true;
resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S);
endBatteryVoltage = getBatteryVoltage();
osdStatsRowCount = 0; // reset to 0 so it will be recalculated on the next stats refresh
}
armState = ARMING_FLAG(ARMED);
@ -661,7 +701,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
}
if (currentTimeUs >= osdStatsRefreshTimeUs) {
osdStatsRefreshTimeUs = currentTimeUs + REFRESH_1S;
osdShowStats(endBatteryVoltage);
osdRefreshStats(endBatteryVoltage);
}
}
}

View file

@ -26,7 +26,7 @@
#include "sensors/esc_sensor.h"
#define OSD_NUM_TIMER_TYPES 3
#define OSD_NUM_TIMER_TYPES 4
extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define OSD_ELEMENT_BUFFER_LENGTH 32
@ -180,6 +180,7 @@ typedef enum {
OSD_TIMER_SRC_ON,
OSD_TIMER_SRC_TOTAL_ARMED,
OSD_TIMER_SRC_LAST_ARMED,
OSD_TIMER_SRC_ON_OR_ARMED,
OSD_TIMER_SRC_COUNT
} osd_timer_source_e;
@ -203,6 +204,8 @@ typedef enum {
OSD_WARNING_LAUNCH_CONTROL,
OSD_WARNING_GPS_RESCUE_UNAVAILABLE,
OSD_WARNING_GPS_RESCUE_DISABLED,
OSD_WARNING_RSSI,
OSD_WARNING_LINK_QUALITY,
OSD_WARNING_COUNT // MUST BE LAST
} osdWarningsFlags_e;
@ -215,6 +218,8 @@ STATIC_ASSERT(OSD_WARNING_COUNT <= 32, osdwarnings_overflow);
#define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds
extern const uint16_t osdTimerDefault[OSD_TIMER_COUNT];
typedef struct osdConfig_s {
uint16_t item_pos[OSD_ITEM_COUNT];
@ -238,6 +243,7 @@ typedef struct osdConfig_s {
uint8_t ahInvert; // invert the artificial horizon
uint8_t osdProfileIndex;
uint8_t overlay_radio_mode;
uint8_t link_quality_alarm;
} osdConfig_t;
PG_DECLARE(osdConfig_t, osdConfig);

View file

@ -296,6 +296,8 @@ static char osdGetTimerSymbol(osd_timer_source_e src)
case OSD_TIMER_SRC_TOTAL_ARMED:
case OSD_TIMER_SRC_LAST_ARMED:
return SYM_FLY_M;
case OSD_TIMER_SRC_ON_OR_ARMED:
return ARMING_FLAG(ARMED) ? SYM_FLY_M : SYM_ON_M;
default:
return ' ';
}
@ -312,6 +314,8 @@ static timeUs_t osdGetTimerValue(osd_timer_source_e src)
statistic_t *stats = osdGetStats();
return stats->armed_time;
}
case OSD_TIMER_SRC_ON_OR_ARMED:
return ARMING_FLAG(ARMED) ? osdFlyTime : micros();
default:
return 0;
}
@ -674,7 +678,7 @@ static void osdElementFlymode(osdElementParms_t *element)
// 5. ACRO
if (FLIGHT_MODE(FAILSAFE_MODE)) {
strcpy(element->buff, "!FS!");
strcpy(element->buff, "*FS*");
} else if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
strcpy(element->buff, "RESC");
} else if (FLIGHT_MODE(HEADFREE_MODE)) {
@ -846,8 +850,14 @@ static void osdElementMainBatteryUsage(osdElementParms_t *element)
static void osdElementMainBatteryVoltage(osdElementParms_t *element)
{
const int batteryVoltage = (getBatteryVoltage() + 5) / 10;
element->buff[0] = osdGetBatterySymbol(getBatteryAverageCellVoltage());
tfp_sprintf(element->buff + 1, "%2d.%02d%c", getBatteryVoltage() / 100, getBatteryVoltage() % 100, SYM_VOLT);
if (batteryVoltage >= 100) {
tfp_sprintf(element->buff + 1, "%d.%d%c", batteryVoltage / 10, batteryVoltage % 10, SYM_VOLT);
} else {
tfp_sprintf(element->buff + 1, "%d.%d0%c", batteryVoltage / 10, batteryVoltage % 10, SYM_VOLT);
}
}
static void osdElementMotorDiagnostics(osdElementParms_t *element)
@ -1020,7 +1030,7 @@ static void osdElementVtxChannel(osdElementParms_t *element)
static void osdElementWarnings(osdElementParms_t *element)
{
#define OSD_WARNINGS_MAX_SIZE 11
#define OSD_WARNINGS_MAX_SIZE 12
#define OSD_FORMAT_MESSAGE_BUFFER_SIZE (OSD_WARNINGS_MAX_SIZE + 1)
STATIC_ASSERT(OSD_FORMAT_MESSAGE_BUFFER_SIZE <= OSD_ELEMENT_BUFFER_LENGTH, osd_warnings_size_exceeds_buffer_size);
@ -1112,6 +1122,22 @@ static void osdElementWarnings(osdElementParms_t *element)
}
#endif // USE_LAUNCH_CONTROL
// RSSI
if (osdWarnGetState(OSD_WARNING_RSSI) && (getRssiPercent() < osdConfig()->rssi_alarm)) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "RSSI LOW");
SET_BLINK(OSD_WARNINGS);
return;
}
#ifdef USE_RX_LINK_QUALITY_INFO
// Link Quality
if (osdWarnGetState(OSD_WARNING_LINK_QUALITY) && (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm)) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "LINK QUALITY");
SET_BLINK(OSD_WARNINGS);
return;
}
#endif // USE_RX_LINK_QUALITY_INFO
if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " LAND NOW");
SET_BLINK(OSD_WARNINGS);
@ -1280,7 +1306,9 @@ static const uint8_t osdElementDisplayOrder[] = {
OSD_MAIN_BATT_USAGE,
OSD_DISARMED,
OSD_NUMERICAL_HEADING,
#ifdef USE_VARIO
OSD_NUMERICAL_VARIO,
#endif
OSD_COMPASS_BAR,
OSD_ANTI_GRAVITY,
#ifdef USE_BLACKBOX
@ -1518,6 +1546,14 @@ void osdUpdateAlarms(void)
CLR_BLINK(OSD_RSSI_VALUE);
}
#ifdef USE_RX_LINK_QUALITY_INFO
if (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm) {
SET_BLINK(OSD_LINK_QUALITY);
} else {
CLR_BLINK(OSD_LINK_QUALITY);
}
#endif // USE_RX_LINK_QUALITY_INFO
if (getBatteryState() == BATTERY_OK) {
CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
@ -1559,7 +1595,7 @@ void osdUpdateAlarms(void)
CLR_BLINK(OSD_REMAINING_TIME_ESTIMATE);
}
if (alt >= osdConfig()->alt_alarm) {
if ((alt >= osdConfig()->alt_alarm) && ARMING_FLAG(ARMED)) {
SET_BLINK(OSD_ALTITUDE);
} else {
CLR_BLINK(OSD_ALTITUDE);

View file

@ -141,7 +141,8 @@
#define PG_RPM_FILTER_CONFIG 544
#define PG_LED_STRIP_STATUS_MODE_CONFIG 545 // Used to hold the configuration for the LED_STRIP status mode (not built on targets with limited flash)
#define PG_VTX_TABLE_CONFIG 546
#define PG_BETAFLIGHT_END 546
#define PG_STATS_CONFIG 547
#define PG_BETAFLIGHT_END 547
// OSD configuration (subject to change)

39
src/main/pg/stats.c Normal file
View file

@ -0,0 +1,39 @@
/*
* 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 "platform.h"
#ifdef USE_PERSISTENT_STATS
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "stats.h"
PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 1);
PG_RESET_TEMPLATE(statsConfig_t, statsConfig,
.stats_enabled = 0,
.stats_total_flights = 0,
.stats_total_time_s = 0,
.stats_total_dist_m = 0,
);
#endif

33
src/main/pg/stats.h Normal file
View file

@ -0,0 +1,33 @@
/*
* 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/>.
*/
#pragma once
#include "pg/pg.h"
#include "drivers/io_types.h"
typedef struct statsConfig_s {
uint32_t stats_total_flights;
uint32_t stats_total_time_s; // [s]
uint32_t stats_total_dist_m; // [m]
uint8_t stats_enabled;
} statsConfig_t;
PG_DECLARE(statsConfig_t, statsConfig);

View file

@ -86,7 +86,7 @@
FAST_RAM_ZERO_INIT gyro_t gyro;
static FAST_RAM_ZERO_INIT uint8_t gyroDebugMode;
static uint8_t gyroToUse = 0;
static FAST_RAM_ZERO_INIT uint8_t gyroToUse;
static FAST_RAM_ZERO_INIT bool overflowDetected;
#ifdef USE_GYRO_OVERFLOW_CHECK
@ -167,6 +167,8 @@ STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor1;
STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor2;
#endif
static gyroDetectionFlags_t gyroDetectionFlags = NO_GYROS_DETECTED;
#ifdef UNIT_TEST
STATIC_UNIT_TESTED gyroSensor_t * const gyroSensorPtr = &gyroSensor1;
STATIC_UNIT_TESTED gyroDev_t * const gyroDevPtr = &gyroSensor1.gyroDev;
@ -201,10 +203,13 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
gyroConfig->gyroMovementCalibrationThreshold = 48;
gyroConfig->gyro_sync_denom = GYRO_SYNC_DENOM_DEFAULT;
gyroConfig->gyro_hardware_lpf = GYRO_HARDWARE_LPF_NORMAL;
gyroConfig->gyro_lowpass_type = FILTER_PT1;
gyroConfig->gyro_lowpass_hz = 100;
gyroConfig->gyro_lowpass2_type = FILTER_PT1;
gyroConfig->gyro_lowpass2_hz = 300;
gyroConfig->gyro_lowpass_type = FILTER_BIQUAD;
gyroConfig->gyro_lowpass_hz = 150; // NOTE: dynamic lpf is enabled by default so this setting is actually
// overridden and the static lowpass 1 is disabled. We can't set this
// value to 0 otherwise Configurator versions 10.4 and earlier will also
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
gyroConfig->gyro_lowpass2_type = FILTER_BIQUAD;
gyroConfig->gyro_lowpass2_hz = 0;
gyroConfig->gyro_high_fsr = false;
gyroConfig->gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT;
gyroConfig->gyro_soft_notch_hz_1 = 0;
@ -221,11 +226,6 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
gyroConfig->dyn_notch_width_percent = 8;
gyroConfig->dyn_notch_q = 120;
gyroConfig->dyn_notch_min_hz = 150;
#ifdef USE_DYN_LPF
gyroConfig->gyro_lowpass_hz = 0;
gyroConfig->gyro_lowpass_type = FILTER_BIQUAD;
gyroConfig->gyro_lowpass2_hz = 0;
#endif
gyroConfig->gyro_filter_debug_axis = FD_ROLL;
}
@ -393,7 +393,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
}
if (gyroHardware != GYRO_NONE) {
detectedSensors[SENSOR_INDEX_GYRO] = gyroHardware;
sensorsSet(SENSOR_GYRO);
}
@ -411,25 +410,31 @@ static void gyroPreInitSensor(const gyroDeviceConfig_t *config)
#endif
}
static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
static bool gyroDetectSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
#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) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20)
if (!mpuDetect(&gyroSensor->gyroDev, config)) {
return false;
}
#else
UNUSED(config);
#endif
const gyroHardware_e gyroHardware = gyroDetect(&gyroSensor->gyroDev);
gyroSensor->gyroDev.gyroHardware = gyroHardware;
return gyroHardware != GYRO_NONE;
}
static void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
gyroSensor->gyroDebugAxis = gyroConfig()->gyro_filter_debug_axis;
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
gyroSensor->gyroDev.gyroAlign = config->align;
gyroSensor->gyroDev.mpuIntExtiTag = config->extiTag;
#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) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20)
mpuDetect(&gyroSensor->gyroDev, config);
#endif
const gyroHardware_e gyroHardware = gyroDetect(&gyroSensor->gyroDev);
gyroSensor->gyroDev.gyroHardware = gyroHardware;
if (gyroHardware == GYRO_NONE) {
return false;
}
// Must set gyro targetLooptime before gyroDev.init and initialisation of filters
gyro.targetLooptime = gyroSetSampleRate(&gyroSensor->gyroDev, gyroConfig()->gyro_hardware_lpf, gyroConfig()->gyro_sync_denom);
gyroSensor->gyroDev.hardware_lpf = gyroConfig()->gyro_hardware_lpf;
@ -437,7 +442,7 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *c
// As new gyros are supported, be sure to add them below based on whether they are subject to the overflow/inversion bug
// Any gyro not explicitly defined will default to not having built-in overflow protection as a safe alternative.
switch (gyroHardware) {
switch (gyroSensor->gyroDev.gyroHardware) {
case GYRO_NONE: // Won't ever actually get here, but included to account for all gyro types
case GYRO_DEFAULT:
case GYRO_FAKE:
@ -471,8 +476,6 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *c
gyroDataAnalyseStateInit(&gyroSensor->gyroAnalyseState, gyro.targetLooptime);
#endif
return true;
}
void gyroPreInit(void)
@ -511,69 +514,71 @@ bool gyroInit(void)
case DEBUG_DUAL_GYRO_COMBINE:
case DEBUG_DUAL_GYRO_DIFF:
case DEBUG_DUAL_GYRO_RAW:
case DEBUG_DUAL_GYRO_SCALED:
useDualGyroDebugging = true;
break;
}
firstArmingCalibrationWasStarted = false;
enum {
NO_GYROS_DETECTED = 0,
DETECTED_GYRO_1 = (1 << 0),
DETECTED_GYRO_2 = (1 << 1),
};
uint8_t detectionFlags = NO_GYROS_DETECTED;
gyroDetectionFlags = NO_GYROS_DETECTED;
gyroToUse = gyroConfig()->gyro_to_use;
if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
if (gyroInitSensor(&gyroSensor1, gyroDeviceConfig(0))) {
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor1.gyroDev.gyroHasOverflowProtection;
detectionFlags |= DETECTED_GYRO_1;
}
if (gyroDetectSensor(&gyroSensor1, gyroDeviceConfig(0))) {
gyroDetectionFlags |= DETECTED_GYRO_1;
}
#ifdef USE_MULTI_GYRO
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
if (gyroInitSensor(&gyroSensor2, gyroDeviceConfig(1))) {
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor2.gyroDev.gyroHasOverflowProtection;
detectionFlags |= DETECTED_GYRO_2;
}
}
if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && detectionFlags != (DETECTED_GYRO_1 | DETECTED_GYRO_2)) {
// at least one gyro is missing.
if (detectionFlags & DETECTED_GYRO_1) {
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
gyroConfigMutable()->gyro_to_use = GYRO_CONFIG_USE_GYRO_1;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor1.gyroDev.gyroHardware;
sensorsSet(SENSOR_GYRO);
return true;
}
if (detectionFlags & DETECTED_GYRO_2) {
gyroToUse = GYRO_CONFIG_USE_GYRO_2;
gyroConfigMutable()->gyro_to_use = GYRO_CONFIG_USE_GYRO_2;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor2.gyroDev.gyroHardware;
sensorsSet(SENSOR_GYRO);
return true;
}
}
// Only allow using both gyros simultaneously if they are the same hardware type.
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.
if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
if (gyroSensor1.gyroDev.gyroHardware != gyroSensor2.gyroDev.gyroHardware) {
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
gyroConfigMutable()->gyro_to_use = GYRO_CONFIG_USE_GYRO_1;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor1.gyroDev.gyroHardware;
sensorsSet(SENSOR_GYRO);
}
#if defined(USE_MULTI_GYRO)
if (gyroDetectSensor(&gyroSensor2, gyroDeviceConfig(1))) {
gyroDetectionFlags |= DETECTED_GYRO_2;
}
#endif
return detectionFlags != NO_GYROS_DETECTED;
if (gyroDetectionFlags == NO_GYROS_DETECTED) {
return false;
}
#if defined(USE_MULTI_GYRO)
if ((gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && !((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_1 && !(gyroDetectionFlags & DETECTED_GYRO_1))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_2 && !(gyroDetectionFlags & DETECTED_GYRO_2))) {
if (gyroDetectionFlags & DETECTED_GYRO_1) {
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
} else {
gyroToUse = GYRO_CONFIG_USE_GYRO_2;
}
gyroConfigMutable()->gyro_to_use = gyroToUse;
}
// Only allow using both gyros simultaneously if they are the same hardware type.
if (((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS) && gyroSensor1.gyroDev.gyroHardware == gyroSensor2.gyroDev.gyroHardware) {
gyroDetectionFlags |= DETECTED_DUAL_GYROS;
} else if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
gyroConfigMutable()->gyro_to_use = gyroToUse;
}
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyroSensor2, gyroDeviceConfig(1));
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor2.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor2.gyroDev.gyroHardware;
}
#endif
if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyroSensor1, gyroDeviceConfig(0));
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor1.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor1.gyroDev.gyroHardware;
}
return true;
}
gyroDetectionFlags_t getGyroDetectionFlags(void)
{
return gyroDetectionFlags;
}
#ifdef USE_DYN_LPF
@ -1094,6 +1099,8 @@ FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DUAL_GYRO, 1, lrintf(gyroSensor1.gyroDev.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 0, lrintf(gyro.gyroADCf[X]));
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 1, lrintf(gyro.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale));
}
break;
#ifdef USE_MULTI_GYRO
@ -1117,6 +1124,8 @@ FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DUAL_GYRO, 3, lrintf(gyroSensor2.gyroDev.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 2, lrintf(gyro.gyroADCf[X]));
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 3, lrintf(gyro.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale));
}
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
@ -1148,6 +1157,10 @@ FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 0, lrintf(gyroSensor1.gyroDev.gyroADCf[X] - gyroSensor2.gyroDev.gyroADCf[X]));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 1, lrintf(gyroSensor1.gyroDev.gyroADCf[Y] - gyroSensor2.gyroDev.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 2, lrintf(gyroSensor1.gyroDev.gyroADCf[Z] - gyroSensor2.gyroDev.gyroADCf[Z]));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale));
}
break;
#endif

View file

@ -36,18 +36,18 @@ typedef struct gyro_s {
extern gyro_t gyro;
typedef enum {
enum {
GYRO_OVERFLOW_CHECK_NONE = 0,
GYRO_OVERFLOW_CHECK_YAW,
GYRO_OVERFLOW_CHECK_ALL_AXES
} gyroOverflowCheck_e;
};
enum {
DYN_NOTCH_RANGE_HIGH = 0,
DYN_NOTCH_RANGE_MEDIUM,
DYN_NOTCH_RANGE_LOW,
DYN_NOTCH_RANGE_AUTO
} ;
};
#define DYN_NOTCH_RANGE_HZ_HIGH 2000
#define DYN_NOTCH_RANGE_HZ_MEDIUM 1333
@ -63,10 +63,20 @@ enum {
#define GYRO_CONFIG_USE_GYRO_2 1
#define GYRO_CONFIG_USE_GYRO_BOTH 2
typedef enum {
enum {
FILTER_LOWPASS = 0,
FILTER_LOWPASS2
} filterSlots;
};
typedef enum gyroDetectionFlags_e {
NO_GYROS_DETECTED = 0,
DETECTED_GYRO_1 = (1 << 0),
#if defined(USE_MULTI_GYRO)
DETECTED_GYRO_2 = (1 << 1),
DETECTED_BOTH_GYROS = (DETECTED_GYRO_1 | DETECTED_GYRO_2),
DETECTED_DUAL_GYROS = (1 << 7), // All gyros are of the same hardware type
#endif
} gyroDetectionFlags_t;
typedef struct gyroConfig_s {
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
@ -125,6 +135,7 @@ bool gyroOverflowDetected(void);
bool gyroYawSpinDetected(void);
uint16_t gyroAbsRateDps(int axis);
uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg);
gyroDetectionFlags_t getGyroDetectionFlags(void);
#ifdef USE_DYN_LPF
float dynThrottle(float throttle);
void dynLpfGyroUpdate(float throttle);

View file

@ -102,6 +102,7 @@
#include "platform.h"
#include "stm32f30x.h"
#include "drivers/system.h"
uint32_t hse_value = HSE_VALUE;
@ -160,6 +161,8 @@ void SetSysClock(void);
*/
void SystemInit(void)
{
initialiseMemorySections();
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */

View file

@ -316,6 +316,7 @@
#include <string.h>
#include "stm32f4xx.h"
#include "drivers/system.h"
#include "system_stm32f4xx.h"
#include "platform.h"
#include "drivers/persistent.h"
@ -506,6 +507,8 @@ void systemClockSetHSEValue(uint32_t frequency)
void SystemInit(void)
{
initialiseMemorySections();
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
@ -854,6 +857,28 @@ uint32_t pllsai_m;
#undef RCC_PLLSAI_GET_FLAG
#endif /* STM32F446xx */
// Configure PLLI2S for 27MHz operation
// Use pll_input (1 or 2) to derive multiplier N for
// 108MHz (27 * 4) PLLI2SCLK with R divider fixed at 2.
// 108MHz will further be prescaled by 4 by mcoInit.
#define PLLI2S_TARGET_FREQ_MHZ (27 * 4)
#define PLLI2S_R 2
uint32_t plli2s_n = (PLLI2S_TARGET_FREQ_MHZ * PLLI2S_R) / pll_input;
#ifdef STM32F40_41xxx
RCC_PLLI2SConfig(plli2s_n, PLLI2S_R);
#elif defined(STM32F411xE)
RCC_PLLI2SConfig(plli2s_n, PLLI2S_R, pll_m);
#elif defined(STM32F446xx)
RCC_PLLI2SConfig(pll_m, plli2s_n, 2, 2, PLLI2S_R); // M, N, P, Q, R
#else
#error Unsupported MCU
#endif
RCC_PLLI2SCmd(ENABLE);
SystemCoreClockUpdate();
}

View file

@ -64,6 +64,7 @@
*/
#include "stm32f7xx.h"
#include "drivers/system.h"
#include "system_stm32f7xx.h"
#include "platform.h"
#include "drivers/persistent.h"
@ -308,6 +309,8 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
*/
void SystemInit(void)
{
initialiseMemorySections();
SystemInitOC();
SystemCoreClock = (pll_n / pll_p) * 1000000;

View file

@ -0,0 +1,38 @@
/*
* 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 "telemetry/telemetry.h"
#include "pg/piniobox.h"
void targetConfiguration(void)
{
telemetryConfigMutable()->halfDuplex = false;
pinioBoxConfigMutable()->permanentId[0] = 40;
}
#endif

View file

@ -0,0 +1,38 @@
/*
* 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 <stdint.h>
#include "platform.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // S2_OUT - DMA1_ST2
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 0, 1 ), // S3_OUT - DMA1_ST6
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0 ), // S4_OUT - DMA1_ST1
DEF_TIM(TIM1, CH3, PA10, TIM_USE_CAMERA_CONTROL, 0, 0 ),
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0 ), // LED - DMA1_ST3
};

View file

@ -0,0 +1,170 @@
/*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "RACE"
#define USBD_PRODUCT_STRING "RacePit"
#define USE_TARGET_CONFIG
/*--------------LED----------------*/
#define LED0_PIN PB9
#define LED1_PIN PB8
/*---------------------------------*/
/*------------BEEPER---------------*/
#define USE_BEEPER
#define BEEPER_PIN PB3
#define BEEPER_INVERTED
/*---------------------------------*/
/*---------- VTX POWER SWITCH---------*/
#define USE_PINIO
#define PINIO1_PIN PC0 // VTX power switcher
#define USE_PINIOBOX
/*------------SENSORS--------------*/
// MPU interrupt
#define USE_EXTI
#define GYRO_1_INT_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_ACC
#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6000
#define GYRO_1_CS_PIN SPI1_NSS_PIN
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_ALIGN CW90_DEG_FLIP
/*---------------------------------*/
/*-------------OSD-----------------*/
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
/*---------------------------------*/
/*------------FLASH----------------*/
#define FLASH_CS_PIN PA15
#define FLASH_SPI_INSTANCE SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
/*---------------------------------*/
/*-----------USB-UARTs-------------*/
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PC11
#define UART3_TX_PIN PC10
#define INVERTER_PIN_UART3 PC15
#define USE_UART4
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
/*---------------------------------*/
/*-------------SPIs----------------*/
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
/*---------------------------------*/
/*-------------I2C-----------------*/
#define USE_I2C
#define USE_I2C_PULLUP
#define USE_I2C_DEVICE_3
#define I2C_DEVICE (I2CDEV_3)
#define I2C3_SCL PA8
#define I2C3_SDA PC9
/*---------------------------------*/
/*-------------ADCs----------------*/
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define VBAT_ADC_PIN PC2
#define CURRENT_METER_ADC_PIN PC1
/*---------------------------------*/
/*-------------ESCs----------------*/
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_PIN PB0 // (HARDWARE=0)
/*---------------------------------*/
/*--------DEFAULT VALUES-----------*/
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3
#define DEFAULT_FEATURES ( FEATURE_LED_STRIP | FEATURE_OSD | FEATURE_MOTOR_STOP )
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
/*---------------------------------*/
/*--------------TIMERS-------------*/
#define USABLE_TIMER_CHANNEL_COUNT 6
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
/*---------------------------------*/

View file

@ -0,0 +1,7 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/max7456.c\
drivers/pinio.c

View file

@ -0,0 +1,36 @@
/*
* 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 <stdint.h>
#include "platform.h"
#include "io/serial.h"
#include "pg/piniobox.h"
#include "target.h"
#define USE_TARGET_CONFIG
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = 40;
pinioBoxConfigMutable()->permanentId[1] = 41;
}

View file

@ -0,0 +1,44 @@
/*
* 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 <stdint.h>
#include "platform.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1), // S1_OUT 2,1
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 1), // S2_OUT 2,2
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR, 0, 0), // S3_OUT 2,6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S4_OUT 1,7
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S5_OUT 1,4
//DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S6_OUT 1,5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), // RSSI 1,2
DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 1), // RX2 1,0
DEF_TIM(TIM2, CH3, PB10, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM CC 1,1
DEF_TIM(TIM2, CH4, PB11, TIM_USE_LED, 0, 0), // LED 1,6
};

View file

@ -0,0 +1,147 @@
/*
* 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/>.
*/
#pragma once
#define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "FW41"
#define USBD_PRODUCT_STRING "FLYWOOF411"
#define LED0_PIN PC13
#define USE_BEEPER
#define BEEPER_PIN PC14
#define BEEPER_INVERTED
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define GYRO_1_CS_PIN PA4
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_ALIGN CW180_DEG
#define USE_EXTI
#define USE_GYRO_EXTI
#define GYRO_1_EXTI_PIN PB3
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_ICM20689
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_ICM20689
// *************** Baro **************************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB8 // SCL pad
#define I2C1_SDA PB9 // SDA pad
#define BARO_I2C_INSTANCE (I2CDEV_1)
#define USE_BARO //External, connect to I2C1
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_MAG
#define USE_MAG_HMC5883 //External, connect to I2C1
#define USE_MAG_QMC5883
// *************** UART *****************************
#define USE_VCP
#define USB_DETECT_PIN PC15
#define USE_USB_DETECT
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
// *************** OSD/FLASH *****************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PB12
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define FLASH_CS_PIN PB2
#define FLASH_SPI_INSTANCE SPI2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
#define VBAT_ADC_PIN PA0
#define CURRENT_METER_ADC_PIN PA1
#define RSSI_ADC_PIN PB1
//#define EXTERNAL1_ADC_PIN PA4
#define USE_ESCSERIAL
#define USE_LED_STRIP
#define USE_PINIO
#define PINIO1_PIN PB5 // VTX switcher
#define PINIO2_PIN PA15 // Camera switcher
#define USE_PINIOBOX
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL | FEATURE_LED_STRIP)
#define CURRENT_METER_SCALE_DEFAULT 170
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(5)|TIM_N(9) )

View file

@ -0,0 +1,13 @@
F411_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/max7456.c

View file

@ -0,0 +1 @@
#KAKUTEF7MINI.mk file

View file

@ -24,13 +24,12 @@
#ifdef KAKUTEF7V2
#define TARGET_BOARD_IDENTIFIER "KT76"
#define USBD_PRODUCT_STRING "KakuteF7-V2"
#elif defined(KAKUTEF7MINI)
#define TARGET_BOARD_IDENTIFIER "KF7M"
#define USBD_PRODUCT_STRING "KakuteF7-Mini"
#else
#define TARGET_BOARD_IDENTIFIER "KTF7"
#endif
#ifdef KAKUTEF7V2
#define USBD_PRODUCT_STRING "KakuteF7-V2"
#else
#define USBD_PRODUCT_STRING "KakuteF7"
#endif
@ -122,6 +121,13 @@
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#if defined(KAKUTEF7MINI)
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define FLASH_CS_PIN SPI1_NSS_PIN
#define FLASH_SPI_INSTANCE SPI1
#else
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
@ -130,6 +136,9 @@
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
#define SPI1_TX_DMA_OPT 1 // DMA 2 Stream 5 Channel 3
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream5
#endif
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)

View file

@ -4,7 +4,11 @@ else
F7X5XG_TARGETS += $(TARGET)
endif
ifeq ($(TARGET), KAKUTEF7MINI)
FEATURES += VCP ONBOARDFLASH
else
FEATURES += SDCARD_SPI VCP
endif
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View file

@ -0,0 +1 @@
#SYNERGYF4

View file

@ -32,6 +32,23 @@
#include "pg/max7456.h"
#include "pg/pg.h"
#ifdef SYNERGYF4
#include "io/vtx.h"
#include "io/ledstrip.h"
#include "fc/config.h"
#include "pg/piniobox.h"
#include "common/axis.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "drivers/pwm_output.h"
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_RX_SERIAL },
{ SERIAL_PORT_USART3, FUNCTION_VTX_SMARTAUDIO },
};
#endif
#ifdef EXUAVF4PRO
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_TELEMETRY_SMARTPORT },
@ -51,5 +68,14 @@ void targetConfiguration(void)
#ifdef EXUAVF4PRO
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
#endif
#ifdef SYNERGYF4
pinioBoxConfigMutable()->permanentId[0] = 39;
vtxSettingsConfigMutable()->pitModeFreq = 0;
ledStripStatusModeConfigMutable()->ledConfigs[0] = DEFINE_LED(0, 0, 0, 0, LF(COLOR), LO(VTX), 0);
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT600;
gyroConfigMutable()->gyro_sync_denom = 1; // 8kHz gyro
pidConfigMutable()->pid_process_denom = 1; // 8kHz PID
#endif
}
#endif

View file

@ -50,10 +50,16 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#if defined(OMNIBUSF4SD) || defined(EXUAVF4PRO)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S5_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
#elif defined(SYNERGYF4)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED strip
#else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S5_OUT
#endif
#if defined(SYNERGYF4)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL
#else
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S6_OUT
#endif
DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, 0, 0), // UART1_TX
DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE, 0, 0), // UART1_RX
};

View file

@ -32,6 +32,9 @@
#define TARGET_BOARD_IDENTIFIER "XRF4"
#elif defined(EXUAVF4PRO)
#define TARGET_BOARD_IDENTIFIER "EXF4"
#elif defined(SYNERGYF4)
#define TARGET_BOARD_IDENTIFIER "SYN4"
#define TARGET_MANUFACTURER_IDENTIFIER "KLEE"
#else
#define TARGET_BOARD_IDENTIFIER "OBF4"
// Example of a manufacturer ID to be persisted as part of the config:
@ -47,6 +50,8 @@
#define USBD_PRODUCT_STRING "XRACERF4"
#elif defined(EXUAVF4PRO)
#define USBD_PRODUCT_STRING "ExuavF4Pro"
#elif defined(SYNERGYF4)
#define USBD_PRODUCT_STRING "SynergyF4"
#else
#define USBD_PRODUCT_STRING "OmnibusF4"
#endif
@ -93,6 +98,9 @@
#elif defined(XRACERF4) || defined(EXUAVF4PRO)
#define GYRO_1_ALIGN CW90_DEG
#define ACC_1_ALIGN CW90_DEG
#elif defined(SYNERGYF4)
#define GYRO_1_ALIGN CW0_DEG_FLIP
#define ACC_1_ALIGN CW0_DEG_FLIP
#else
#define GYRO_1_ALIGN CW180_DEG
#define ACC_1_ALIGN CW180_DEG
@ -113,12 +121,15 @@
#define GYRO_2_EXTI_PIN NONE
#define ACC_2_ALIGN ALIGN_DEFAULT
#if !defined(SYNERGYF4) //No mag sensor on SYNERGYF4
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
#endif
#if !defined(SYNERGYF4) //No baro sensor on SYNERGYF4
#define USE_BARO
#if defined(OMNIBUSF4SD)
#define USE_BARO_SPI_BMP280
@ -135,6 +146,7 @@
#else
#define DEFAULT_BARO_BMP280
#endif
#endif
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
@ -278,7 +290,11 @@
#define RANGEFINDER_HCSR04_ECHO_PIN PA8
#define USE_RANGEFINDER_TF
#if defined(SYNERGYF4)
#define DEFAULT_FEATURES (FEATURE_LED_STRIP | FEATURE_OSD | FEATURE_AIRMODE)
#else
#define DEFAULT_FEATURES (FEATURE_OSD)
#endif
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
@ -295,3 +311,8 @@
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) )
#endif
#if defined(SYNERGYF4)
#define USE_PINIO
#define PINIO1_PIN PB15 // VTX power switcher
#define USE_PINIOBOX
#endif

View file

@ -34,9 +34,9 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// MOTORS
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //S1
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), //S1
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), //S2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), //S3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //S3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), //S4
};

View file

@ -0,0 +1,45 @@
/*
* 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 <stdint.h>
#include "platform.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM&SBUS
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S1
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S3
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S4
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S5
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // S6
DEF_TIM(TIM2, CH4, PB11, TIM_USE_LED, 0, 0), // LED STRIP
//DEF_TIM(TIM3, CH4, PB1, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_CAMERA_CONTROL, 0, 0),
};

View file

@ -0,0 +1,142 @@
/*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "RSF7"
#define USBD_PRODUCT_STRING "RUSHCORE7"
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PC13
#define USE_BEEPER
#define BEEPER_PIN PB1
#define BEEPER_INVERTED
//#define BEEPER_PWM_HZ 1100
#define USE_EXTI
#define USE_GYRO_EXTI
#define USE_MPU_DATA_READY_SIGNAL
#define USE_ACC
#define USE_GYRO
#define USE_GYRO_MPU6000
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
#define USE_ACC_MPU6000
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define GYRO_1_CS_PIN PA4
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_EXTI_PIN PC4
#define GYRO_1_ALIGN CW270_DEG_FLIP
#define USE_BARO
#define USE_BARO_MS5611
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_UART4
#define USE_UART5
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define SERIAL_PORT_COUNT 6
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE I2CDEV_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define USE_SPI
#define USE_SPI_DEVICE_1 //GYRO/ACC
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2 //MAX7456
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PB12
#define USE_SPI_DEVICE_3 // FLASH
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define FLASH_CS_PIN PC15
#define FLASH_SPI_INSTANCE SPI3
#define USE_ADC
#define ADC_INSTANCE ADC3
#define ADC3_DMA_STREAM DMA2_Stream0
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC3
#define RSSI_ADC_PIN PA0
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define USE_OSD
#define USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES FEATURE_OSD
#define SERIALRX_UART SERIAL_PORT_USART2
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9) )

View file

@ -0,0 +1,13 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/max7456.c

View file

@ -293,14 +293,6 @@
#endif
#endif
// F4 and F7 single gyro boards
#if defined(USE_MULTI_GYRO) && !defined(GYRO_2_SPI_INSTANCE)
#define GYRO_2_SPI_INSTANCE GYRO_1_SPI_INSTANCE
#define GYRO_2_CS_PIN NONE
#define GYRO_2_ALIGN ALIGN_DEFAULT
#define GYRO_2_EXTI_PIN NONE
#endif
#if !defined(GYRO_1_SPI_INSTANCE)
#define GYRO_1_SPI_INSTANCE NULL
#endif
@ -317,6 +309,14 @@
#define GYRO_1_ALIGN ALIGN_DEFAULT
#endif
// F4 and F7 single gyro boards
#if defined(USE_MULTI_GYRO) && !defined(GYRO_2_SPI_INSTANCE)
#define GYRO_2_SPI_INSTANCE GYRO_1_SPI_INSTANCE
#define GYRO_2_CS_PIN NONE
#define GYRO_2_ALIGN ALIGN_DEFAULT
#define GYRO_2_EXTI_PIN NONE
#endif
#if defined(MPU_ADDRESS)
#define GYRO_I2C_ADDRESS MPU_ADDRESS
#else

View file

@ -258,17 +258,17 @@
#undef USE_GYRO_DATA_ANALYSE
#endif
#ifndef USE_DSHOT
#undef USE_DSHOT_TELEMETRY
#undef USE_RPM_FILTER
#endif
#ifndef USE_CMS
#undef USE_CMS_FAILSAFE_MENU
#endif
#ifndef USE_DSHOT
#undef USE_DSHOT_TELEMETRY
#endif
#ifndef USE_DSHOT_TELEMETRY
#undef USE_RPM_FILTER
#undef USE_DSHOT_TELEMETRY_STATS
#endif
#if !defined(USE_BOARD_INFO)
@ -280,6 +280,10 @@
#undef USE_ACRO_TRAINER
#endif
#if (!defined(USE_GPS_RESCUE) || !defined(USE_CMS_FAILSAFE_MENU))
#undef USE_CMS_GPS_RESCUE_MENU
#endif
#ifndef USE_BEEPER
#undef BEEPER_PIN
#undef BEEPER_PWM_HZ

View file

@ -54,6 +54,7 @@
#endif
#define USE_DSHOT
#define USE_DSHOT_TELEMETRY
#define USE_DSHOT_TELEMETRY_STATS
#define USE_RPM_FILTER
#define I2C3_OVERCLOCK true
#define USE_GYRO_DATA_ANALYSE
@ -62,6 +63,7 @@
#define USE_USB_CDC_HID
#define USE_USB_MSC
#define USE_PERSISTENT_MSC_RTC
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
// Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
@ -79,6 +81,7 @@
#define USE_FAST_RAM
#define USE_DSHOT
#define USE_DSHOT_TELEMETRY
#define USE_DSHOT_TELEMETRY_STATS
#define USE_RPM_FILTER
#define I2C3_OVERCLOCK true
#define I2C4_OVERCLOCK true
@ -295,9 +298,11 @@
#define USE_ESCSERIAL_SIMONK
#define USE_SERIAL_4WAY_SK_BOOTLOADER
#define USE_CMS_FAILSAFE_MENU
#define USE_CMS_GPS_RESCUE_MENU
#define USE_SMART_FEEDFORWARD
#define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
// Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
//#define USE_VTX_TABLE
#define USE_PERSISTENT_STATS
#endif

View file

@ -34,5 +34,6 @@ MEMORY
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
REGION_ALIAS("VECTAB", RAM)
INCLUDE "stm32_flash_split.ld"

View file

@ -20,6 +20,8 @@ TARGET_DIR = $(USER_DIR)/target
include $(ROOT)/make/system-id.mk
include $(ROOT)/make/targets_list.mk
VPATH := $(VPATH):$(USER_DIR):$(TEST_DIR)
# specify which files that are included in the test in addition to the unittest file.
# variables available:
# <test_name>_SRC
@ -658,4 +660,3 @@ target_list:
@echo $(foreach target,$(ALT_TARGETS),$(target)\>$(call get_base_target,$(target)))
@echo ========== ALT/BASE FULL MAPPING ==========
@echo $(foreach target,$(VALID_TARGETS),$(target)\>$(call get_base_target,$(target)))

View file

@ -17,7 +17,6 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <limits.h>
@ -55,9 +54,12 @@ extern "C" {
void cliSet(char *cmdline);
void cliGet(char *cmdline);
int cliGetSettingIndex(char *name, uint8_t length);
const clivalue_t valueTable[] = {
{ "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 }
{ "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 },
{ "str_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, 0 }, PG_RESERVED_FOR_TESTING_1, 0 },
{ "wos_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, STRING_FLAGS_WRITEONCE }, PG_RESERVED_FOR_TESTING_1, 0 },
};
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
const lookupTableEntry_t lookupTables[] = {};
@ -87,21 +89,20 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
TEST(CLIUnittest, TestCliSet)
TEST(CLIUnittest, TestCliSetArray)
{
char *str = (char *)"array_unit_test = 123, -3 , 1";
cliSet(str);
cliSet((char *)"array_unit_test = 123, -3 , 1");
const uint16_t index = cliGetSettingIndex(str, 15);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t cval = {
.name = "array_unit_test",
.type = MODE_ARRAY | MASTER_VALUE | VAR_INT8,
.pgn = PG_RESERVED_FOR_TESTING_1,
.offset = 0
};
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
int8_t *data = (int8_t *)cliGetValuePointer(&cval);
for(int i=0; i<3; i++){
int8_t *data = (int8_t *)cliGetValuePointer(&val);
for(int i=0; i < val.config.array.length; i++){
printf("data[%d] = %d\n", i, data[i]);
}
printf("\n===============================\n");
@ -116,6 +117,82 @@ TEST(CLIUnittest, TestCliSet)
//EXPECT_EQ(false, false);
}
TEST(CLIUnittest, TestCliSetStringNoFlags)
{
char *str = (char *)"str_unit_test = SAMPLE";
cliSet(str);
const uint16_t index = cliGetSettingIndex(str, 13);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
}
TEST(CLIUnittest, TestCliSetStringWriteOnce)
{
char *str1 = (char *)"wos_unit_test = SAMPLE";
char *str2 = (char *)"wos_unit_test = ELPMAS";
cliSet(str1);
const uint16_t index = cliGetSettingIndex(str1, 13);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
cliSet(str2);
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
cliSet(str1);
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
printf("\n");
}
// STUBS
extern "C" {

View file

@ -517,7 +517,7 @@ TEST(OsdTest, TestAlarms)
printf("%d\n", i);
#endif
displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI);
displayPortTestBufferSubstring(12, 1, "%c16.80%c", SYM_BATT_FULL, SYM_VOLT);
displayPortTestBufferSubstring(12, 1, "%c16.8%c", SYM_BATT_FULL, SYM_VOLT);
displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer
displayPortTestBufferSubstring(20, 1, "%c01:", SYM_ON_M); // only test the minute part of the timer
displayPortTestBufferSubstring(23, 7, " .0%c", SYM_M);
@ -546,7 +546,7 @@ TEST(OsdTest, TestAlarms)
#endif
if (i % 2 == 0) {
displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI);
displayPortTestBufferSubstring(12, 1, "%c13.50%c", SYM_MAIN_BATT, SYM_VOLT);
displayPortTestBufferSubstring(12, 1, "%c13.5%c", SYM_MAIN_BATT, SYM_VOLT);
displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer
displayPortTestBufferSubstring(20, 1, "%c02:", SYM_ON_M); // only test the minute part of the timer
displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M);

View file

@ -79,6 +79,7 @@ extern "C" {
float getRcDeflection(int axis) { return simulatedRcDeflection[axis]; }
void beeperConfirmationBeeps(uint8_t) { }
bool isLaunchControlActive(void) {return unitLaunchControlActive; }
void disarm(void) { }
}
pidProfile_t *pidProfile;
@ -130,7 +131,6 @@ void setDefaultTestSettings(void) {
pidProfile->throttle_boost = 0;
pidProfile->throttle_boost_cutoff = 15;
pidProfile->iterm_rotation = false;
pidProfile->smart_feedforward = false,
pidProfile->iterm_relax = ITERM_RELAX_OFF,
pidProfile->iterm_relax_cutoff = 11,
pidProfile->iterm_relax_type = ITERM_RELAX_SETPOINT,

Some files were not shown because too many files have changed in this diff Show more