1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-17 05:15:23 +03:00

Merge branch 'master' into abo_mission_restart_option

This commit is contained in:
breadoven 2021-10-29 10:05:10 +01:00 committed by GitHub
commit e18173f8bd
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
316 changed files with 6245 additions and 5101 deletions

View file

@ -30,7 +30,7 @@ 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
@ -38,7 +38,7 @@ These boards are powerful and in general support everything INAV is capable of.
### 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
@ -46,4 +46,4 @@ Boards based on STM32F1 CPUs are no longer supported by latest INAV version. Las
### 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.

View file

@ -34,10 +34,12 @@ The stick positions are combined to activate different functions:
| Trim Acc Forwards | HIGH | CENTER | HIGH | CENTER |
| Trim Acc Backwards | HIGH | CENTER | LOW | CENTER |
| Save current waypoint mission | LOW | CENTER | HIGH | LOW |
| Load/unload current waypoint mission | LOW | CENTER | HIGH | HIGH |
| Load current waypoint mission | LOW | CENTER | HIGH | HIGH |
| Unload waypoint mission | LOW | CENTER | LOW | HIGH |
| 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

View file

@ -9,12 +9,13 @@ 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).
@ -22,9 +23,9 @@ Note that:
* 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.
@ -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`
@ -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

View file

@ -28,7 +28,6 @@ The following adjustments can be made in flight as well as on the ground.
* Throttle Expo
* Pitch, Roll, Yaw Rates
* Pitch, Roll, Yaw PIDs
* Rate profile
* Manual rates
* FW cruise_throttle, pitch2thr, min_throttle_down_pitch_angle
* Board alignment
@ -62,7 +61,7 @@ Hint: With OpenTX transmitters you can combine two momentary OFF-ON switches to
The CLI command `adjrange` is used to configure adjustment ranges.
12 adjustment ranges can be defined.
20 adjustment ranges can be defined.
4 adjustments can be made at the same time, each simultaneous adjustment requires an adjustment slot.
Show the current ranges using:
@ -77,12 +76,12 @@ Configure a range using:
| Argument | Value | Meaning |
| -------- | ----- |-------- |
| Index | 0 - 11 | Select the adjustment range to configure |
| Index | 0 - 19 | Select the adjustment range to configure |
| Slot | 0 - 3 | Select the adjustment slot to use |
| Range Channel | 0 based index, AUX1 = 0, AUX2 = 1 | The AUX channel to use to select an adjustment for a switch/pot |
| Range Start | 900 - 2100. Steps of 25, e.g. 900, 925, 950... | Start of range |
| Range End | 900 - 2100 | End of range |
| Adjustment function | 0 - 11 | See Adjustment function table |
| Adjustment function | 0 - 56 | See Adjustment function table |
| Adjustment channel | 0 based index, AUX1 = 0, AUX2 = 1 | The channel that is controlled by a 3 Position switch/Pot |
Range Start/End values should match the values sent by your receiver.
@ -100,8 +99,8 @@ this reason ensure that you define enough ranges to cover the range channel's us
### Adjustment function
| Value | Adjustment | Notes |
| ----- | ---------- |------ |
| Value | Adjustment |
| ----- | ---------- |
| 0 | None |
| 1 | RC RATE |
| 2 | RC_EXPO |
@ -111,47 +110,54 @@ this reason ensure that you define enough ranges to cover the range channel's us
| 6 | PITCH_ROLL_P |
| 7 | PITCH_ROLL_I |
| 8 | PITCH_ROLL_D |
| 9 | YAW_P |
| 10 | YAW_I |
| 11 | YAW_D_FF |
| 12 | RATE_PROFILE | Switch between 3 rate profiles using a 3 position switch. |
| 13 | PITCH_RATE |
| 14 | ROLL_RATE |
| 15 | PITCH_P |
| 16 | PITCH_I |
| 17 | PITCH_D_FF |
| 18 | ROLL_P |
| 19 | ROLL_I |
| 20 | ROLL_D_FF |
| 21 | RC_YAW_EXPO |
| 22 | MANUAL_RC_EXPO |
| 23 | MANUAL_RC_YAW_EXPO |
| 24 | MANUAL_PITCH_ROLL_RATE |
| 25 | MANUAL_ROLL_RATE |
| 26 | MANUAL_PITCH_RATE |
| 27 | MANUAL_YAW_RATE |
| 28 | NAV_FW_CRUISE_THROTTLE |
| 29 | NAV_FW_PITCH2THR |
| 30 | ROLL_BOARD_ALIGNMENT |
| 31 | PITCH_BOARD_ALIGNMENT |
| 32 | LEVEL_P |
| 33 | LEVEL_I |
| 34 | LEVEL_D |
| 35 | POS_XY_P |
| 36 | POS_XY_I |
| 37 | POS_XY_D |
| 38 | POS_Z_P |
| 39 | POS_Z_I |
| 40 | POS_Z_D |
| 41 | HEADING_P |
| 42 | VEL_XY_P |
| 43 | VEL_XY_I |
| 44 | VEL_XY_D |
| 45 | VEL_Z_P |
| 46 | VEL_Z_I |
| 47 | VEL_Z_D |
| 48 | FW_MIN_THROTTLE_DOWN_PITCH_ANGLE |
| 49 | ADJUSTMENT_VTX_POWER_LEVEL |
| 9 | PITCH_ROLL_FF |
| 10 | PITCH_P |
| 11 | PITCH_I |
| 12 | PITCH_D |
| 13 | PITCH_FF |
| 14 | ROLL_P |
| 15 | ROLL_I |
| 16 | ROLL_D |
| 17 | ROL_FF |
| 18 | YAW_P |
| 19 | YAW_I |
| 20 | YAW_D |
| 21 | YAW_FF
| 22 | Unused |
| 23 | PITCH_RATE |
| 24 | ROLL_RATE |
| 25 | RC_YAW_EXPO |
| 26 | MANUAL_RC_EXPO |
| 27 | MANUAL_RC_YAW_EXPO |
| 28 | MANUAL_PITCH_ROLL_RATE |
| 29 | MANUAL_ROLL_RATE |
| 30 | MANUAL_PITCH_RATE |
| 31 | MANUAL_YAW_RATE |
| 32 | NAV_FW_CRUISE_THROTTLE |
| 33 | NAV_FW_PITCH2THR |
| 34 | ROLL_BOARD_ALIGNMENT |
| 35 | PITCH_BOARD_ALIGNMENT |
| 36 | LEVEL_P |
| 37 | LEVEL_I |
| 38 | LEVEL_D |
| 39 | POS_XY_P |
| 40 | POS_XY_I |
| 41 | POS_XY_D |
| 42 | POS_Z_P |
| 43 | POS_Z_I |
| 44 | POS_Z_D |
| 45 | HEADING_P |
| 46 | VEL_XY_P |
| 47 | VEL_XY_I |
| 48 | VEL_XY_D |
| 49 | VEL_Z_P |
| 50 | VEL_Z_I |
| 51 | VEL_Z_D |
| 52 | FW_MIN_THROTTLE_DOWN_PITCH_ANGLE |
| 53 | ADJUSTMENT_VTX_POWER_LEVEL |
| 54 | TPA |
| 55 | TPA_BREAKPOINT |
| 56 | NAV_FW_CONTROL_SMOOTHNESS |
## Examples
@ -193,9 +199,9 @@ range.
adjrange 3 2 1 900 1150 6 3
adjrange 4 2 1 1150 1300 7 3
adjrange 5 2 1 1300 1500 8 3
adjrange 6 2 1 1500 1700 9 3
adjrange 7 2 1 1700 1850 10 3
adjrange 8 2 1 1850 2100 11 3
adjrange 6 2 1 1500 1700 18 3
adjrange 7 2 1 1700 1850 19 3
adjrange 8 2 1 1850 2100 20 3
```
explained:
@ -210,38 +216,19 @@ explained:
(1) in the range 1300-1500 then use adjustment Pitch/Roll D (8) when aux 4
(3) is in the appropriate position.
* configure adjrange 6 to use adjustment slot 3 (2) so that when aux2
(1) in the range 1500-1700 then use adjustment Yaw P (9) when aux 4
(1) in the range 1500-1700 then use adjustment Yaw P (18) when aux 4
(3) is in the appropriate position.
* configure adjrange 7 to use adjustment slot 3 (2) so that when aux2
(1) in the range 1700-1850 then use adjustment Yaw I (10) when aux 4
(1) in the range 1700-1850 then use adjustment Yaw I (19) when aux 4
(3) is in the appropriate position.
* configure adjrange 8 to use adjustment slot 3 (2) so that when aux2
(1) in the range 1850-2100 then use adjustment Yaw D (11) when aux 4
(1) in the range 1850-2100 then use adjustment Yaw D (20) when aux 4
(3) is in the appropriate position.
### Example 4 - Use a single 3 position switch to change between 3 different rate profiles
adjrange 11 3 3 900 2100 12 3
explained:
* configure adjrange 11 to use adjustment slot 4 (3) so that when aux4
(3) in the range 900-2100 then use adjustment Rate Profile (12) when aux 4
(3) is in the appropriate position.
When the switch is low, rate profile 0 is selcted.
When the switch is medium, rate profile 1 is selcted.
When the switch is high, rate profile 2 is selcted.
### Configurator examples
The following 5 images show valid configurations. In all cases the entire usable range for the Range Channel is used.
![Configurator example 1](Screenshots/adjustments-rate-profile-selection-via-3pos.png)
---
![Configurator example 2](Screenshots/adjustments-pitch-and-roll-rate-adjustment-via-3pos.png)
---
@ -263,4 +250,4 @@ The following examples shows __incorrect__ configurations - the entire usable ra
In the following example, the incorrect configuraton (above) has been corrected by adding a range that makes 'No changes'.
![Configurator example 7](Screenshots/adjustments-incorrect-config-2-corrected.png)
![Configurator example 7](Screenshots/adjustments-incorrect-config-2-corrected.png)

View file

@ -2,7 +2,7 @@
A profile is a set of configuration settings.
Currently three profiles are supported. The default profile is profile `0`.
Currently three profiles are supported. The default profile is profile `1`.
## Changing profiles
@ -10,9 +10,9 @@ Profiles can be selected using a GUI or the following stick combinations:
| Profile | Throttle | Yaw | Pitch | Roll |
| ------- | -------- | ----- | ------ | ------ |
| 0 | Down | Left | Middle | Left |
| 1 | Down | Left | Up | Middle |
| 2 | Down | Left | Middle | Right |
| 1 | Down | Left | Middle | Left |
| 2 | Down | Left | Up | Middle |
| 3 | Down | Left | Middle | Right |
The CLI `profile` command can also be used:
@ -20,45 +20,127 @@ The CLI `profile` command can also be used:
profile <index>
```
# Rate Profiles
INAV supports rate profiles in addition to regular profiles.
Rate profiles contain settings that adjust how your craft behaves based on control input.
Three rate profiles are supported.
Rate profiles can be selected while flying using the inflight adjustments feature.
Each normal profile has a setting called 'default_rate_profile`. When a profile is activated the
corresponding rate profile is also activated.
Profile 0 has a default rate profile of 0.
Profile 1 has a default rate profile of 1.
Profile 2 has a default rate profile of 2.
The defaults are set this way so that it's simple to configure a profile and a rate profile at the same.
The current rate profile can be shown or set using the CLI `rateprofile` command:
```
rateprofile <index>
```
The values contained within a rate profile can be seen by using the CLI `dump rates` command.
The values contained within a profile can be seen by using the CLI `dump profile` command.
e.g
```
# dump rates
# dump profile
# rateprofile
rateprofile 0
# profile
profile 1
set rc_expo = 65
set mc_p_pitch = 40
set mc_i_pitch = 30
set mc_d_pitch = 23
set mc_cd_pitch = 60
set mc_p_roll = 40
set mc_i_roll = 30
set mc_d_roll = 23
set mc_cd_roll = 60
set mc_p_yaw = 85
set mc_i_yaw = 45
set mc_d_yaw = 0
set mc_cd_yaw = 60
set mc_p_level = 20
set mc_i_level = 15
set mc_d_level = 75
set fw_p_pitch = 5
set fw_i_pitch = 7
set fw_d_pitch = 0
set fw_ff_pitch = 50
set fw_p_roll = 5
set fw_i_roll = 7
set fw_d_roll = 0
set fw_ff_roll = 50
set fw_p_yaw = 6
set fw_i_yaw = 10
set fw_d_yaw = 0
set fw_ff_yaw = 60
set fw_p_level = 20
set fw_i_level = 5
set fw_d_level = 75
set max_angle_inclination_rll = 300
set max_angle_inclination_pit = 300
set dterm_lpf_hz = 110
set dterm_lpf_type = PT2
set dterm_lpf2_hz = 0
set dterm_lpf2_type = PT1
set yaw_lpf_hz = 0
set fw_iterm_throw_limit = 165
set fw_loiter_direction = RIGHT
set fw_reference_airspeed = 1500.000
set fw_turn_assist_yaw_gain = 1.000
set fw_turn_assist_pitch_gain = 1.000
set fw_iterm_limit_stick_position = 0.500
set fw_yaw_iterm_freeze_bank_angle = 0
set pidsum_limit = 500
set pidsum_limit_yaw = 350
set iterm_windup = 50
set rate_accel_limit_roll_pitch = 0
set rate_accel_limit_yaw = 10000
set heading_hold_rate_limit = 90
set nav_mc_pos_z_p = 50
set nav_mc_vel_z_p = 100
set nav_mc_vel_z_i = 50
set nav_mc_vel_z_d = 10
set nav_mc_pos_xy_p = 65
set nav_mc_vel_xy_p = 40
set nav_mc_vel_xy_i = 15
set nav_mc_vel_xy_d = 100
set nav_mc_vel_xy_ff = 40
set nav_mc_heading_p = 60
set nav_mc_vel_xy_dterm_lpf_hz = 2.000
set nav_mc_vel_xy_dterm_attenuation = 90
set nav_mc_vel_xy_dterm_attenuation_start = 10
set nav_mc_vel_xy_dterm_attenuation_end = 60
set nav_fw_pos_z_p = 40
set nav_fw_pos_z_i = 5
set nav_fw_pos_z_d = 10
set nav_fw_pos_xy_p = 75
set nav_fw_pos_xy_i = 5
set nav_fw_pos_xy_d = 8
set nav_fw_heading_p = 60
set nav_fw_pos_hdg_p = 30
set nav_fw_pos_hdg_i = 2
set nav_fw_pos_hdg_d = 0
set nav_fw_pos_hdg_pidsum_limit = 350
set mc_iterm_relax = RP
set mc_iterm_relax_cutoff = 15
set d_boost_min = 0.500
set d_boost_max = 1.250
set d_boost_max_at_acceleration = 7500.000
set d_boost_gyro_delta_lpf_hz = 80
set antigravity_gain = 1.000
set antigravity_accelerator = 1.000
set antigravity_cutoff_lpf_hz = 15
set pid_type = AUTO
set mc_cd_lpf_hz = 30
set fw_level_pitch_trim = 0.000
set smith_predictor_strength = 0.500
set smith_predictor_delay = 0.000
set smith_predictor_lpf_hz = 50
set fw_level_pitch_gain = 5.000
set thr_mid = 50
set thr_expo = 0
set roll_pitch_rate = 0
set yaw_rate = 0
set tpa_rate = 0
set tpa_breakpoint = 1500
set fw_tpa_time_constant = 0
set rc_expo = 70
set rc_yaw_expo = 20
set roll_rate = 20
set pitch_rate = 20
set yaw_rate = 20
set manual_rc_expo = 70
set manual_rc_yaw_expo = 20
set manual_roll_rate = 100
set manual_pitch_rate = 100
set manual_yaw_rate = 100
set fpv_mix_degrees = 0
set rate_dynamics_center_sensitivity = 100
set rate_dynamics_end_sensitivity = 100
set rate_dynamics_center_correction = 10
set rate_dynamics_end_correction = 10
set rate_dynamics_center_weight = 0
set rate_dynamics_end_weight = 0
```

View file

@ -74,7 +74,8 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` |
| 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. |
| 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder |
| 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. |
| 42 | SET_PROFILE | Sets the active config profile (PIDFF/Rates/Filters/etc) to `Operand A`. `Operand A` must be a valid profile number, currently from 1 to 3. If not, the profile will not change |
### Operands
@ -125,8 +126,10 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 30 | ACTIVE_WAYPOINT_ACTION | See ACTIVE_WAYPOINT_ACTION paragraph |
| 31 | 3D HOME_DISTANCE | in `meters`, calculated from HOME_DISTANCE and ALTITUDE using Pythagorean theorem |
| 32 | CROSSFIRE LQ | Crossfire Link quality as returned by the CRSF protocol |
| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix |
| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix |
| 35 | LOITER_RADIUS | The current loiter radius in cm. |
| 36 | ACTIVE_PROFILE | integer for the active config profile `[1..MAX_PROFILE_COUNT]` |
#### ACTIVE_WAYPOINT_ACTION

View file

@ -14,19 +14,17 @@ Current support of rangefinders in INAV is very limited. They are used only to:
Following rangefinders are supported:
* HC-SR04 - ***DO NOT USE*** HC-SR04 while most popular is not suited to use in noise reach environments (like multirotors). It is proven that this sonar rangefinder start to report random values already at 1.5m above solid concrete surface. Reported altitude is valid up to only 75cm above concrete. ***DO NOT USE***
* US-100 in trigger-echo mode - Can be used as direct replacement of _HC-SR04_ when `rangefinder_hardware` is set to _HCSR04_. Useful up to 2m over concrete and correctly reporting _out of range_ when out of range
* SRF10 - experimental
* INAV_I2C - is a simple [DIY rangefinder interface with Arduino Pro Mini 3.3V](https://github.com/iNavFlight/inav-rangefinder). Can be used to connect when flight controller has no Trigger-Echo ports.
* VL53L0X - simple laser rangefinder usable up to 75cm
* UIB - experimental
* MSP - experimental
* TOF10120 - small & lightweight laser range sensor, usable up to 200cm
## Connections
Target dependent in case of Trigger/Echo solutions like `HC-SR04` and `US-100`.
I2C solutions like `VL53L0X` or `INAV_I2C` can be connected to I2C port and used as any other I2C device.
#### Constraints
Target dependent in case of Trigger/Echo solutions like `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
iNav does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.

View file

@ -452,6 +452,16 @@ If the remaining battery capacity goes below this threshold the beeper will emit
---
### beeper_pwm_mode
Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode
| Default | Min | Max |
| --- | --- | --- |
| OFF | | |
---
### blackbox_device
Selection of where to write blackbox data
@ -562,16 +572,6 @@ ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the
---
### d_boost_factor
_// TODO_
| Default | Min | Max |
| --- | --- | --- |
| 1.25 | 1 | 3 |
---
### d_boost_gyro_delta_lpf_hz
_// TODO_
@ -582,6 +582,16 @@ _// TODO_
---
### d_boost_max
_// TODO_
| Default | Min | Max |
| --- | --- | --- |
| 1.25 | 1 | 3 |
---
### d_boost_max_at_acceleration
_// TODO_
@ -592,6 +602,16 @@ _// TODO_
---
### d_boost_min
_// TODO_
| Default | Min | Max |
| --- | --- | --- |
| 0.5 | 0 | 1 |
---
### deadband
These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle.
@ -734,11 +754,11 @@ Cutoff frequency for stage 2 D-term low pass filter
### dterm_lpf2_type
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`.
| Default | Min | Max |
| --- | --- | --- |
| BIQUAD | | |
| PT1 | | |
---
@ -748,17 +768,17 @@ Dterm low pass filter cutoff frequency. Default setting is very conservative and
| Default | Min | Max |
| --- | --- | --- |
| 40 | 0 | 500 |
| 110 | 0 | 500 |
---
### dterm_lpf_type
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`.
| Default | Min | Max |
| --- | --- | --- |
| BIQUAD | | |
| PT2 | | |
---
@ -768,17 +788,17 @@ Enable/disable dynamic gyro notch also known as Matrix Filter
| Default | Min | Max |
| --- | --- | --- |
| OFF | | |
| ON | | |
---
### dynamic_gyro_notch_min_hz
Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70`
Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirotors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70`
| Default | Min | Max |
| --- | --- | --- |
| 150 | 30 | 1000 |
| 50 | 30 | 1000 |
---
@ -792,16 +812,6 @@ Q factor for dynamic notches
---
### dynamic_gyro_notch_range
Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers
| Default | Min | Max |
| --- | --- | --- |
| MEDIUM | | |
---
### eleres_freq
_// TODO_
@ -894,7 +904,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 |
| --- | --- | --- |
@ -904,7 +914,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 |
| --- | --- | --- |
@ -914,7 +924,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 |
| --- | --- | --- |
@ -998,7 +1008,7 @@ What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Fai
| Default | Min | Max |
| --- | --- | --- |
| SET-THR | | |
| LAND | | |
---
@ -1158,13 +1168,13 @@ The target percentage of maximum mixer output used for determining the rates in
| Default | Min | Max |
| --- | --- | --- |
| 90 | 50 | 100 |
| 80 | 50 | 100 |
---
### fw_autotune_min_stick
Minimum stick input [%] to consider overshoot/undershoot detection
Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input.
| Default | Min | Max |
| --- | --- | --- |
@ -1522,36 +1532,6 @@ Enable use of Galileo satellites. This is at the expense of other regional const
---
### gyro_abg_alpha
Alpha factor for Gyro Alpha-Beta-Gamma filter
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 1 |
---
### gyro_abg_boost
Boost factor for Gyro Alpha-Beta-Gamma filter
| Default | Min | Max |
| --- | --- | --- |
| 0.35 | 0 | 2 |
---
### gyro_abg_half_life
Sample half-life for Gyro Alpha-Beta-Gamma filter
| Default | Min | Max |
| --- | --- | --- |
| 0.5 | 0 | 10 |
---
### gyro_anti_aliasing_lpf_hz
Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz
@ -1658,7 +1638,7 @@ _// TODO_
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 1 |
| 0 | 0 | 2 |
---
@ -1928,7 +1908,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements
| Default | Min | Max |
| --- | --- | --- |
| 2500 | | 65535 |
| 1000 | | 65535 |
---
@ -1938,7 +1918,7 @@ Inertial Measurement Unit KP Gain for compass measurements
| Default | Min | Max |
| --- | --- | --- |
| 10000 | | 65535 |
| 5000 | | 65535 |
---
@ -2458,7 +2438,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 |
---
@ -2832,26 +2812,6 @@ When powering up, gyro bias is calculated. If the model is shaking/moving during
---
### motor_accel_time
Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 1000 |
---
### motor_decel_time
Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 1000 |
---
### motor_direction_inverted
Use if you need to inverse yaw motor direction.
@ -2924,7 +2884,7 @@ Maximum climb/descent rate that UAV is allowed to reach during navigation modes.
### nav_auto_speed
Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]
Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]
| Default | Min | Max |
| --- | --- | --- |
@ -3424,7 +3384,7 @@ Maximum climb/descent rate firmware is allowed when processing pilot input for A
### nav_manual_speed
Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]
Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]
| Default | Min | Max |
| --- | --- | --- |
@ -3442,6 +3402,16 @@ Max allowed altitude (above Home Point) that applies to all NAV modes (including
---
### nav_max_auto_speed
Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]
| Default | Min | Max |
| --- | --- | --- |
| 1000 | 10 | 2000 |
---
### nav_max_terrain_follow_alt
Max allowed above the ground altitude for terrain following mode
@ -4132,6 +4102,16 @@ Value above which to make the OSD distance from home indicator blink (meters)
---
### osd_esc_rpm_precision
Number of characters used to display the RPM value.
| Default | Min | Max |
| --- | --- | --- |
| 3 | 3 | 6 |
---
### osd_esc_temp_alarm_max
Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)
@ -4552,6 +4532,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`
@ -4782,6 +4772,66 @@ Limits acceleration of YAW rotation speed that can be requested by stick input.
---
### rate_dynamics_center_correction
The center stick correction for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 10 | 10 | 95 |
---
### rate_dynamics_center_sensitivity
The center stick sensitivity for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 100 | 25 | 175 |
---
### rate_dynamics_center_weight
The center stick weight for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 95 |
---
### rate_dynamics_end_correction
The end stick correction for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 10 | 10 | 95 |
---
### rate_dynamics_end_sensitivity
The end stick sensitivity for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 100 | 25 | 175 |
---
### rate_dynamics_end_weight
The end stick weight for Rate Dynamics
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 95 |
---
### rc_expo
Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)
@ -5128,7 +5178,7 @@ Enable Kalman filter on the gyro data
| Default | Min | Max |
| --- | --- | --- |
| OFF | | |
| ON | | |
---
@ -5654,7 +5704,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 |
| --- | --- | --- |

View file

@ -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.

BIN
docs/assets/betafpvf722.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 221 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1,012 KiB

After

Width:  |  Height:  |  Size: 666 KiB

Before After
Before After

View file

@ -2,23 +2,23 @@
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
width="2478.5964mm"
height="1400.9835mm"
viewBox="0 0 8782.4284 4964.1146"
id="svg2"
version="1.1"
inkscape:version="0.92.4 (5da689c313, 2019-01-14)"
inkscape:version="1.1 (c4e8f9ed74, 2021-05-24)"
sodipodi:docname="StickPositions.svg"
inkscape:export-filename="C:\Users\teckel.SSCORP\Downloads\StickPositions.png"
inkscape:export-filename="StickPositions.png"
inkscape:export-xdpi="74.996788"
inkscape:export-ydpi="74.996788">
inkscape:export-ydpi="74.996788"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns="http://www.w3.org/2000/svg"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:dc="http://purl.org/dc/elements/1.1/">
<defs
id="defs4" />
<sodipodi:namedview
@ -29,15 +29,15 @@
inkscape:pageopacity="0.0"
inkscape:pageshadow="2"
inkscape:zoom="0.13995495"
inkscape:cx="3633.6202"
inkscape:cy="2120.4595"
inkscape:cx="6594.9793"
inkscape:cy="3265.3365"
inkscape:document-units="px"
inkscape:current-layer="g4157"
showgrid="false"
inkscape:window-width="2560"
inkscape:window-height="1377"
inkscape:window-x="-8"
inkscape:window-y="-8"
inkscape:window-width="1920"
inkscape:window-height="1010"
inkscape:window-x="0"
inkscape:window-y="0"
inkscape:window-maximized="1"
fit-margin-top="1"
fit-margin-left="1"
@ -49,7 +49,8 @@
inkscape:guide-bbox="true"
inkscape:snap-object-midpoints="true"
inkscape:snap-others="false"
inkscape:object-nodes="true" />
inkscape:object-nodes="true"
inkscape:pagecheckerboard="0" />
<metadata
id="metadata7">
<rdf:RDF>
@ -58,7 +59,7 @@
<dc:format>image/svg+xml</dc:format>
<dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
<dc:title></dc:title>
<dc:title />
</cc:Work>
</rdf:RDF>
</metadata>
@ -160,7 +161,7 @@
x="533.55804"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan4711"
y="-1909.1018"
x="533.55804"
@ -205,7 +206,7 @@
x="533.55804"
y="-1488.6938"
id="tspan4763"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Profile 2</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Profile 2</tspan></text>
<rect
ry="0"
y="-1317.7664"
@ -242,7 +243,7 @@
x="533.55804"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan4815"
y="-1068.2856"
x="533.55804"
@ -287,7 +288,7 @@
x="533.55811"
y="583.57056"
id="tspan4867"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Calibrate Gyro</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Calibrate Gyro</tspan></text>
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect4875"
@ -328,7 +329,7 @@
x="533.55811"
y="1003.9787"
id="tspan4919"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Calibrate Acc</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Calibrate Acc</tspan></text>
<rect
ry="0"
y="1171.4286"
@ -365,7 +366,7 @@
x="536.28436"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan4971"
y="1420.9093"
x="536.2843"
@ -408,7 +409,7 @@
x="5680.7969"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan5651"
y="-1527.5551"
x="5680.7969"
@ -453,7 +454,7 @@
x="5680.7969"
y="-1107.1469"
id="tspan5703"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Left</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Left</tspan></text>
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect5711"
@ -492,7 +493,7 @@
x="5680.7969"
y="-686.73877"
id="tspan5755"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Right</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Right</tspan></text>
<rect
ry="0"
y="-489.01691"
@ -527,7 +528,7 @@
x="5680.7969"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan5807"
y="-266.3306"
x="5680.7969"
@ -570,7 +571,7 @@
x="5680.7969"
y="154.07762"
id="tspan5859"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Backwards</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Trim Acc Backwards</tspan></text>
<rect
ry="0"
y="351.79944"
@ -607,7 +608,7 @@
x="5680.7969"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan5911"
y="574.48572"
x="5680.7969"
@ -626,6 +627,20 @@
id="path5923"
d="m 5992.6852,1082.4789 c 0,10.5728 -14.6765,19.1438 -32.7809,19.1438 -18.1044,0 -32.7809,-8.571 -32.7809,-19.1438 0,-10.5729 14.6765,-163.59574 32.7809,-163.59574 18.1044,0 32.7809,153.02284 32.7809,163.59574 z"
style="display:inline;opacity:1;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07780743;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
<rect
ry="0"
y="1145.4941"
x="5811.6289"
height="288.94339"
width="288.94339"
id="rect5919-7"
style="display:inline;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.0566;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
<path
sodipodi:nodetypes="sssss"
inkscape:connector-curvature="0"
id="path5923-5"
d="m 5988.8813,1455.7655 c 0,10.5728 -14.6765,19.1438 -32.7809,19.1438 -18.1044,0 -32.7809,-8.571 -32.7809,-19.1438 0,-10.5729 14.6765,-163.5957 32.7809,-163.5957 18.1044,0 32.7809,153.0228 32.7809,163.5957 z"
style="display:inline;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07781;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect5941"
@ -648,54 +663,81 @@
x="5680.7969"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan5963"
y="994.89398"
x="5680.7969"
sodipodi:role="line">Load waypoint mission</tspan></text>
<text
id="text5961-3"
y="1369.7102"
x="5681.5464"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;display:inline;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan5963-6"
y="1369.7102"
x="5681.5464"
sodipodi:role="line">Unload waypoint mission</tspan></text>
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.0566;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect5971"
width="288.94339"
height="288.94339"
x="5815.4326"
y="1192.6158"
y="1526.3658"
ry="0" />
<path
sodipodi:nodetypes="sssss"
inkscape:connector-curvature="0"
id="path5977"
d="m 5863.6503,1478.825 c -7.4762,7.4762 -23.9146,3.1589 -36.7164,-9.6428 -12.8017,-12.8018 -17.119,-29.2402 -9.6428,-36.7164 7.4761,-7.4761 126.0574,-105.3017 138.8592,-92.5 12.8017,12.8018 -85.0239,131.3831 -92.5,138.8592 z"
style="display:inline;opacity:1;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07780743;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
d="m 5863.6503,1812.575 c -7.4762,7.4762 -23.9146,3.1589 -36.7164,-9.6428 -12.8017,-12.8018 -17.119,-29.2402 -9.6428,-36.7164 7.4761,-7.4761 126.0574,-105.3017 138.8592,-92.5 12.8017,12.8018 -85.0239,131.3831 -92.5,138.8592 z"
style="display:inline;opacity:1;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07781;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
inkscape:transform-center-y="73.935654"
inkscape:transform-center-x="73.935653" />
<rect
ry="0"
y="1192.6158"
y="1526.3658"
x="6221.147"
height="288.94339"
width="288.94339"
id="rect5993"
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.0566;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
<path
sodipodi:nodetypes="sssss"
inkscape:connector-curvature="0"
id="path6001"
d="m 6460.9887,1478.825 c 7.4761,7.4762 23.9146,3.1589 36.7163,-9.6428 12.8017,-12.8018 17.119,-29.2402 9.6428,-36.7164 -7.4761,-7.4761 -126.0574,-105.3017 -138.8591,-92.5 -12.8018,12.8018 85.0238,131.3831 92.5,138.8592 z"
style="display:inline;opacity:1;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07780743;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
d="m 6460.9887,1812.575 c 7.4761,7.4762 23.9146,3.1589 36.7163,-9.6428 12.8017,-12.8018 17.119,-29.2402 9.6428,-36.7164 -7.4761,-7.4761 -126.0574,-105.3017 -138.8591,-92.5 -12.8018,12.8018 85.0238,131.3831 92.5,138.8592 z"
style="display:inline;opacity:1;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07781;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
inkscape:transform-center-y="73.935654"
inkscape:transform-center-x="-73.935657" />
<rect
ry="0"
y="1140.2471"
x="6228.9062"
height="288.94339"
width="288.94339"
id="rect5993-3"
style="display:inline;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.0566;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
<path
sodipodi:nodetypes="sssss"
inkscape:connector-curvature="0"
id="path6001-5"
d="m 6468.7482,1426.4562 c 7.4761,7.4762 23.9146,3.1589 36.7163,-9.6428 12.8017,-12.8018 17.119,-29.2402 9.6428,-36.7164 -7.4761,-7.4761 -126.0574,-105.3017 -138.8591,-92.5 -12.8018,12.8018 85.0238,131.3831 92.5,138.8592 z"
style="display:inline;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:8.07781;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
inkscape:transform-center-y="73.935654"
inkscape:transform-center-x="-73.935657" />
<text
xml:space="preserve"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
x="5680.7969"
y="1415.3022"
x="5714.6821"
y="1775.6128"
id="text6013"><tspan
sodipodi:role="line"
x="5680.7969"
y="1415.3022"
x="5714.6821"
y="1775.6128"
id="tspan6015"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Save Setting</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Save Setting</tspan></text>
<text
xml:space="preserve"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
@ -706,7 +748,7 @@
x="5690.6709"
y="-1955.0773"
id="tspan4219"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Enter OSD Menu (CMS)</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Enter OSD Menu (CMS)</tspan></text>
<text
xml:space="preserve"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
@ -717,7 +759,7 @@
x="2179.2812"
y="-2663.0625"
id="tspan7909"
style="font-size:352.85842896px;line-height:1.25;text-align:center;text-anchor:middle">Mode 2 Stick Functions</tspan></text>
style="font-size:352.858px;line-height:1.25;text-align:center;text-anchor:middle">Mode 2 Stick Functions</tspan></text>
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect927"
@ -752,7 +794,7 @@
x="533.55811"
y="-673.06989"
id="tspan935"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Battery profile 1</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Battery profile 1</tspan></text>
<rect
style="display:inline;opacity:1;fill:none;fill-opacity:1;stroke:#808080;stroke-width:11.05660725;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
id="rect943"
@ -773,7 +815,7 @@
x="533.55804"
style="font-style:normal;font-weight:normal;line-height:0%;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
xml:space="preserve"><tspan
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end"
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end"
id="tspan947"
y="-252.66168"
x="533.55811"
@ -802,7 +844,7 @@
x="533.55811"
y="167.74652"
id="tspan959"
style="font-size:286.5987854px;line-height:1.25;text-align:end;text-anchor:end">Battery profile 3</tspan></text>
style="font-size:286.599px;line-height:1.25;text-align:end;text-anchor:end">Battery profile 3</tspan></text>
<path
sodipodi:nodetypes="sssss"
inkscape:connector-curvature="0"

Before

Width:  |  Height:  |  Size: 44 KiB

After

Width:  |  Height:  |  Size: 46 KiB

Before After
Before After

View file

@ -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
@ -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

12
docs/boards/BetFPVF722.md Normal file
View file

@ -0,0 +1,12 @@
# BetaFPVF722
## I2C bus for magnetometer
BetFPVF722 does not have I2C pads broken out. I2C is shared with UART3
* TX3 - SCL
* RX3 - SDA
> 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)

View file

0
docs/Board - KroozX.md → docs/boards/KroozX.md Executable file → Normal file
View file

View file

@ -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
@ -22,4 +20,4 @@
## Where to buy:
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)

0
docs/Board - NOX.md → docs/boards/NOX.md Executable file → Normal file
View file

View file

@ -155,14 +155,14 @@ This board allows for single **SoftwareSerial** port on small soldering pads loc
Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount pads CH5/CH6.
### Omnibus F4 Pro SoftwareSerial Connections
![Omnibus F4 Pro SoftwareSerial Connections](assets/images/omnibusf4pro_ss.jpg)
![Omnibus F4 Pro SoftwareSerial Connections](../assets/images/omnibusf4pro_ss.jpg)
| Pad | SoftwareSerial Role |
| ---- | ---- |
| CH5 | RX |
| CH6 | TX |
![Omnibus F4 Pro SmartPort using SoftwareSerial](assets/images/omnibusf4pro_ss.png)
![Omnibus F4 Pro SmartPort using SoftwareSerial](../assets/images/omnibusf4pro_ss.png)
### Omnibus F4 v3/v4/v5 SoftwareSerial Connections
@ -181,22 +181,22 @@ Following diagrams applies to _Pro_ version with integrated current meter and JS
## Board layout
![Omnibus F4 Pro Board Layout](assets/images/omnibusf4pro.png)
![Omnibus F4 Pro Board Layout](../assets/images/omnibusf4pro.png)
## Flying wing motor and servos
![Omnibus F4 Pro Flying Wing Setup](assets/images/omnibusf4pro_flyingwing_setup.png)
![Omnibus F4 Pro Flying Wing Setup](../assets/images/omnibusf4pro_flyingwing_setup.png)
## RX setup
![Omnibus F4 Pro RX Setup](assets/images/omnibusf4pro_rx.png)
![Omnibus F4 Pro RX Setup](../assets/images/omnibusf4pro_rx.png)
## FPV setup
![Omnibus F4 Pro FPV Setup](assets/images/omnibusf4pro_fpv_setup.png)
![Omnibus F4 Pro FPV Setup](../assets/images/omnibusf4pro_fpv_setup.png)
## GPS setup
![Omnibus F4 Pro GPS Setup](assets/images/omnibusf4pro_gps_setup.png)
![Omnibus F4 Pro GPS Setup](../assets/images/omnibusf4pro_gps_setup.png)
_Diagrams created by Albert Kravcov (skaman82)_

View file

@ -1,51 +0,0 @@
# Atomic Barrier Warning
If GCC is upgraded and a warning appears when compiling then the generated asm source must be verified.
e.g.
```
%% serial_softserial.c
warning "Please verify that ATOMIC_BARRIER works as intended"
```
To perform the verification, proceed as per discusson on issue #167 which reads:
I hope it's enough to check that optimized-away variable still has cleanup code at end of scope.
```
static int markme=0;
markme++;
ATOMIC_BLOCK_NB(0xff) {
ATOMIC_BARRIER(markme);
markme++;
};
markme++;
```
pass `-save-temps=obj` (or `-save-temps=cwd`, but lots of files will end up in same directory as makefile) to gcc link step (LTO is in use), find resulting `*.ltrans*.ltrans.s` (grep for `markme`, on linux it ends up in `/tmp`) and check that generated assembly sequence is:
```
MSR basepri_max, r3
# (possibly markme address load)
# barier (markme) start
# (increment markme, load and store to memory)
ldr r2, [r3]
adds r0, r2, #1
str r0, [r3]
# barier(markme) end
MSR basepri, r3
# (markme value should be cached in register on next increment)
```
The # barrier(markme) must surround access code and must be inside MSR basepri instructions ..
Similar approach is used for ATOMIC_BLOCK in avr libraries, so gcc should not break this behavior.
IMO attribute(cleanup) and asm volatile is defined in a way that should guarantee this.
attribute(cleanup) is probably safer way to implement atomic sections - another possibility is to explicitly place barriers in code, but that can (and will eventually) lead to missed barrier/basepri restore on same path creating very hard to find bug.
The MEMORY_BARRIER() code can be omitted and use ATOMIC_BLOCK with full memory barriers, but IMO it is better to explicitly state what memory is protected by barrier and gcc can use this knowledge to greatly improve generated code in future.

View file

@ -65,7 +65,7 @@ The `git clone` creates an `inav` directory; we can enter this directory, config
## Build tooling
For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build enviroment with `cmake` before we can build any firmware.
For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplifies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build environment with `cmake` before we can build any firmware.
## Using `cmake`
@ -96,14 +96,14 @@ Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is
The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`.
Typically, to build a single target, just pass the target name to `make`; note that unlike eariler releases, `make` without a target specified will build **all** targets.
Typically, to build a single target, just pass the target name to `make`; note that unlike earlier releases, `make` without a target specified will build **all** targets.
```
# Build the MATEKF405 firmware
make MATEKF405
```
One can also build multiple targets from a sinlge `make` command:
One can also build multiple targets from a single `make` command:
```
make MATEKF405 MATEKF722
@ -128,7 +128,7 @@ make clean_MATEKF405
make clean_MATEKF405 clean_MATEKF722
```
### `cmake` cache maintainance
### `cmake` cache maintenance
`cmake` caches the build environment, so you don't need to rerun `cmake` each time you build a target. Two `make` options are provided to maintain the `cmake` cache.
@ -141,7 +141,7 @@ It is unlikely that the typical user will need to employ these options, other th
In order to update your local firmware build:
* Navigate to the local iNav repository
* Navigate to the local inav repository
* Use the following steps to pull the latest changes and rebuild your local version of inav firmware from the `build` directory:
```
@ -154,3 +154,9 @@ $ make <TARGET>
## Advanced Usage
For more advanced development information and `git` usage, please refer to the [development guide](https://github.com/iNavFlight/inav/blob/master/docs/development/Development.md).
## Unsupported platforms
If you're using a host platform for which Arm does not supply a cross-compiler (Arm32, IA32), and the distro either does not package a suitable compiler or it's too old, then you can usually find a suitable compiler in the [xpack devtools collection](https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack).
You will need to configure `cmake` to use the external compiler.

View file

@ -20,13 +20,13 @@ Install Ubuntu:
NOTE: from this point all commands are entered into the Ubunto shell command window
Update the repo packages:
1. `sudo apt update`
- `sudo apt update`
Install Git, Make, gcc and Ruby
1. `sudo apt-get install git`
1. `sudo apt-get install make`
1. `sudo apt-get install cmake`
1. `sudo apt-get install ruby`
- `sudo apt-get install git make cmake ruby`
Install python and python-yaml to allow updates to settings.md
- `sudo apt-get install python3 python-yaml`
### CMAKE and Ubuntu 18_04
@ -78,6 +78,12 @@ cd build
make MATEKF722
```
## Updating the documents
```
cd /mnt/c/inav
python3 src/utils/update_cli_docs.py
```
## Flashing:
Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]`
Hex files can be found in the folder `c:\inav\build`
@ -132,3 +138,28 @@ appendWindowsPath=false
8. `cd build`
9. `cmake ..`
9. `make {TARGET}` should be working again
### Building targets is very slow
I was pretty shocked when my new i7 -10750 laptop took 25 minutes to build a single target. My old i3-4030 could do the same job in about 2.5 minutes. If you're also suffering from slow builds. Open an elevated PowerShell window and type
```
wsl -l -v
```
If you see your Linux distribution is using WSL 2, this is the problem. WSL 2 is quicker than WSL 1 for a lot of things. However, if your files are on a windows mounted drive in Linux, it is extremely slow. There are two options:
1. Put your files on the Linux file system
2. Change to WSL 1
#### Using the Linux file system (recommended)
To use the Linux file system, make sure the distro is running. Open File Explorer and navigate to `\\wsl$`. In that path you will find your distros listed. At this point, map a network drive to your distro. Inside the distro, you can find your home directory at `/home/~username~/`. Create your GitHub folders here.
If after this you have problems with writing to the directories from within VSCode. Open the application for your distro and type
```
sudo chown -R ~username~ GitHub
```
`~Username~` is your root distro user that you created and `GitHub` should be the root folder for your GitHub repositories.
#### To switch back to WSL 1
To do this, in the elevated PowerShell window, you can see the name of your distro. Mine is **Ubuntu-20.04**, so I'll use that in this example. Simply type
```
wsl --set-version Ubuntu-20.04 1
```
and your distro will be converted to WSL 1. Once finished, reboot your system. Next time you compile a build, it will be faster.

View file

@ -79,30 +79,6 @@ Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard
// for the documentation about the tasks.json format
"version": "2.0.0",
"tasks": [
{
"label": "Build Matek F722-SE",
"type": "shell",
"command": "make MATEKF722SE",
"group": "build",
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}/build"
}
},
{
"label": "Build Matek F722",
"type": "shell",
"command": "make MATEKF722",
"group": {
"kind": "build",
"isDefault": true
},
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}/build"
}
}
,
{
"label": "Install/Update CMAKE",
"type": "shell",
@ -112,6 +88,37 @@ Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard
"options": {
"cwd": "${workspaceFolder}"
}
},
{
"label": "Compile autogenerated docs",
"type": "shell",
"command": "python3 src/utils/update_cli_docs.py",
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}"
}
},
// Example of building a single target
{
"label": "Build Matek F722-WPX",
"type": "shell",
"command": "make MATEKF722WPX",
"group": "build",
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}/build"
}
},
// Example of building multiple targets
{
"label": "Build Matek F405-STD & WING",
"type": "shell",
"command": "make MATEKF405 MATEKF405SE",
"group": "build",
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}/build"
}
}
]
}