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

Merge branch 'master' of https://github.com/dragnea/inav into dragnea_autolaunch_refactor

This commit is contained in:
root 2020-10-17 13:47:12 +03:00
commit 91e69c9614
579 changed files with 17653 additions and 10892 deletions

View file

@ -95,31 +95,41 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
### serial
The syntax of the `serial` command is `serial <id> <functions> <msp-baudrate> <gps-baudrate> <telemetry-baudate> <peripheral-baudrate>`.
The syntax of the `serial` command is `serial <id> <function_value> <msp-baudrate> <gps-baudrate> <telemetry-baudate> <peripheral-baudrate>`.
A shorter form is also supported to enable and disable functions using `serial <id> +n` and
`serial <id> -n`, where n is the a serial function identifier. The following values are available:
A shorter form is also supported to enable and disable a single function using `serial <id> +n` and `serial <id> -n`, where n is the a serial function identifier. The following values are available:
| Function | Identifier |
|-----------------------|---------------|
| MSP | 0 |
| GPS | 1 |
| TELEMETRY_FRSKY | 2 |
| TELEMETRY_HOTT | 3 |
| TELEMETRY_LTM | 4 |
| TELEMETRY_SMARTPORT | 5 |
| RX_SERIAL | 6 |
| BLACKBOX | 7 |
| TELEMETRY_MAVLINK | 8 |
| TELEMETRY_IBUS | 9 |
| RCDEVICE | 10 |
| VTX_SMARTAUDIO | 11 |
| VTX_TRAMP | 12 |
| UAV_INTERCONNECT | 13 |
| OPTICAL_FLOW | 14 |
| LOG | 15 |
| RANGEFINDER | 16 |
| VTX_FFPV | 17 |
| Function | Bit Identifier | Numeric value |
|-----------------------|---------------|----------------|
| MSP | 0 | 1 |
| GPS | 1 | 2 |
| TELEMETRY_FRSKY | 2 | 4 |
| TELEMETRY_HOTT | 3 | 8 |
| TELEMETRY_LTM | 4 | 16 |
| TELEMETRY_SMARTPORT | 5 | 32 |
| RX_SERIAL | 6 | 64 |
| BLACKBOX | 7 | 128 |
| TELEMETRY_MAVLINK | 8 | 256 |
| TELEMETRY_IBUS | 9 | 512 |
| RCDEVICE | 10 | 1024 |
| VTX_SMARTAUDIO | 11 | 2048 |
| VTX_TRAMP | 12 | 4096 |
| UAV_INTERCONNECT | 13 | 8192 |
| OPTICAL_FLOW | 14 | 16384 |
| LOG | 15 | 32768 |
| RANGEFINDER | 16 | 65536 |
| VTX_FFPV | 17 | 131072 |
Thus, to enable MSP and LTM on a port, one would use the function **value** of 17 (1 << 0)+(1<<4), aka 1+16, aka 17.
```
serial 0 17 57600 57600 57600 57600
```
but to remove LTM using the +/- shorthand, use the **bit Id** (4, TELEMETRY_LTM):
```
serial 0 -4
```
`serial` can also be used without any argument to print the current configuration of all the serial ports.

View file

@ -0,0 +1,25 @@
# INAV PID Controller
What you have to know about INAV PID/PIFF/PIDCD controllers:
1. INAV PID uses floating-point math
1. Rate/Angular Velocity controllers work in dps [degrees per second]
1. P, I, D and Multirotor CD gains are scaled like Betafligfht equivalents, but actual mechanics are different, and PID response might be different
1. Depending on platform type, different controllers are used
1. Fixed-wing uses **PIFF**:
1. Error is computed with a formula `const float rateError = pidState->rateTarget - pidState->gyroRate;`
1. P-term with a formula `rateError * pidState->kP`
1. Simple I-term without Iterm Relax. I-term limit based on stick position is used instead. I-term is no allowed to grow if stick (roll/pitch/yaw) is deflected above threshold defined in `fw_iterm_limit_stick_position`. `pidState->errorGyroIf += rateError * pidState->kI * dT;`
1. No D-term
1. FF-term (Feed Forward) is computed from the controller input with a formula `pidState->rateTarget * pidState->kFF`. Bear in mind, this is not a **FeedForward** from Betaflight!
1. Multirotor uses **PIDCD**:
1. Error is computed with a formula `const float rateError = pidState->rateTarget - pidState->gyroRate;`
1. P-term with a formula `rateError * pidState->kP`
1. I-term
1. Iterm Relax is used to dynamically attenuate I-term during fast stick movements
1. I-term formula `pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT);`
1. I-term can be limited when motor output is saturated
1. D-term is computed only from gyro measurement
1. There are 2 LPF filters on D-term
1. D-term can by boosted during fast maneuvers using D-Boost. D-Boost is an equivalent of Betaflight D_min
1. **Control Derivative**, CD, or CD-term is a derivative computed from the setpoint that helps to boost PIDCD controller during fast stick movements. `newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT);` It is an equivalent of Betaflight Feed Forward

View file

@ -113,45 +113,45 @@ this reason ensure that you define enough ranges to cover the range channel's us
| 8 | PITCH_ROLL_D |
| 9 | YAW_P |
| 10 | YAW_I |
| 11 | YAW_D |
| 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 |
| 17 | PITCH_D_FF |
| 18 | ROLL_P |
| 19 | ROLL_I |
| 20 | RC_YAW_EXPO |
| 21 | MANUAL_RC_EXPO |
| 22 | MANUAL_RC_YAW_EXPO |
| 23 | MANUAL_PITCH_ROLL_RATE |
| 24 | MANUAL_ROLL_RATE |
| 25 | MANUAL_PITCH_RATE |
| 26 | MANUAL_YAW_RATE |
| 27 | NAV_FW_CRUISE_THROTTLE |
| 28 | NAV_FW_PITCH2THR |
| 29 | ROLL_BOARD_ALIGNMENT |
| 30 | PITCH_BOARD_ALIGNMENT |
| 31 | LEVEL_P |
| 32 | LEVEL_I |
| 33 | LEVEL_D |
| 34 | POS_XY_P |
| 35 | POS_XY_I |
| 36 | POS_XY_D |
| 37 | POS_Z_P |
| 38 | POS_Z_I |
| 39 | POS_Z_D |
| 40 | HEADING_P |
| 41 | VEL_XY_P |
| 42 | VEL_XY_I |
| 43 | VEL_XY_D |
| 44 | VEL_Z_P |
| 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 | PROFILE | Switch between 3 rate profiles using a 3 position switch. |
| 49 | ADJUSTMENT_VTX_POWER_LEVEL |
## Examples
@ -263,4 +263,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

@ -52,17 +52,22 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` |
| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` |
| 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
| 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` |
| 33 | SIN | Computes SIN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
| 34 | COS | Computes COS of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
| 35 | TAN | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
| 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled |
| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
### Operands
@ -106,6 +111,24 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 23 | IS_WP | boolean `0`/`1` |
| 24 | IS_LANDING | boolean `0`/`1` |
| 25 | IS_FAILSAFE | boolean `0`/`1` |
| 26 | STABILIZED_ROLL | Roll PID controller output `[-500:500]` |
| 27 | STABILIZED_PITCH | Pitch PID controller output `[-500:500]` |
| 28 | STABILIZED_YAW | Yaw PID controller output `[-500:500]` |
| 29 | ACTIVE_WAYPOINT_INDEX | Indexed from `1`. To verify WP is in progress, use `IS_WP` |
| 30 | ACTIVE_WAYPOINT_ACTION | See ACTIVE_WAYPOINT_ACTION paragraph |
##### ACTIVE_WAYPOINT_ACTION
| Action | Value |
|---- |---- |
| WAYPOINT | 1 |
| HOLD_TIME | 3 |
| RTH | 4 |
| SET_POI | 5 |
| JUMP | 6 |
| SET_HEAD | 7 |
| LAND | 8 |
#### FLIGHT_MODE
@ -173,3 +196,36 @@ Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true
If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel
### Set VTX channel with a POT
Set VTX channel with a POT on the radio assigned to RC channel 6
```
logic 0 1 -1 15 1 6 0 1000 0
logic 1 1 -1 37 4 0 0 7 0
logic 2 1 -1 14 4 1 0 1 0
logic 3 1 -1 31 4 2 0 0 0
```
Steps:
1. Normalize range `[1000:2000]` to `[0:1000]` by substracting `1000`
2. Scale range `[0:1000]` to `[0:7]`
3. Increase range by `1` to have the range of `[1:8]`
4. Assign LC#2 to VTX channel function
### Set VTX power with a POT
Set VTX power with a POT on the radio assigned to RC channel 6. In this example we scale POT to 4 power level `[1:4]`
```
logic 0 1 -1 15 1 6 0 1000 0
logic 1 1 -1 37 4 0 0 3 0
logic 2 1 -1 14 4 1 0 1 0
logic 3 1 -1 25 4 2 0 0 0
```
Steps:
1. Normalize range [1000:2000] to [0:1000] by substracting `1000`
2. Scale range [0:1000] to [0:3]
3. Increase range by `1` to have the range of [1:4]
4. Assign LC#2 to VTX power function

View file

@ -95,9 +95,20 @@ Just connect the S.Port wire from the receiver to the TX pad of a free UART on y
#### Configuration
For INAV 2.6 and newer versions, the default configuration should just work. However, if you're
upgrading from a previous version you might need to set the following settings to their
default values:
```
set serialrx_inverted = true
set serialrx_halfduplex = true
set serialrx_inverted = OFF
set serialrx_halfduplex = AUTO
```
For INAV versions prior to 2.6, you need to change the following settings:
```
set serialrx_inverted = ON
set serialrx_halfduplex = ON
```
### XBUS

70
docs/Safehomes.md Normal file
View file

@ -0,0 +1,70 @@
# INav - Safehomes
## Introduction
The "Home" position is used for the landing point when landing is enabled or in an emergency situation. It is usually determined by the GPS location where the aircraft is armed.
For airplanes, the landing procedure is explained very well by Pawel Spychalski [here.](https://quadmeup.com/inav-1-8-automated-landing-for-fixed-wings/)
<img src="https://quadmeup.com/wp-content/uploads/2017/06/fixed-wing-landing-1024x683.png" width="600">
One potential risk when landing is that there might be buildings, trees and other obstacles in the way as the airplance circles lower toward the ground at the arming point. Most people don't go the middle of the field when arming their airplanes.
## Safehome
Safehomes are a list of GPS coordinates that identify safe landing points. When the flight controller is armed, it checks the list of safehomes. The first one that is enabled and within 200m of the current position will be selected. Otherwise, it reverts to the old behaviour of using your current GPS position as home.
You can define up to 8 safehomes for different locations you fly at.
When you are choosing safehome locations, ensure that the location is clear of obstructions for a radius more than 50m (`nav_fw_loiter_radius`). As the plane descends, the circles aren't always symmetrical, as wind direction could result in some wider or tighter turns. Also, the direction and length of the final landing stage is also unknown. You want to choose a point that has provides a margin for variation and the final landing.
## OSD Message when Armed
When the aircraft is armed, the OSD briefly shows `ARMED` and the current GPS position and current date and time.
If a safehome is selected, an additional message appears:
```
H - DIST -> SAFEHOME n <- New message
n is the Safehome index (0-7)
ARMED DIST is the distance from
GPS LATITUDE your current position to this safehome
GPS LONGITUDE
GPS PLUS CODE
CURRENT DATE
CURRENT TIME
```
The GPS details are those of the selected safehome.
To draw your attention to "HOME" being replaced, the message flashes and stays visible longer.
## CLI command `safehome` to manage safehomes
`safehome` - List all safehomes
`safehome reset` - Clears all safehomes.
`safehome <n> <enabled> <lat> <lon>` - Set the parameters of a safehome with index `<n>`.
Parameters:
* `<enabled>` - 0 is disabled, 1 is enabled.
* `<lat>` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789).
* `<lon>` - Longitude.
Safehomes are saved along with your regular settings and will appear in `diff` and `dump` output. Use `save` to save any changes, as with other settings.
### `safehome` example
```
# safehome
safehome 0 1 543533193 -45179273
safehome 1 1 435464846 -78654544
safehome 2 0 0 0
safehome 3 0 0 0
safehome 4 0 0 0
safehome 5 0 0 0
safehome 6 0 0 0
safehome 7 0 0 0
```

View file

@ -12,6 +12,8 @@
| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
| acc_notch_cutoff | | |
| acc_notch_hz | | |
| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
@ -33,6 +35,7 @@
| antigravity_accelerator | 1 | |
| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain |
| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements |
| applied_defaults | 0 | Internal (configurator) hint. Should not be changed manually |
| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. |
| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting |
@ -51,7 +54,11 @@
| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. |
| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. |
| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. |
| d_boost_factor | | |
| d_boost_gyro_delta_lpf_hz | | |
| d_boost_max_at_acceleration | | |
| deadband | 5 | 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. |
| debug_mode | NONE | Defines debug values exposed in debug variables (developer / debugging setting) |
| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. |
| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON |
| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter |
@ -62,6 +69,14 @@
| dynamic_gyro_notch_min_hz | 150 | 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` |
| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches |
| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers |
| eleres_freq | | |
| eleres_loc_delay | | |
| eleres_loc_en | | |
| eleres_loc_power | | |
| eleres_signature | | |
| eleres_telemetry_en | | |
| eleres_telemetry_power | | |
| esc_sensor_listen_only | | |
| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). |
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
@ -80,6 +95,7 @@
| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
| fpv_mix_degrees | | |
| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
@ -120,9 +136,12 @@
| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
| gyro_notch_cutoff | | |
| gyro_notch_hz | | |
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) |
| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
| gyro_to_use | | |
| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. |
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
@ -135,6 +154,7 @@
| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements |
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements |
| inav_allow_dead_reckoning | OFF | Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation |
| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. |
| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] |
| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. |
@ -142,23 +162,34 @@
| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] |
| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) |
| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
| inav_use_gps_no_baro | | |
| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. |
| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation |
| inav_w_xy_flow_p | | |
| inav_w_xy_flow_v | | |
| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. |
| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed |
| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost |
| inav_w_xyz_acc_p | | |
| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate |
| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero |
| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost |
| inav_w_z_surface_p | | |
| inav_w_z_surface_v | | |
| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) |
| ledstrip_visual_beeper | OFF | |
| log_level | `ERROR` | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. |
| log_topics | 0 | Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage. |
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. |
| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. |
| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target |
| maggain_x | 0 | Magnetometer calibration X gain. If 0, no calibration or calibration failed |
| maggain_y | 0 | Magnetometer calibration Y gain. If 0, no calibration or calibration failed |
| maggain_z | 0 | Magnetometer calibration Z gain. If 0, no calibration or calibration failed |
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
@ -167,6 +198,11 @@
| manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] |
| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% |
| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% |
| mavlink_ext_status_rate | | |
| mavlink_extra1_rate | | |
| mavlink_extra2_rate | | |
| mavlink_pos_rate | | |
| mavlink_rc_chan_rate | | |
| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° |
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
@ -185,6 +221,8 @@
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL |
| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW |
| mc_iterm_relax | | |
| mc_iterm_relax_cutoff | | |
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
@ -197,8 +235,10 @@
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. |
| motor_poles | | |
| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED |
| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. |
| msp_override_channels | 0 | Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. |
| name | Empty string | Craft name |
| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] |
| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] |
@ -248,7 +288,8 @@
| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] |
| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] |
| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] |
| nav_mc_auto_disarm_delay | 2000 | |
| nav_max_terrain_follow_alt | | |
| nav_mc_auto_disarm_delay | 2000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) |
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode |
| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value |
@ -265,6 +306,11 @@
| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) |
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
| nav_mc_vel_xy_dterm_attenuation | 90 | Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. |
| nav_mc_vel_xy_dterm_attenuation_end | 60 | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum |
| nav_mc_vel_xy_dterm_attenuation_start | 10" | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins |
| nav_mc_vel_xy_dterm_lpf_hz | | |
| nav_mc_vel_xy_ff | | |
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
@ -280,35 +326,62 @@
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) |
| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) |
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats |
| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude |
| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. |
| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius |
| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. |
| opflow_hardware | | Selection of OPFLOW hardware. |
| opflow_scale | | |
| osd_ahi_bordered | OFF | Shows a border/corners around the AHI region (pixel OSD only) |
| osd_ahi_height | 162 | AHI height in pixels (pixel OSD only) |
| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. |
| osd_ahi_vertical_offset | 0 | AHI vertical offset from center (pixel OSD only) |
| osd_ahi_width | 132 | AHI width in pixels (pixel OSD only) |
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon |
| osd_artificial_horizon_reverse_roll | | |
| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) |
| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) |
| osd_camera_fov_h | 135 | Horizontal field of view for the camera in degres |
| osd_camera_fov_v | 85 | Vertical field of view for the camera in degres |
| osd_camera_uptilt | 0 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal |
| osd_coordinate_digits | | |
| osd_crosshairs_style | DEFAULT | To set the visual type for the crosshair |
| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. |
| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) |
| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe |
| osd_force_grid | OFF | Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) |
| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) |
| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) |
| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) |
| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. |
| osd_horizon_offset | 0 | To vertically adjust the whole OSD and AHI and scrolling bars |
| osd_hud_homepoint | 0 | To 3D-display the home point location in the hud |
| osd_hud_homing | 0 | To display little arrows around the crossair showing where the home point is in the hud |
| osd_hud_margin_h | 3 | Left and right margins for the hud area |
| osd_hud_margin_v | 3 | Top and bottom margins for the hud area |
| osd_hud_radar_disp | 0 | Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc |
| osd_hud_radar_nearest | 0 | To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable. |
| osd_hud_radar_range_max | 4000" | In meters, radar aircrafts further away than this will not be displayed in the hud |
| osd_hud_radar_range_min | 3 | In meters, radar aircrafts closer than this will not be displayed in the hud |
| osd_hud_wp_disp | 0 | How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2) |
| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_left_sidebar_scroll | | |
| osd_left_sidebar_scroll_step | 0 | How many units each sidebar step represents. 0 means the default value for the scroll type. |
| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. |
| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
| osd_plus_code_digits | | |
| osd_right_sidebar_scroll | | |
| osd_right_sidebar_scroll_step | 0 | Same as left_sidebar_scroll_step, but for the right sidebar |
| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) |
| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink |
| osd_sidebar_horizontal_offset | 0 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. |
| osd_sidebar_scroll_arrows | | |
| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) |
| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` |
| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) |
@ -317,9 +390,17 @@
| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` |
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
| pinio_box1 | | |
| pinio_box2 | | |
| pinio_box3 | | |
| pinio_box4 | | |
| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
| pitot_hardware | NONE | Selection of pitot hardware. |
| pitot_lpf_milli_hz | | |
| pitot_scale | | |
| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo |
| rangefinder_hardware | NONE | Selection of rangefinder hardware. |
| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts |
| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. |
| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. |
@ -327,6 +408,7 @@
| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values |
| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) |
| reboot_character | 82 | Special character used to trigger reboot |
| receiver_type | `TARGET dependent` | Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL` |
| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON |
| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV |
@ -341,14 +423,22 @@
| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation |
| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. |
| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. |
| rx_spi_id | | |
| rx_spi_protocol | | |
| rx_spi_rf_channel_count | | |
| sbus_sync_interval | | |
| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. |
| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire |
| serialrx_halfduplex | AUTO | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire. |
| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). |
| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
| servo_center_pulse | 1500 | Servo midpoint |
| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] |
| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) |
| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. |
| setpoint_kalman_enabled | OFF | Enable Kalman filter on the PID controller setpoint |
| setpoint_kalman_q | 100 | Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds |
| setpoint_kalman_sharpness | 100 | Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets |
| setpoint_kalman_w | 4 | Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response |
| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. |
| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. |
| sim_pin | Empty string | PIN code for the SIM module |
@ -356,9 +446,12 @@
| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 |
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] |
| smartport_master_halfduplex | | |
| smartport_master_inverted | | |
| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX |
| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) |
| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. |
| stats_total_energy | | |
| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. |
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
@ -386,6 +479,8 @@
| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. |
| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. |
| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. |
| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities |
| vtx_pit_mode_chan | | |
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
| yaw_deadband | 5 | 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. |
| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |

View file

@ -12,6 +12,10 @@ This assigns the device to the plugdev group(a standard group in Ubuntu). To che
```
sudo usermod -a -G plugdev <username>
```
On Arch and its derivatives the group would be uucp and the command:
```
sudo usermod -a -G uucp <username>
```
## Platform Specific: Windows
Chrome can have problems accessing USB devices on Windows. A driver should be automatically installed by Windows for the ST Device in DFU Mode but this doesn't always allow access for Chrome. The solution is to replace the ST driver with a libusb driver. The easiest way to do that is to download [Zadig](http://zadig.akeo.ie/).

View file

@ -83,11 +83,5 @@ Data rate 496Hz 35806 bytes/s 358100 baud
```
## Developer Notes
Providing MSC for a target requires that the `.mk` file includes in `FEATURES` the key `MSC` and at least one of `ONBOARDFLASH` and /or `SDCARD`.
For F4 and F7 targets, `USE_USB_MSC` is set unconditionally in `common.h`; if your target does not support blackbox logging to either SD card or internal flash, you should over-ride this in `target.h`
```
#ifdef USE_USB_MSC
# undef USE_USB_MSC
#endif
```
Providing MSC is automatically enabled for all F4 and up targets that support
`ONBOARDFLASH` and /or `SDCARD`.

View file

@ -28,7 +28,7 @@ You'll have to manually execute the same steps that the build script does:
1. `docker build -t inav-build .`
+ This step is only needed the first time.
2. `docker run --rm -v <PATH_TO_REPO>:/home/src/ inav-build make TARGET=<TARGET>`
2. `docker run --rm -it -v <PATH_TO_REPO>:/src inav-build <TARGET>`
+ Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build.
Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details.

View file

@ -1,50 +0,0 @@
# Short Version
Install the latest Eclipse Standard/SDK and install the **C/C++ developments Tools** plugins
![plugin eclipse](http://i.imgur.com/IdJ8ki1.png)
Import the project using the wizard **Existing Code as Makefile Project**
![](http://i.imgur.com/XsVCwe2.png)
Adjust your build option if necessary
![](https://camo.githubusercontent.com/64a1d32400d6be64dd4b5d237df1e7f1b817f61b/687474703a2f2f692e696d6775722e636f6d2f6641306d30784d2e706e67)
Make sure you have a valid ARM toolchain and Ruby in the path
![](http://i.imgur.com/dAbscJo.png)
# Long version
* First you need an ARM toolchain. Good choices are **GCC ARM Embedded** (https://launchpad.net/gcc-arm-embedded) or **Yagarto** (http://www.yagarto.de).
* Install Ruby (see the document for your operating system).
* Now download Eclipse and unpack it somewhere. At the time of writing Eclipse 4.2 was the latest stable version.
* To work with ARM projects in Eclipse you need a few plugins:
+ **Eclipse C Development Tools** (CDT) (available via *Help > Install new Software*).
+ **Zylin Embedded CDT Plugin** (http://opensource.zylin.com/embeddedcdt.html).
+ **GNU ARM Eclipse** (http://sourceforge.net/projects/gnuarmeclipse/).
+ If you want to hook up an SWD debugger you also need the **GDB Hardware Debugging** plugin (Also available via *Install new Software*).
* Now clone the project to your harddrive.
* Create a new C project in Eclipse and choose ARM Cross Target Application and your ARM toolchain.
* Import the Git project into the C project in Eclipse via *File > Import > General > File System*.
* Activate Git via *Project > Team > Share Project*.
* Switch to the development branch in Eclipse (*Project > Team > Switch To > development*).
* The next thing you need to do is adjust the project configuration. There is a Makefile included that works but you might want to use GNU ARM Eclipse's automatic Makefile generation. Open the Project configuration and go to *C/C++ Build > Settings*
* Under *Target Processor* choose "cortex-m3"
* Under *ARM Yagarto [Windows/Mac OS] Linker > General* (or whatever toolchain you chose)
+ Browse to the Script file *stm32_flash.ld*
+ Uncheck "Do not use standard start files"
+ Check "Remove unused sections"
* Under *ARM Yagarto [Windows/Mac OS] Linker > Libraries*
+ Add "m" for the math library
* Under *ARM Yagarto [Windows/Mac OS] Compiler > Preprocessor* add the following 2 items to "Defined Symbols":
+ STM32F10X_MD
+ USE_STDPERIPH_DRIVER
* Under *ARM Yagarto [Windows/Mac OS] Compiler > Directories* add the following 3 items
+ ${workspace_loc:/${ProjName}/lib/CMSIS/CM3/CoreSupport}
+ ${workspace_loc:/${ProjName}/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x}
+ ${workspace_loc:/${ProjName}/lib/STM32F10x_StdPeriph_Driver/inc}
* Under *ARM Yagarto [Windows/Mac OS] Compiler > Miscellaneous* add the following item to "Other flags":
+ -fomit-frame-pointer
* The code in the support directory is for uploading firmware to the board and is meant for your host machine. Hence, it must not be included in the build process. Just right-click on it to open its properties and choose "Exclude from build" under *C/C++ Build > Settings*
* The last thing you need to do is adding your toolchain to the PATH environment variable.
+ Go to *Project > Properties > C/C++ Build > Environment*, add a variable named "PATH" and fill in the full path of your toolchain's binaries.
+ Make sure "Append variables to native environment" is selected.
* Try to build the project via *Project > Build Project*.
* **Note**: If you're getting "...could not be resolved" errors for data types like int32_t etc. try to disable and re-enable the Indexer under *Project > Properties > C/C++ General > Indexer*.

View file

@ -0,0 +1,12 @@
# Building in FreeBSD
In order to build the inav firmware in FreeBSD, it is recommended to install [Linux Binary Emulation](https://www.freebsd.org/doc/handbook/linuxemu.html). This will enable you to use the project recommended ARM cross-compiler. The cross-compiler available in Ports tends to be too old to build inav firmware.
* Install Linux binary emulation
* Install the following packages (`pkg` provides suitable versions)
- `git`
- `cmake`
- `make`
- `ruby`
* Follow the [Building in Linux](Building%20in%20Linux.md) guide.

View file

@ -0,0 +1,156 @@
# Generic Linux development tools
## Overview
This article endeavours to provide a generic guide for compiling inav on Linux for inav 2.6 and later.
inav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux).
In order to provide a uniform and reasonably modern cross compiler, inav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The inav approach of providing a recommended compiler is however both sound and justified:
* The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers)
* Disto cross-compilers are often older than the recommended inav compiler
* The installed cross-compiler is only used to build inav and it not obviously / generally available outside of the inav build environment.
There are a however some specific cases for using the distro cross-compiler in preference to that installed by inav:
* You are using a distro that installs a more modern compiler (Arch)
* You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32).
## Prerequisites
In addition to a cross-compiler, it is necessary to install some other tools:
* `git` : clone and manage the inav code repository
* `cmake` : generate the build environment
* `make` : run the firmware compilation
* `ruby` : build some generated source files from JSON definitions
* `gcc` : native compiler used to generate settings and run tests
Note that inav requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools.
Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does.
### Ubuntu / Debian
```
# make sure the system is updated first
sudo apt update && sudo apt upgrade
sudo apt install git make ruby cmake gcc
```
### Fedora
```
# make sure the system is updated first
sudo dnf -y update
sudo dnf install git make ruby cmake gcc
```
### Arch
```
# make sure the system is updated first
sudo pacman -Syu
sudo pacman -S git make ruby cmake gcc
```
Once these prerequisites are installed, we can clone the repository to provide a local instance of the inav source code.
## Cloning the repository
```
git clone https://github.com/iNavFlight/inav.git
```
Note: If you have a Github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link.
The `git clone` creates an `inav` directory; we can enter this directory, configure the build environment and build firmware.
## 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.
## Using `cmake`
The canonanical method of using `cmake` is to create a `build` directory and run the `cmake` and `make` commands from within the `build` directory. So, assuming we've cloned the firmware repository into an `inav` directory, we can issue the following commands to set up the build environment.
```
cd inav
# first time only, create the build directory
mkdir build
cd build
cmake ..
# note the "..", this is required as it tells cmake where to find its ruleset
```
`cmake` will check for the presence of an inav-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler.
Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as:
```
cmake -DCOMPILER_VERSION_CHECK=OFF ..
```
`cmake` will generate a number of files in your `build` directory, including a cache of generated build settings `CMakeCache.txt` and a `Makefile`.
## Bulding the firmware
Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler.
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.
```
# Build the MATEKF405 firmware
make MATEKF405
```
One can also build multiple targets from a sinlge `make` command:
```
make MATEKF405 MATEKF722
```
The resultant hex file are in the `build` directory.
You can then use the INAV Configurator to flash the local `build/inav_x.y.z_TARGET.hex` file, or use `stm32flash` or `dfu-util` directly from the command line.
[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing.
### Cleaning
You can clean out the built files, either for all targets or selectively; a selective clean target is simply defined by prefixing the target name with `clean_`:
```
# clean out every thing
make clean
# clean out single target
make clean_MATEKF405
# or multiple targets
make clean_MATEKF405 clean_MATEKF722
```
### `cmake` cache maintainance
`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.
* `make edit_cache`
* `make rebuild_cache`
It is unlikely that the typical user will need to employ these options, other than perhaps to change between the embedded ARM and distro compilers.
## Updating and rebuilding
In order to update your local firmware build:
* 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:
```
$ cd inav
$ git pull
$ cd build
$ 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).

View file

@ -3,7 +3,7 @@
Building in Mac OS X can be accomplished in just a few steps:
* Install general development tools (clang, make, git)
* Install ARM GCC 7.2 series compiler or higher
* Install cmake
* Checkout INAV sourcecode through git
* Build the code
@ -35,41 +35,24 @@ installation, open up XCode and enter its preferences menu. Go to the "downloads
[from the App Store]: https://itunes.apple.com/us/app/xcode/id497799835
## Install ARM GCC 7.2 series or higher compiler
## Install cmake
INAV is built using series 7.2 or above GCC compiler provided by the [GNU Tools for ARM Embedded Processors project][].
The easiest way to install cmake's command line executable is via
[Homebrew](https://brew.sh) (a package manager for macOS). Go to their site
and follow their installation instructions.
Grab the Mac installation tarball for the latest version in the 7.2 series or above (e.g. gcc-arm-none-eabi-7-2017-q4-major-mac.tar.bz2). Move it somewhere useful
such as a `~/development` folder (in your home directory) and double click it to unpack it. You should end up with a
folder with a name similar to `~/development/gcc-arm-none-eabi-7-2017-q4-major/`.
Once Homebrew is installed, type `brew install cmake` in a terminal to install
cmake.
Now you just need to add the `bin/` directory from inside the GCC directory to your system's path. Run `nano ~/.profile`. Add a
new line at the end of the file which adds the path for the `bin/` folder to your path, like so:
Alternatively, cmake binaries for macOS are available from
[cmake.org](https://cmake.org/download/). If you prefer installing it this way,
you'd have to manually add cmake's command line binary to your `$PATH`. Assuming
`CMake.app` has been copied to `/Applications`, adding the following line to
`~/.zshrc` would make the cmake command available.
```sh
export PATH=$PATH:/Applications/CMake.app/Contents/bin
```
export PATH=$PATH:~/development/gcc-arm-none-eabi-7-2017-q4-major/bin
```
Press CTRL+X to exit nano, and answer "y" when prompted to save your changes.
Now *close this terminal window* and open a new one. Try running:
```
arm-none-eabi-gcc --version
```
You should get output similar to (in this example compiler series 7.2.1 is used):
```
arm-none-eabi-gcc (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 7.2.1 20170904 (release) [ARM/embedded-7-branch revision 255204]
Copyright (C) 2017 Free Software Foundation, Inc.
This is free software; see the source for copying conditions. There is NO
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
```
If `arm-none-eabi-gcc` couldn't be found, go back and check that you entered the correct path in your `~/.profile` file.
[GNU Tools for ARM Embedded Processors project]: https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
## Ruby
@ -90,9 +73,48 @@ This will download the entire INAV repository for you into a new folder called "
## Build the code
Enter the inav directory and run `make TARGET=SPRACINGF3` to build firmware for the SPRacing F3. When the build completes,
the .hex firmware should be available as `obj/inav_x.x.x_SPRACINGF3.hex` for you to flash using the INAV
Configurator.
Assuming you've just cloned the source code, you can switch your current
directory to inav's source try by typing:
```sh
cd inav
```
Inside the inav directory, create a new directory to store the built files. This
helps keeping everything nice and tidy, separating source code from artifacts. By
convention this directory is usually called `build`, but any name would work. Enter
the following command to create it and switch your working directory to it:
```sh
mkdir -p build && cd build
```
Now we need to configure the build by using the following command:
```sh
cmake ..
```
This will automatically download the required compiler for inav, so it
might take a few minutes. Once it's finished without errors, you can
build the target that you want by typing `make target-name`. e.g.:
```sh
make -j8 MATEKF722 # Will build MATEKF722 target
```
A list of all the available targets can be displayed with:
```sh
make targets
```
Once the build completes, the correspondent `.hex` file will be found
in current directory (e.g. `build`) and it will be named as
`inav_x.y.z_TARGET.hex`. `x.y.z` corresponds to the INAV version number
while `TARGET` will be the target name you've just built. e.g.
`inav_2.6.0_MATEKF722.hex`. This is the file that can be flashed using
INAV Configurator.
## Updating to the latest source
@ -100,10 +122,9 @@ If you want to erase your local changes and update to the latest version of the
inav directory and run these commands to first erase your local changes, fetch and merge the latest
changes from the repository, then rebuild the firmware:
```
```sh
git reset --hard
git pull
make clean TARGET=SPRACINGF3
make TARGET=SPRACINGF3
make target-name # e.g. make MATEKF722
```

View file

@ -1,4 +1,4 @@
# Building in Windows 10 with Linux subsystem
# Building in Windows 10 with Linux subsystem [Recommended]
Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10.
@ -25,9 +25,13 @@ Update the repo packages:
Install Git, Make, gcc and Ruby
1. `sudo apt-get install git`
1. `sudo apt-get install make`
1. `sudo apt-get install gcc-arm-none-eabi`
1. `sudo apt-get install cmake`
1. `sudo apt-get install ruby`
### CMAKE and Ubuntu 18_04
To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71)
## Downloading the iNav repository (example):
Mount MS windows C drive and clone iNav
@ -40,15 +44,52 @@ You now have a folder called inav in the root of C drive that you can edit in wi
## Building (example):
For detailed build instrusctions see [Building in Linux](Building%20in%20Linux.md)
Launch Ubuntu:
Click Windows Start button then scroll and lauch "Ubuntu"
Building from Ubunto command line
`cd /mnt/c/inav`
`make clean TARGET=OMNIBUSF4PRO` (as an example)
`make TARGET=MATEKF405` (as an example)
Building from Ubuntu command line
`cd /mnt/c/inav`
Do it onece to prepare build environment
```
mkdir build
cd build
cmake ..
```
Then to build
```
cd build
make MATEKF722
```
## 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\obj`
Hex files can be found in the folder `c:\inav\build`
## Troubleshooting
### Syntax error: "(" unexpected
```
dzikuvx@BerlinAtHome:/mnt/c/Users/pspyc/Documents/Projects/inav/build$ make MATEKF722SE
Generating MATEKF722SE/settings_generated.h, MATEKF722SE/settings_generated.c
/bin/sh: 1: Syntax error: "(" unexpected
make[3]: *** [src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.elf.dir/build.make:63: src/main/target/MATEKF722SE/MATEKF722SE/settings_generated.h] Error 2
make[2]: *** [CMakeFiles/Makefile2:33607: src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.elf.dir/all] Error 2
make[1]: *** [CMakeFiles/Makefile2:33290: src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.dir/rule] Error 2
make: *** [Makefile:13703: MATEKF722SE] Error 2
```
This error can be triggered by a Windows PATHs included in the Linux Subsystem. The solution is to:
1. Open Windows RegEdit tool
1. Find `HKEY_CURRENT_USER\Software\Microsoft\Windows\CurrentVersion\Lxss\{GUID}\Flags`
1. Change `Flags` from `7` to `5`
1. Restart WSL and Windows preferably
1. `cd build`
1. `cmake ..`
1. `make {TARGET}` should be working again

View file

@ -1,4 +1,4 @@
# Building in windows light
# Building in windows light [Deprecated]
no cygwin and no path changes
## Install Git for windows

View file

@ -0,0 +1,69 @@
# Cmake Usage
## Introduction
This guide documents inav usage of the `cmake` build tool.
## Target Defintion
A target requires `CMakeLists.txt` file. This file contains one of more lines of the form:
```
target_hardware_definition(name optional_parameters)
```
For example:
```
target_stm32f405xg(QUARKVISION HSE_MHZ 16)
```
* The hardware is `stm32f405xg`, a F405 with a 1MiB flash
* The name is `QUARKVISION` (a board that never reached production)
* The optional parameter is `HSE_MHZ 16` defining the non-default high-speed external (HSE) oscillator clock.
## Hardware names
As of inav 2.6, the following target hardware platforms are recognised:
* stm32f303xc
* stm32f405xg
* stm32f411xe
* stm32f427xg
* stm32f722xe
* stm32f745xg
* stm32f765xg
* stm32f765xi
The device characteristics for these names may be found at [stm32-base.org](https://stm32-base.org/cheatsheets/linker-memory-regions/).
## Optional Parameters
The following optional parameters are recognised:
| Paramater | Usage |
| --------- | ----- |
| `SKIP_RELEASES` | The target is disabled for releases and CI. It still may be possible to build the target directly. |
| `COMPILE_DEFINITIONS "VAR[=value]"` | Sets a preprocessor define. |
| `HSE_MZ value` | The target uses a high-speed external crystal (HSE) oscillator clock with a frequency different from the 8MHz default. The `value` is the desired clock, for example `HSE_MHZ 24` |
Multiple optional parameters may be specified, for example `HSE_MHZ 16 SKIP_RELEASES`.
## Target variations
A number of targets support multiple variants, either successive versions of the same hardware, or varations that enable different resources (soft serial, leds etc.) This is defined by adding additional `target_` lines to `CMakeLists.txt`. For example, the OMNIBUSF4 and its multiple clones / variations, `src/main/target/OMNIBUSF4/CMakeLists.txt`:
```
target_stm32f405xg(DYSF4PRO)
target_stm32f405xg(DYSF4PROV2)
target_stm32f405xg(OMNIBUSF4)
# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping
target_stm32f405xg(OMNIBUSF4PRO)
target_stm32f405xg(OMNIBUSF4PRO_LEDSTRIPM5)
target_stm32f405xg(OMNIBUSF4V3_S5_S6_2SS)
target_stm32f405xg(OMNIBUSF4V3_S5S6_SS)
target_stm32f405xg(OMNIBUSF4V3_S6_SS)
# OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target,
# except for an inverter on UART6.
target_stm32f405xg(OMNIBUSF4V3)
```

View file

@ -1,148 +0,0 @@
# Generic Linux development tools
## Overview
This article endeavours to provide a generic guide for compiling iNav on Linux for iNav after iNav 2.2.1.
iNav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux).
In order to provide a uniform and reasonably modern cross compiler, after release iNav 2.2.1, iNav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The iNav approach of providing a recommended compiler is however both sound and justified:
* The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our UAS)
* Disto cross-compiler are often older than the recommended iNav compiler
* The installed cross-compiler is only used to build iNav and it not obviously / generally available outside of the iNav build environment.
There are a however some specific cases for using the distro cross-compiler in preference to that installed by iNav:
* You are using a distro that installs a more modern compiler (Arch)
* You are using a host platform other than x86_64 (e.g. ia32, AArch64).
However, before we consider the compiler options, it is necessary to install some other dependencies.
## Other Prerequisites
In addition to a cross-compiler, it is necessary to install some other tools:
### Ubuntu / Debian
```
$ # make sure the system is updated first
$ sudo apt update && sudo apt upgrade
$ sudo apt install gcc git make ruby curl
```
### Fedora
```
$ # make sure the system is updated first
$ sudo dnf -y update
$ sudo dnf install gcc git make ruby curl
```
### Arch
```
$ # make sure the system is updated first
$ sudo pacman -Syu
$ sudo pacman -S gcc git make ruby curl
```
Once these prerequisites are installed, we can clone the repository to provide a local instance of the iNav source code.
## Cloning the repository
```
$ git clone https://github.com/iNavFlight/inav.git
```
Note: If you have a Github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link.
The `git clone` creates an `inav` directory; we can enter this directory and try and build the firmware. Initially, will probably fail as we have not yet defined the cross-compiler. The following example is from Ubuntu 19.04:
```
$ cd inav
$ make TARGET=MATEKF405
make/tools.mk:78: *** **ERROR** your arm-none-eabi-gcc is '7.3.1', but '8.2.1' is expected. Override with 'GCC_REQUIRED_VERSION' in make/local.mk or run 'make arm_sdk_install' to install the right version automatically in the tools folder of this repo. Stop.
```
We must either install the iNav toolchain cross-compiler (preferred option) or define the distro cross-compiler.
## Compiler choices
### Installing the iNav preferred cross compiler.
In the iNav directory, issue the command `make arm_sdk_install`. The output will be something like the following (only hopefully you do not suffer from "rural broadband"):
```
$ make arm_sdk_install
mkdir -p tools
mkdir -p downloads
Warning: Illegal date format for -z, --time-cond (and not a file name).
Warning: Disabling time condition. See curl_getdate(3) for valid date syntax.
% Total % Received % Xferd Average Speed Time Time Time Current
Dload Upload Total Spent Left Speed
100 244 100 244 0 0 645 0 --:--:-- --:--:-- --:--:-- 643
100 102M 100 102M 0 0 1385k 0 0:01:15 0:01:15 --:--:-- 1392k
```
Note that the `curl` warning will only occur the first time (as there is no pre-existing iNav-specific cross-compiler installed).
### Using the Distro compiler.
If your distro provides a more recent cross compiler, or you're using a host platform other than x86_64 you may choose to use your distro compiler (or have no choice in the case of "not x86_64").
You must first install the distro compiler: Arch is the most likely to provide a more modern cross compiler, which would need to be installed as `sudo pacman -S arm-none-eabi-gcc arm-none-eabi-binutils arm-none-eabi-newlib`.
There are two options to define the distro compiler version:
* Invoke `make` with the variable `GCC_REQUIRED_VERSION` set to the distro version. This can be done as:
```
$ make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion)
```
For convenience, you can create an `alias` or define a shell function. The shell function will be evaluated each time it is invoked, while the alias will be evaluated once (typically at login), for example:
```
# bash function, typically in ~/.bashrc
$ makefc() { make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) $@; }
export -f makefc
# or, bash alias, typically in ~/.bash_aliases
$ alias makefc="make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) $@"
```
then e.g `$ makefc TARGET=MATEKF405`
* or, create the file `make/local.mk` defining the local distro compiler version.
```
$ echo GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) > make/local.mk
```
then use `make` normally, `$ make TARGET=MATEKF405`
If you define the distro cross-compiler version in `make/local.mk`, you will need to update `make/local.mk` whenever your disto updates the cross-compiler.
## Building the firmware
By default, `make` builds the REVO target, to build another target, specify the target name to the make command, for example:
```
make TARGET=MATEKF405
```
The resultant hex file are in the `obj/` directory.
You can use the INAV Configurator to flash the local ```obj/inav_TARGET.hex``` file, or use `stm32flash` or `dfu-util` directly from the command line.
[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing.
## Updating and rebuilding
In order to update your local firmware build:
* Navigate to the local iNav repository
* Use the following steps to pull the latest changes and rebuild your local version of iNav:
```
$ cd inav
$ git pull
$ make TARGET=<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).

View file

@ -0,0 +1,119 @@
# IDE - Visual Studio Code with Windows 10
![Visual Studio Code](assets/vscode01.png)
[Visual Studio Code](https://code.visualstudio.com/) is probably the best free option for all Windows 10 users. It provides almost seamless integration with WSL running Ubuntu, syntax highlighting, building, and hardware debugging.
## Setup
1. Setup build environment using [generic WSL guide](Building%20in%20Windows%2010%20with%20Linux%20Subsystem.md)
1. Download and install [Visual Studio Code](https://code.visualstudio.com/)
1. From the VS Code Extensions download [Remote - WSL](https://marketplace.visualstudio.com/items?itemName=ms-vscode-remote.remote-wsl) plugin
1. Open INAV folder
1. Use `Ctrl + Shift + P` to run option `Remote-WSL: Reopen Folder in WSL`
1. Allow firewall and other permissions if requested
1. Install plugins in WSL workspace:
1. [C/C++ from Microsoft](https://marketplace.visualstudio.com/items?itemName=ms-vscode.cpptools) for C/C++ support
1. [Bookmarks](https://marketplace.visualstudio.com/items?itemName=alefragnani.Bookmarks) for simpler navigation
1. Configure the environment using the following snippets as a base
### C propertiues
Edit file `./.vscode/c_cpp_properties.json` to setup enabled `defines`
```
{
"configurations": [
{
"name": "Win32",
"includePath": [
"${workspaceRoot}",
"${workspaceRoot}/src/main/**"
],
"browse": {
"limitSymbolsToIncludedHeaders": false,
"path": [
"${workspaceRoot}/**"
]
},
"intelliSenseMode": "msvc-x64",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
"USE_NAV",
"NAV_FIXED_WING_LANDING",
"USE_OSD",
"USE_GYRO_NOTCH_1",
"USE_GYRO_NOTCH_2",
"USE_DTERM_NOTCH",
"USE_ACC_NOTCH",
"USE_GYRO_BIQUAD_RC_FIR2",
"USE_D_BOOST",
"USE_SERIALSHOT",
"USE_ANTIGRAVITY",
"USE_ASYNC_GYRO_PROCESSING",
"USE_RPM_FILTER",
"USE_GLOBAL_FUNCTIONS",
"USE_DYNAMIC_FILTERS",
"USE_IMU_BNO055",
"USE_SECONDARY_IMU",
"USE_DSHOT",
"FLASH_SIZE 480",
"USE_I2C_IO_EXPANDER",
"USE_PCF8574",
"USE_ESC_SENSOR"
]
}
],
"version": 4
}
```
### Tasks
Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard shortcut and from Command Console.
```
{
// See https://go.microsoft.com/fwlink/?LinkId=733558
// 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": "CMAKE Update",
"type": "shell",
"command": "cmake ..",
"group": "build",
"problemMatcher": [],
"options": {
"cwd": "${workspaceFolder}/build"
}
}
]
}
```

View file

@ -1,63 +0,0 @@
### IO variables
`gyroADC/8192*2000 = deg/s`
`gyroADC/4 ~ deg/s`
`rcCommand` - `<-500 - 500>` nominal, but is scaled with `rcRate/100`, max +-1250
`inclination` - in 0.1 degree, roll and pitch deviation from horizontal position
`max_angle_inclination` - in 0.1 degree, default 50 degrees (500)
`axisPID` - output to mixer, will be added to throttle(`<1000-2000>`), output range is `<minthrottle, maxthrottle>` (default `<1150 - 1850>`)
### PID controller 0, "MultiWii" (default)
#### Leveling term
```
error = constrain(2*rcCommand[axis], limit +- max_angle_inclination) - inclination[axis]
Pacc = constrain(P8[PIDLEVEL]/100 * error, limit +- 5 * D8[PIDLEVEL])
Iacc = intergrate(error, limit +-10000) * I8[PIDLEVEL] / 4096
```
#### Gyro term
```
Pgyro = rcCommand[axis];
error = rcCommand[axis] * 10 * 8 / pidProfile->P8[axis] - gyroADC[axis] / 4; (conversion so that error is in deg/s ?)
Igyro = integrate(error, limit +-16000) / 10 / 8 * I8[axis] / 100 (conversion back to mixer units ?)
```
reset I term if
- axis rotation rate > +-64deg/s
- axis is YAW and rcCommand>+-100
##### Mode dependent mix(yaw is always from gyro)
- HORIZON - proportionally according to max deflection
```
deflection = MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])) / 500 ; limit to 0.0 .. 1.0
P = Pacc * (1-deflection) + Pgyro * deflection
I = Iacc * (1-deflection) + Igyro * deflection
```
- gyro
```
P = Pgyro
I = Igyro
```
- ANGLE
```
P = Pacc
I = Iacc
```
#### Gyro stabilization
```
P -= gyroADC[axis] / 4 * dynP8 / 10 / 8
D = -mean(diff(gyroADC[axis] / 4), over 3 samples) * 3 * dynD8 / 32
[equivalent to :]
D = - (gyroADC[axis]/4 - (<3 loops old>gyroADC[axis]/4)) * dynD8 / 32
```
This can be seen as sum of
- PI controller (handles rcCommand, HORIZON/ANGLE); `Igyro` is only output based on gyroADC
- PD controller(parameters dynP8/dynD8) with zero setpoint acting on gyroADC

Binary file not shown.

After

Width:  |  Height:  |  Size: 564 KiB