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

Merge branch 'iNavFlight:master' into airspeed-alarms

This commit is contained in:
Igor 2021-10-31 18:13:46 +05:00 committed by GitHub
commit 10a8dc4384
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
47 changed files with 773 additions and 722 deletions

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

@ -788,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 |
---
@ -812,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_
@ -1542,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
@ -2478,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 |
---
@ -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
@ -4142,6 +4112,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)
@ -5208,7 +5188,7 @@ Enable Kalman filter on the gyro data
| Default | Min | Max |
| --- | --- | --- |
| OFF | | |
| ON | | |
---

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

View file

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

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

@ -148,7 +148,17 @@ If you see your Linux distribution is using WSL 2, this is the problem. WSL 2 is
1. Put your files on the Linux file system
2. Change to WSL 1
I opted for the latter. 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
#### 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
```

View file

@ -1,80 +0,0 @@
# General Info
This is a guide on how to use Windows MSYS2 distribution and building platform to build iNav firmware. This environment is very simple to manage and does not require installing docker for Windows which may get in the way of VMWare or any other virtualization software you already have running for other reasons. Another benefit of this approach is that the compiler runs natively on Windows, so performance is much better than compiling in a virtual environment or a container. You can also integrate with whatever IDE you are using to make code edits and work with github, which makes the entire development and testing workflow a lot more efficient. In addition to MSYS2, this build environment also uses Arm Embedded GCC tolkit from The xPack Project, which provides many benefits over the toolkits maintained by arm.com
Some of those benefits are described here:
https://xpack.github.io/arm-none-eabi-gcc/
## Setting up build environment
Download MSYS2 for your architecture (most likely 64-bit)
https://www.msys2.org/wiki/MSYS2-installation/
Click on 64-bit, scroll all the way down for the latest release
pacman is the package manager which makes it a lot easier to install and maintain all the dependencies
## Installing dependencies
Once MSYS2 is installed, you can open up a new terminal window by running:
"C:\msys64\mingw64.exe"
You can also make a shortcut of this somewhere on your taskbar, desktop, etc, or even setup a shortcut key to open it up every time you need to get a terminal window. If you right click on the window you can customize the font and layout to make it more comfortable to work with. This is very similar to cygwin or any other terminal program you might have used before
This is the best part:
```
pacman -S git ruby make cmake gcc mingw-w64-x86_64-libwinpthread-git unzip wget
```
Now, each release needs a different version of arm toolchain. To setup the xPack ARM toolchain, use the following process:
First, setup your work path, get the release you want to build or master if you want the latest/greatest
```
mkdir /c/Workspace
cd /c/Workspace
# you can also check out your own fork here which makes contributing easier
git clone https://github.com/iNavFlight/inav
cd inav
# switch to release you want or skip next 2 lines if you want latest
git fetch origin
git checkout -b release_2.6.1 origin/release_2.6.1
```
Now create the build and xpack directories and get the toolkit version you need for your inav version
```
mkdir build
cd build
mkdir /c/Workspace/xpack
cd /c/Workspace/xpack
cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2
```
This will give you the version you need for any given release or master branch. You can get to all the releases here and find the version you need
https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/
```
# for version 2.6.1, version needed is 9.2.1
wget https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/download/v9.2.1-1.1/xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
unzip xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
```
This is important, put the toolkit first before your path so that it is picked up ahead of any other versions that may be present on your system
```
export PATH=/c/Workspace/xpack/xpack-arm-none-eabi-gcc-9.2.1-1.1/bin:$PATH
cd /c/Workspace/inav/build
```
You may need to run rm -rf * in build directory if you had any failed previous runs now run cmake
```
# while inside the build directory
cmake ..
```
Once that's done you can compile the firmware for your controller
```
make DALRCF405
```
To get a list of available targets in iNav, see the target src folder
https://github.com/tednv/inav/tree/master/src/main/target
The generated hex file will be in /c/Workspace/inav/build folder
At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method