Skip to content

Commit

Permalink
Merge branch 'iNavFlight:master' into nav_rth_climb_first_stage
Browse files Browse the repository at this point in the history
  • Loading branch information
MrD-RC authored Oct 9, 2021
2 parents 7db8605 + d3a95d8 commit 2762f25
Show file tree
Hide file tree
Showing 180 changed files with 2,730 additions and 2,780 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ else()
include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake")
endif()

project(INAV VERSION 3.1.0)
project(INAV VERSION 4.0.0)

enable_language(ASM)

Expand Down
10 changes: 7 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@

![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png)

# INAV Community

* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
* [INAV Official on Telegram](https://t.me/INAVFlight)

## Features

* Runs on the most popular F4 and F7 flight controllers
Expand Down Expand Up @@ -47,9 +54,6 @@ See: https://github.com/iNavFlight/inav/blob/master/docs/Installation.md
* [Wing Tuning Masterclass](docs/INAV_Wing_Tuning_Masterclass.pdf)
* [Official documentation](https://github.com/iNavFlight/inav/tree/master/docs)
* [Official Wiki](https://github.com/iNavFlight/inav/wiki)
* [INAV Official on Telegram](https://t.me/INAVFlight)
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
* [Video series by Painless360](https://www.youtube.com/playlist?list=PLYsWjANuAm4qdXEGFSeUhOZ10-H8YTSnH)
* [Video series by Paweł Spychalski](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLloACrA6f1_daCjhqY2x0fB)

Expand Down
12 changes: 6 additions & 6 deletions cmake/arm-none-eabi-checks.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@ include(gcc)
set(arm_none_eabi_triplet "arm-none-eabi")

# Keep version in sync with the distribution files below
set(arm_none_eabi_gcc_version "9.3.1")
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/9-2020q2/gcc-arm-none-eabi-9-2020-q2-update")
set(arm_none_eabi_gcc_version "10.2.1")
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10-2020q4/gcc-arm-none-eabi-10-2020-q4-major")
# suffix and checksum
set(arm_none_eabi_win32 "win32.zip" 184b3397414485f224e7ba950989aab6)
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 2b9eeccc33470f9d3cda26983b9d2dc6)
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 000b0888cbe7b171e2225b29be1c327c)
set(arm_none_eabi_gcc_macos "mac.tar.bz2" 75a171beac35453fd2f0f48b3cb239c3)
set(arm_none_eabi_win32 "win32.zip" 5ee6542a2af847934177bc8fa1294c0d)
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 8312c4c91799885f222f663fc81f9a31)
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 1c3b8944c026d50362eef1f01f329a8e)
set(arm_none_eabi_gcc_macos "mac.tar.bz2" e588d21be5a0cc9caa60938d2422b058)

function(arm_none_eabi_gcc_distname var)
string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url})
Expand Down
2 changes: 2 additions & 0 deletions cmake/stm32f3.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@ main_sources(STM32F3_SRC
target/system_stm32f30x.c

config/config_streamer_stm32f3.c
config/config_streamer_ram.c
config/config_streamer_extflash.c

drivers/adc_stm32f30x.c
drivers/bus_i2c_stm32f30x.c
Expand Down
7 changes: 5 additions & 2 deletions cmake/stm32f4.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ main_sources(STM32F4_SRC
target/system_stm32f4xx.c

config/config_streamer_stm32f4.c
config/config_streamer_ram.c
config/config_streamer_extflash.c

drivers/adc_stm32f4xx.c
drivers/adc_stm32f4xx.c
Expand Down Expand Up @@ -124,6 +126,7 @@ exclude_basenames(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F411_OR_F427_STDPERIPH_
set(STM32F411_COMPILE_DEFINITIONS
STM32F411xE
MCU_FLASH_SIZE=512
OPTIMIZATION -Os
)

function(target_stm32f411xe name)
Expand All @@ -132,9 +135,9 @@ function(target_stm32f411xe name)
STARTUP startup_stm32f411xe.s
SOURCES ${STM32F411_OR_F427_STDPERIPH_SRC}
COMPILE_DEFINITIONS ${STM32F411_COMPILE_DEFINITIONS}
LINKER_SCRIPT stm32_flash_f411xe
LINKER_SCRIPT stm32_flash_f411xe
SVD STM32F411
${ARGN}
${ARGN}
)
endfunction()

Expand Down
2 changes: 2 additions & 0 deletions cmake/stm32f7.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ main_sources(STM32F7_SRC
target/system_stm32f7xx.c

config/config_streamer_stm32f7.c
config/config_streamer_ram.c
config/config_streamer_extflash.c

drivers/adc_stm32f7xx.c
drivers/bus_i2c_hal.c
Expand Down
4 changes: 3 additions & 1 deletion cmake/stm32h7.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,8 @@ main_sources(STM32H7_SRC
target/system_stm32h7xx.c

config/config_streamer_stm32h7.c
config/config_streamer_ram.c
config/config_streamer_extflash.c

drivers/adc_stm32h7xx.c
drivers/bus_i2c_hal.c
Expand Down Expand Up @@ -217,4 +219,4 @@ macro(define_target_stm32h7 subfamily size)
endfunction()
endmacro()

define_target_stm32h7(43 i)
define_target_stm32h7(43 i)
6 changes: 3 additions & 3 deletions docs/Boards.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,20 +30,20 @@ These boards are well tested with INAV and are known to be of good quality and r
It's possible to find more supported and tested boards [here](https://github.com/iNavFlight/inav/wiki/Welcome-to-INAV,-useful-links-and-products)
### Boards documentation

See the [docs](https://github.com/iNavFlight/inav/tree/master/docs) folder for additional information regards to many targets in INAV, to example help in finding pinout and features. _Feel free to help improve the docs._
See the [docs/boards](https://github.com/iNavFlight/inav/tree/master/docs/boards) folder for additional information regards to many targets in INAV, to example help in finding pinout and features. _Feel free to help improve the docs._

### Boards based on F4/F7 CPUs

These boards are powerful and in general support everything INAV is capable of. Limitations are quite rare and are usually caused by hardware design issues.

### Boards based on F3 CPUs

Boards based on F3 boards will be supported for as long as practical, sometimes with reduced features due to lack of resources. No new features will be added so F3 boards are not recommended for new builds.
Boards based on STM32F3 MCUs are no longer supported by latest INAV version. Last release is 2.6.1.

### Boards based on F1 CPUs

Boards based on STM32F1 CPUs are no longer supported by latest INAV version. Last release is 1.7.3

### Not recommended for new setups

F1 and F3 boards are no longer recommended. Users should choose a board from the supported F4 or F7 devices available in the latest release.
F1 and F3 boards are no longer recommended. Users should choose a board from the supported F4 or F7 devices available in the latest release.
1 change: 1 addition & 0 deletions docs/Controls.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ The stick positions are combined to activate different functions:
| Save setting | LOW | LOW | LOW | HIGH |
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |

For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/).
![Stick Positions](assets/images/StickPositions.png)

## Yaw control
Expand Down
25 changes: 15 additions & 10 deletions docs/Failsafe.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,22 +9,23 @@ Failsafe is a state the flight controller is meant to enter when the radio recei
If the failsafe happens while the flight controller is disarmed, it only prevent arming. If it happens while armed, the failsafe policy configured in `failsafe_procedure` is engaged. The available procedures are:

* __DROP:__ Just kill the motors and disarm (crash the craft).
* __SET-THR:__ Enable auto-level mode (for multirotor) or enter preconfigured roll/pitch/yaw spiral down (for airplanes) and set the throttle to a predefined value (`failsafe_throttle`) for a predefined time (`failsafe_off_delay`). This is meant to get the craft to a safe-ish landing (or more realistically, a controlled crash), it doesn't require any extra sensor other than gyros and accelerometers.
* __RTH:__ (Return To Home) One of the key features of inav, it automatically navigates the craft back to the home position and (optionally) lands it. Similarly to all other automated navigation methods, it requires GPS for any type of craft, plus compass and barometer for multicopters.
* __LAND:__ (replaces **SET-THR** from INAV V3.1.0) Performs an Emergency Landing. Enables auto-level mode (for multirotor) or enters a preconfigured roll/pitch/yaw spiral down (for airplanes). If altitude sensors are working an actively controlled descent is performed using the Emergency Landing descent speed (`nav_emerg_landing_speed`). If altitude sensors are unavailable descent is performed with the throttle set to a predefined value (`failsafe_throttle`). The descent can be limited to a predefined time (`failsafe_off_delay`) after which the craft disarms. This is meant to get the craft to a safe-ish landing (or more realistically, a controlled crash), Other than using altitude sensors for an actively controlled descent it doesn't require any extra sensors other than gyros and accelerometers.
* __SET-THR:__ (Pre INAV V3.1.0) Same as **LAND** except it doesn't use an Emergency Landing but is limited instead to just setting the throttle to a predefined value (`failsafe_throttle`) to perform a descent. It doesn't require any extra sensors other than gyros and accelerometers.
* __RTH:__ (Return To Home) One of the key features of INAV, it automatically navigates the craft back to the home position and (optionally) lands it. Similarly to all other automated navigation methods, it requires GPS for any type of craft, plus compass and barometer for multicopters.
* __NONE:__ Do nothing. This is meant to let the craft perform a fully automated flight (eg. waypoint flight) outside of radio range. Highly unsafe when used with manual flight.

Note that:
* Should the failsafe disarm the flight controller (**DROP**, **SET-THR** after `failsafe_off_delay` or **RTH** with `nav_disarm_on_landing` ON), the flight controller will be disarmed and re-arming will be locked until the signal from the receiver is restored for 30 seconds AND the arming switch is in the OFF position (when an arm switch is in use).
* Should the failsafe disarm the flight controller (**DROP**, **LAND/SET-THR** after `failsafe_off_delay` or **RTH** with `nav_disarm_on_landing` ON), the flight controller will be disarmed and re-arming will be locked until the signal from the receiver is restored for 30 seconds AND the arming switch is in the OFF position (when an arm switch is in use).

* Prior to starting failsafe it is checked if the throttle position has been below `min_throttle` for the last `failsafe_throttle_low_delay` seconds. If it was, the craft is assumed to be on the ground and is simply disarmed. This feature can be disabled completely by setting `failsafe_throttle_low_delay` to zero, which may be necessary to do if the craft may fly long with zero throttle (eg. gliders).

## Notes about safety

* If the craft is landed but armed, the failsafe may make the motors and props spin again and even make the craft take off (in case of **RTH** failsafe). Take expecially care of this when using `MOTOR_STOP` feature. **Props will spin up without warning**. Have a look at the `failsafe_throttle_low_delay` setting explained above to learn when this could happen.

* If any required navigation sensor becomes unavailable during a Return to Home (eg. loss of GPS fix), an emergency landing similar to **SET-THR** but with barometer support will be performed after a short timeout. An emergency landing would also be performed right when the failsafe is triggered if any required sensor is reported as unavailable.
* If any required navigation sensor becomes unavailable during a Return to Home (eg. loss of GPS fix), an emergency landing, as used by the **LAND** procedure, will be performed after a short timeout. An emergency landing would also be performed right when the failsafe is triggered if any required sensor is reported as unavailable.

* **SET-THR** doesn't control the descend in any other way than setting a fixed throttle. Thus, appropriate testing must be performed to find the right throttle value. Consider that a constant throttle setting will yield different thrusts depending on battery voltage, so when you evaluate the throttle value do it with a loaded battery. Failure to do so may cause a flyaway.
* The **SET-THR** procedure doesn't control descent in any way other than setting a fixed throttle. This is also the case for the **LAND** procedure when altitude sensors are unavailable. Thus, appropriate testing must be performed to find the right throttle value. Consider that a constant throttle setting will yield different thrusts depending on battery voltage, so when you evaluate the throttle value do it with a loaded battery. Failure to do so may cause a flyaway.

* When the failsafe mode is aborted (RC signal restored/failsafe switch set to OFF), the current stick positions will be enforced immediately. Be ready to react quickly.

Expand All @@ -48,7 +49,7 @@ Failsafe delays are configured in 0.1 second units. Distances are in centimeters

#### `failsafe_procedure`

Selects the failsafe procedure. Valid procedures are **DROP**, **SET-THR**, **RTH** and **NONE**. See above for a description of each one.
Selects the failsafe procedure. Valid procedures are **DROP**, **LAND/SET-THR**, **RTH** and **NONE**. See above for a description of each one.

#### `failsafe_delay`

Expand Down Expand Up @@ -122,25 +123,29 @@ Enables landing when home position is reached. If OFF the craft will hover indef

Instructs the flight controller to disarm the craft when landing is detected

### Parameters relevant to **SET-THR** failsafe procedure
### Parameters relevant to **LAND/SET-THR** failsafe procedure

#### `failsafe_off_delay`

Delay after failsafe activates before motors finally turn off. This is the amount of time 'failsafe_throttle' is active. If you fly at higher altitudes you may need more time to descend safely. Set to zero to keep `failsafe_throttle` active indefinitely.

#### `nav_emerg_landing_speed`

(**LAND** only) Actively controlled descent speed when altitude sensors are available. If altitude sensors aren't available landing descent falls back to using the fixed thottle setting `failsafe_throttle` so ensure this is also set correctly.

#### `failsafe_throttle`

Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec. Default is set to 1000 which should correspond to throttle off.

#### `failsafe_fw_roll_angle`

This parameter defines amount of roll angle (in 1/10 deg units) to execute on failsafe. Negative = LEFT
This parameter defines the amount of roll angle (in 1/10 deg units) to execute on failsafe. Negative = LEFT

#### `failsafe_fw_pitch_angle`

This parameter defines amount of pitch angle (in 1/10 deg units) to execute on `SET-THR` failsafe for an airplane. Negative = CLIMB
This parameter defines the amount of pitch angle (in 1/10 deg units) to execute on failsafe for an airplane. Negative = CLIMB

#### `failsafe_fw_yaw_rate`

This parameter defines amount of yaw rate (in deg per second units) to execute on `SET-THR` failsafe for an airplane. Negative = LEFT
This parameter defines the amount of yaw rate (in deg per second units) to execute on failsafe for an airplane. Negative = LEFT

28 changes: 19 additions & 9 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -914,7 +914,7 @@ Time in deciseconds to wait before activating failsafe when signal is lost. See

### failsafe_fw_pitch_angle

Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb
Amount of dive/climb when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb

| Default | Min | Max |
| --- | --- | --- |
Expand All @@ -924,7 +924,7 @@ Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine.

### failsafe_fw_roll_angle

Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll
Amount of banking when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll

| Default | Min | Max |
| --- | --- | --- |
Expand All @@ -934,7 +934,7 @@ Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In

### failsafe_fw_yaw_rate

Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn
Requested yaw rate to execute when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn

| Default | Min | Max |
| --- | --- | --- |
Expand Down Expand Up @@ -1018,7 +1018,7 @@ What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Fai

| Default | Min | Max |
| --- | --- | --- |
| SET-THR | | |
| LAND | | |

---

Expand Down Expand Up @@ -1678,7 +1678,7 @@ _// TODO_

| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 1 |
| 0 | 0 | 2 |

---

Expand Down Expand Up @@ -1948,7 +1948,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements

| Default | Min | Max |
| --- | --- | --- |
| 2500 | | 65535 |
| 1000 | | 65535 |

---

Expand All @@ -1958,7 +1958,7 @@ Inertial Measurement Unit KP Gain for compass measurements

| Default | Min | Max |
| --- | --- | --- |
| 10000 | | 65535 |
| 5000 | | 65535 |

---

Expand Down Expand Up @@ -2478,7 +2478,7 @@ Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100

| Default | Min | Max |
| --- | --- | --- |
| 70 | 0 | 100 |
| 35 | 0 | 100 |

---

Expand Down Expand Up @@ -4562,6 +4562,16 @@ Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD st

---

### osd_stats_page_auto_swap_time

Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0.

| Default | Min | Max |
| --- | --- | --- |
| 3 | 0 | 10 |

---

### osd_telemetry

To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`
Expand Down Expand Up @@ -5724,7 +5734,7 @@ These are values (in us) by how much RC input can be different before it's consi

### yaw_lpf_hz

Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)
Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)

| Default | Min | Max |
| --- | --- | --- |
Expand Down
1 change: 1 addition & 0 deletions docs/Telemetry.md
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@ The following sensors are transmitted
* **0430** : if `frsky_pitch_roll = ON` set this will be pitch degrees*10
* **0440** : if `frsky_pitch_roll = ON` set this will be roll degrees*10
* **0450** : 'Flight Path Vector' or 'Course over ground' in degrees*10
* **0460** : Azimuth in degrees*10
### Compatible SmartPort/INAV telemetry flight status

To quickly and easily monitor these SmartPort sensors and flight modes, install [OpenTX Telemetry Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.
Expand Down
File renamed without changes.
File renamed without changes.
4 changes: 2 additions & 2 deletions docs/Board - AnyFC F7.md → docs/boards/AnyFC F7.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ Airplanes

Buzzer is supported with additional switching MOSFET transistor when connected to PWM Output #9.

![Buzzer](assets/images/anyfcf7_buzzer_pwm9.png)
![Buzzer](../assets/images/anyfcf7_buzzer_pwm9.png)

## SD Card Detection

Expand All @@ -83,4 +83,4 @@ Buzzer is supported with additional switching MOSFET transistor when connected t

# AnyFC F7 Pro from Banggood

This board is not yet officially supported. It _should_ work but INAV devs did not tested it yet. Use on your own responsibility
This board is not yet officially supported. It _should_ work but INAV devs did not tested it yet. Use on your own responsibility
File renamed without changes.
2 changes: 1 addition & 1 deletion docs/Board - BetFPVF722.md → docs/boards/BetFPVF722.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,4 @@ BetFPVF722 does not have I2C pads broken out. I2C is shared with UART3

> I2C and UART3 can not be used at the same time! Connect the serial receiver to a different serial port when I2C device like MAG is used.
![BetaFPVF722 I2C](assets/betafpvf722.png)
![BetaFPVF722 I2C](../assets/betafpvf722.png)
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
# Board - [MATEKSYS F405-Wing](https://inavflight.com/shop/p/MATEKF405WING)

![Matek F405 Wing](https://quadmeup.com/wp-content/uploads/2018/12/DSC_0007.jpg)

## Specification:

* STM32F405 CPU
Expand All @@ -22,4 +20,4 @@

## Where to buy:

* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Loading

0 comments on commit 2762f25

Please sign in to comment.