mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-15 12:25:17 +03:00
Merge branch 'master' of https://github.com/RomanLut/inav into submit-gps-fix-estimation
removed GPS Off box implemented Disable GPS sensor fix logic condition
This commit is contained in:
commit
cb2d448911
379 changed files with 5433 additions and 3656 deletions
6
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
6
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
|
@ -9,9 +9,9 @@ assignees: ''
|
||||||
|
|
||||||
**PLEASE MAKE SURE YOU READ AND UNDERSTAND THE SOCIAL MEDIA SUPPORT CHANNELS. QUESTIONS ABOUT FLASHING, CONFIGURING, PILOTING MAY BE CLOSED WITHOUT FURTHER INTERACTION.**
|
**PLEASE MAKE SURE YOU READ AND UNDERSTAND THE SOCIAL MEDIA SUPPORT CHANNELS. QUESTIONS ABOUT FLASHING, CONFIGURING, PILOTING MAY BE CLOSED WITHOUT FURTHER INTERACTION.**
|
||||||
|
|
||||||
* [Telegram channel](https://t.me/INAVFlight)
|
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
|
||||||
* [Facebook group](https://www.facebook.com/groups/INAVOfficial)
|
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
||||||
* [RC Groups thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-%28navigation-rewrite%29-project)
|
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||||
|
|
||||||
**Please double-check that nobody reported the issue before by using search in this bug tracker.**
|
**Please double-check that nobody reported the issue before by using search in this bug tracker.**
|
||||||
|
|
||||||
|
|
8
.github/workflows/ci.yml
vendored
8
.github/workflows/ci.yml
vendored
|
@ -6,13 +6,13 @@ on: pull_request
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
build:
|
build:
|
||||||
runs-on: ubuntu-18.04
|
runs-on: ubuntu-latest
|
||||||
strategy:
|
strategy:
|
||||||
matrix:
|
matrix:
|
||||||
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
|
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
|
||||||
|
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v3
|
||||||
- name: Install dependencies
|
- name: Install dependencies
|
||||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||||
- name: Setup environment
|
- name: Setup environment
|
||||||
|
@ -45,9 +45,9 @@ jobs:
|
||||||
|
|
||||||
test:
|
test:
|
||||||
needs: [build]
|
needs: [build]
|
||||||
runs-on: ubuntu-18.04
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v3
|
||||||
- name: Install dependencies
|
- name: Install dependencies
|
||||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||||
- name: Run Tests
|
- name: Run Tests
|
||||||
|
|
4
.github/workflows/docs.yml
vendored
4
.github/workflows/docs.yml
vendored
|
@ -11,10 +11,10 @@ on:
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
settings_md:
|
settings_md:
|
||||||
runs-on: ubuntu-18.04
|
runs-on: ubuntu-latest
|
||||||
|
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v3
|
||||||
- name: Install dependencies
|
- name: Install dependencies
|
||||||
run: sudo apt-get update && sudo apt-get -y install python3-yaml
|
run: sudo apt-get update && sudo apt-get -y install python3-yaml
|
||||||
- name: Check that Settings.md is up to date
|
- name: Check that Settings.md is up to date
|
||||||
|
|
|
@ -2,7 +2,9 @@ FROM ubuntu:focal
|
||||||
|
|
||||||
ENV DEBIAN_FRONTEND noninteractive
|
ENV DEBIAN_FRONTEND noninteractive
|
||||||
|
|
||||||
RUN apt-get update && apt-get install -y git cmake make ruby gcc
|
RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip
|
||||||
|
|
||||||
|
RUN pip install pyyaml
|
||||||
|
|
||||||
RUN useradd inav
|
RUN useradd inav
|
||||||
|
|
||||||
|
|
3
cmake/docker_docs.sh
Normal file
3
cmake/docker_docs.sh
Normal file
|
@ -0,0 +1,3 @@
|
||||||
|
#!/bin/bash
|
||||||
|
cd /src/
|
||||||
|
python3 src/utils/update_cli_docs.py
|
|
@ -242,7 +242,7 @@ set vbat_min_cell_voltage = 250
|
||||||
|
|
||||||
#### Simple example with automatic profile switching
|
#### Simple example with automatic profile switching
|
||||||
|
|
||||||
In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the iNav defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD.
|
In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the INAV defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD.
|
||||||
|
|
||||||
```
|
```
|
||||||
feature BAT_PROF_AUTOSWITCH
|
feature BAT_PROF_AUTOSWITCH
|
||||||
|
@ -311,6 +311,25 @@ set battery_capacity_warning = 300
|
||||||
set battery_capacity_critical = 150
|
set battery_capacity_critical = 150
|
||||||
```
|
```
|
||||||
|
|
||||||
|
#### Change control profile based on battery profile
|
||||||
|
|
||||||
|
You can change the control profile, automatically, based on the battery profile. This allows for fine tuning of each power choice.
|
||||||
|
|
||||||
|
```
|
||||||
|
feature BAT_PROF_AUTOSWITCH
|
||||||
|
|
||||||
|
|
||||||
|
battery_profile 1
|
||||||
|
|
||||||
|
set bat_cells = 3
|
||||||
|
set controlrate_profile = 1
|
||||||
|
|
||||||
|
battery_profile 2
|
||||||
|
|
||||||
|
set bat_cells = 4
|
||||||
|
set controlrate_profile = 2
|
||||||
|
```
|
||||||
|
|
||||||
## Remaining flight time and flight distance estimation
|
## Remaining flight time and flight distance estimation
|
||||||
|
|
||||||
The estimated remaining flight time and flight distance estimations can be displayed on the OSD (for fixed wing only for the moment). They are calculated from the GPS distance from home, remaining battery capacity and average power draw. They are taking into account the requested altitude change and heading to home change after altitude change following the switch to RTH. They are also taking into account the estimated wind if `osd_estimations_wind_compensation` is set to `ON`. When the timer and distance indicator reach 0 they will blink and you need to go home in a straight line manually or by engaging RTH. You should be left with at least `rth_energy_margin`% of battery left when arriving home if the cruise speed and power are set correctly (see bellow).
|
The estimated remaining flight time and flight distance estimations can be displayed on the OSD (for fixed wing only for the moment). They are calculated from the GPS distance from home, remaining battery capacity and average power draw. They are taking into account the requested altitude change and heading to home change after altitude change following the switch to RTH. They are also taking into account the estimated wind if `osd_estimations_wind_compensation` is set to `ON`. When the timer and distance indicator reach 0 they will blink and you need to go home in a straight line manually or by engaging RTH. You should be left with at least `rth_energy_margin`% of battery left when arriving home if the cruise speed and power are set correctly (see bellow).
|
||||||
|
|
10
docs/Cli.md
10
docs/Cli.md
|
@ -57,6 +57,9 @@ To perform the restore simply paste the saved commands in the Configurator CLI t
|
||||||
|
|
||||||
After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be.
|
After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be.
|
||||||
|
|
||||||
|
## Flight Controller opereration while connected to the CLI
|
||||||
|
|
||||||
|
While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0 onwards).
|
||||||
|
|
||||||
## CLI Command Reference
|
## CLI Command Reference
|
||||||
|
|
||||||
|
@ -86,7 +89,6 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
|
||||||
| `gpspassthrough` | Passthrough gps to serial |
|
| `gpspassthrough` | Passthrough gps to serial |
|
||||||
| `gvar` | Configure global variables |
|
| `gvar` | Configure global variables |
|
||||||
| `help` | Displays CLI help and command parameters / options |
|
| `help` | Displays CLI help and command parameters / options |
|
||||||
| `imu2` | Secondary IMU |
|
|
||||||
| `led` | Configure leds |
|
| `led` | Configure leds |
|
||||||
| `logic` | Configure logic conditions |
|
| `logic` | Configure logic conditions |
|
||||||
| `map` | Configure rc channel order |
|
| `map` | Configure rc channel order |
|
||||||
|
@ -109,7 +111,7 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
|
||||||
| `servo` | Configure servos |
|
| `servo` | Configure servos |
|
||||||
| `set` | Change setting with name=value or blank or * for list |
|
| `set` | Change setting with name=value or blank or * for list |
|
||||||
| `smix` | Custom servo mixer |
|
| `smix` | Custom servo mixer |
|
||||||
| `status` | Show status |
|
| `status` | Show status. Error codes can be looked up [here](https://github.com/iNavFlight/inav/wiki/%22Something%22-is-disabled----Reasons) |
|
||||||
| `tasks` | Show task stats |
|
| `tasks` | Show task stats |
|
||||||
| `temp_sensor` | List or configure temperature sensor(s). See [temperature sensors documentation](Temperature-sensors.md) for more information. |
|
| `temp_sensor` | List or configure temperature sensor(s). See [temperature sensors documentation](Temperature-sensors.md) for more information. |
|
||||||
| `version` | Show version |
|
| `version` | Show version |
|
||||||
|
@ -152,8 +154,8 @@ A shorter form is also supported to enable and disable a single function using `
|
||||||
| DJI_HD_OSD | 21 | 2097152 |
|
| DJI_HD_OSD | 21 | 2097152 |
|
||||||
| SERVO_SERIAL | 22 | 4194304 |
|
| SERVO_SERIAL | 22 | 4194304 |
|
||||||
| TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 |
|
| TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 |
|
||||||
| IMU2 | 24 | 16777216 |
|
| UNUSED | 24 | 16777216 |
|
||||||
| HDZERO | 25 | 33554432 |
|
| MSP_DISPLAYPORT | 25 | 33554432 |
|
||||||
|
|
||||||
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.
|
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.
|
||||||
|
|
||||||
|
|
|
@ -4,7 +4,7 @@
|
||||||
|
|
||||||
When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. With multirotors, the motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended).
|
When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. With multirotors, the motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended).
|
||||||
|
|
||||||
Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in iNav 2.2)
|
Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in INAV 2.2)
|
||||||
|
|
||||||
**YAW STICK ARMING OVERRIDE:**
|
**YAW STICK ARMING OVERRIDE:**
|
||||||
Arming is disabled when Nav modes are configured and no GPS lock is available or if a WP mission is loaded but the first WP is farther than the `nav_wp_safe_distance` setting. This Arming block can be bypassed if need be by setting `nav_extra_arming_safety` to `ALLOW_BYPASS` and moving the Yaw stick to the high position when the Arm switch is used. This bypasses GPS Arm blocking pre INAV 4.0.0 and both GPS and "First WP too far" Arm blocking from INAV 4.0.0.
|
Arming is disabled when Nav modes are configured and no GPS lock is available or if a WP mission is loaded but the first WP is farther than the `nav_wp_safe_distance` setting. This Arming block can be bypassed if need be by setting `nav_extra_arming_safety` to `ALLOW_BYPASS` and moving the Yaw stick to the high position when the Arm switch is used. This bypasses GPS Arm blocking pre INAV 4.0.0 and both GPS and "First WP too far" Arm blocking from INAV 4.0.0.
|
||||||
|
@ -80,7 +80,7 @@ For tricopters, you may want to retain the ability to yaw while on the ground, s
|
||||||
|
|
||||||
## Throttle settings and their interaction
|
## Throttle settings and their interaction
|
||||||
|
|
||||||
*Terminology. After iNav 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.*
|
*Terminology. After INAV 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.*
|
||||||
|
|
||||||
`min_command` -
|
`min_command` -
|
||||||
With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety.
|
With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety.
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
# Display
|
# Display
|
||||||
|
|
||||||
INAV supports displays to provide information to you about your aircraft and iNav state.
|
INAV supports displays to provide information to you about your aircraft and INAV state.
|
||||||
|
|
||||||
When the aircraft is armed, an "Armed" message is displayed. When it is disarmed, a summary page is displayed. Page cycling has been removed and no other information is currently available
|
When the aircraft is armed, an "Armed" message is displayed. When it is disarmed, a summary page is displayed. Page cycling has been removed and no other information is currently available
|
||||||
|
|
||||||
|
|
|
@ -71,9 +71,9 @@ Example: 100 km/h = 100 * 27.77 = 2777 m/s
|
||||||
|
|
||||||
# Disabling GPS sensor from RC controller
|
# Disabling GPS sensor from RC controller
|
||||||
|
|
||||||

|

|
||||||
|
|
||||||
For testing purpoces, it is now possible to disable GPS sensor from RC controller:
|
For testing purpoces, it is possible to disable GPS sensor fix from RC controller in programming tab:
|
||||||
|
|
||||||
*GPS can be disabled only after 1) initial GPS fix is acquired 2) in ARMED mode.*
|
*GPS can be disabled only after 1) initial GPS fix is acquired 2) in ARMED mode.*
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,7 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co
|
||||||
## NAV POSHOLD mode - position hold
|
## NAV POSHOLD mode - position hold
|
||||||
|
|
||||||
Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
|
Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
|
||||||
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From inav 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
|
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
|
||||||
|
|
||||||
### CLI parameters affecting POSHOLD mode:
|
### CLI parameters affecting POSHOLD mode:
|
||||||
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
|
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
|
||||||
|
@ -59,11 +59,11 @@ NAV WP allows the craft to autonomously navigate a set route defined by waypoint
|
||||||
|
|
||||||
`wp load` - Load list of waypoints from EEPROM to FC.
|
`wp load` - Load list of waypoints from EEPROM to FC.
|
||||||
|
|
||||||
`wp <n> <action> <lat> <lon> <alt> <p1> <p2> <p3> <flag>` - Set parameters of waypoint with index `<n>`. Note that prior to inav 2.5, the `p2` and `p3` parameters were not required. From 2.5, inav will accept either version but always saves and lists the later full version.
|
`wp <n> <action> <lat> <lon> <alt> <p1> <p2> <p3> <flag>` - Set parameters of waypoint with index `<n>`. Note that prior to INAV 2.5, the `p2` and `p3` parameters were not required. From 2.5, INAV will accept either version but always saves and lists the later full version.
|
||||||
|
|
||||||
Parameters:
|
Parameters:
|
||||||
|
|
||||||
* `<action>` - The action to be taken at the WP. The following are enumerations are available in inav 2.6 and later:
|
* `<action>` - The action to be taken at the WP. The following are enumerations are available in INAV 2.6 and later:
|
||||||
* 0 - Unused / Unassigned
|
* 0 - Unused / Unassigned
|
||||||
* 1 - WAYPOINT
|
* 1 - WAYPOINT
|
||||||
* 3 - POSHOLD_TIME
|
* 3 - POSHOLD_TIME
|
||||||
|
@ -77,13 +77,24 @@ Parameters:
|
||||||
|
|
||||||
* `<lon>` - Longitude.
|
* `<lon>` - Longitude.
|
||||||
|
|
||||||
* `<alt>` - Altitude in cm.
|
* `<alt>` - Altitude in cm. See `p3` bit 0 for datum definition.
|
||||||
|
|
||||||
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI.
|
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI.
|
||||||
|
|
||||||
* `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
|
* `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
|
||||||
|
|
||||||
* `<p3>` - Reserved for future use. If `p2` is provided, then `p3` is also required.
|
* `<p3>` - A bitfield with four bits reserved for user specified actions. It is anticipated that these actions will be exposed through the logic conditions.
|
||||||
|
* Bit 0 - Altitude (`alt`) : Relative (to home altitude) (0) or Absolute (AMSL) (1).
|
||||||
|
* Bit 1 - WP Action 1
|
||||||
|
* Bit 2 - WP Action 2
|
||||||
|
* Bit 3 - WP Action 3
|
||||||
|
* Bit 4 - WP Action 4
|
||||||
|
* Bits 5 - 15 : undefined / reserved.
|
||||||
|
|
||||||
|
Note:
|
||||||
|
|
||||||
|
* If `p2` is specified, then `p3` is also required.
|
||||||
|
* `p3` is only defined for navigable WP types (WAYPOINT, POSHOLD_TIME, LAND). The affect of specifying a non-zero `p3` for other WP types is undefined.
|
||||||
|
|
||||||
* `<flag>` - Last waypoint must have `flag` set to 165 (0xA5).
|
* `<flag>` - Last waypoint must have `flag` set to 165 (0xA5).
|
||||||
|
|
||||||
|
@ -116,7 +127,8 @@ wp 59 0 0 0 0 0 0 0 0
|
||||||
|
|
||||||
Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.
|
Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.
|
||||||
|
|
||||||
**Multi-missions**\
|
## Multi-missions
|
||||||
|
|
||||||
Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command.
|
Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command.
|
||||||
|
|
||||||
E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0).
|
E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0).
|
||||||
|
@ -156,4 +168,4 @@ wp 11 0 0 0 0 0 0 0 0
|
||||||
wp 12 0 0 0 0 0 0 0 0
|
wp 12 0 0 0 0 0 0 0 0
|
||||||
...
|
...
|
||||||
wp 59 0 0 0 0 0 0 0 0
|
wp 59 0 0 0 0 0 0 0 0
|
||||||
```
|
```
|
||||||
|
|
|
@ -19,7 +19,7 @@ the actual one measured by the gyroscopes, and the controller tries to bring thi
|
||||||
Note that:
|
Note that:
|
||||||
|
|
||||||
* For fixed wing, a PIFF controller is used. Some documentation is available in the wiki and legacy release notes.
|
* For fixed wing, a PIFF controller is used. Some documentation is available in the wiki and legacy release notes.
|
||||||
* The iNav Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine.
|
* The INAV Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine.
|
||||||
|
|
||||||
## PIDs
|
## PIDs
|
||||||
|
|
||||||
|
|
|
@ -80,6 +80,12 @@ IPF can be edited using INAV Configurator user interface, of via CLI
|
||||||
| 44 | MAX | Finds the highest value of `Operand A` and `Operand B` |
|
| 44 | MAX | Finds the highest value of `Operand A` and `Operand B` |
|
||||||
| 45 | FLIGHT_AXIS_ANGLE_OVERRIDE | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees |
|
| 45 | FLIGHT_AXIS_ANGLE_OVERRIDE | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees |
|
||||||
| 46 | FLIGHT_AXIS_RATE_OVERRIDE | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second |
|
| 46 | FLIGHT_AXIS_RATE_OVERRIDE | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second |
|
||||||
|
| 47 | EDGE | `Operand A` is activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. |
|
||||||
|
| 48 | DELAY | This will return `true` when `Operand A` is true, and the delay time in `Operand B` [ms] has been exceeded. |
|
||||||
|
| 49 | TIMER | `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. |
|
||||||
|
| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater. |
|
||||||
|
| 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. |
|
||||||
|
|
||||||
### Operands
|
### Operands
|
||||||
|
|
||||||
| Operand Type | Name | Notes |
|
| Operand Type | Name | Notes |
|
||||||
|
|
|
@ -27,4 +27,4 @@ I2C solutions like `VL53L0X` or `INAV_I2C` can be connected to I2C port and used
|
||||||
|
|
||||||
#### Constraints
|
#### Constraints
|
||||||
|
|
||||||
iNav does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
|
INAV does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
|
|
@ -9,7 +9,7 @@ There are 2 basic types of receivers:
|
||||||
|
|
||||||
## PPM Receivers
|
## PPM Receivers
|
||||||
|
|
||||||
**Only supported in inav 3.x and below**
|
**Only supported in INAV 3.x and below**
|
||||||
|
|
||||||
PPM is sometimes known as PPM SUM or CPPM.
|
PPM is sometimes known as PPM SUM or CPPM.
|
||||||
|
|
||||||
|
@ -47,7 +47,7 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
|
||||||
|
|
||||||
#### Spektrum pesudo RSSI
|
#### Spektrum pesudo RSSI
|
||||||
|
|
||||||
As of iNav 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal iNav RSSI (0-1023 range). In order to use this feature, the following is necessary:
|
As of INAV 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal INAV RSSI (0-1023 range). In order to use this feature, the following is necessary:
|
||||||
|
|
||||||
* Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient.
|
* Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient.
|
||||||
* The CLI variable `rssi_channel` is set to channel 9:
|
* The CLI variable `rssi_channel` is set to channel 9:
|
||||||
|
@ -154,7 +154,7 @@ It is possible to use IBUS RX and IBUS telemetry on only one port of the hardwar
|
||||||
|
|
||||||
### SRXL2
|
### SRXL2
|
||||||
|
|
||||||
SRXL2 is a newer Spektrum protocol that provides a bidirectional link between the FC and the receiver, allowing the user to get FC telemetry data and basic settings on Spektrum Gen 2 airware TX. SRXL2 is supported in inav 2.6 and later. It offers improved performance and features compared to earlier Spektrum RX.
|
SRXL2 is a newer Spektrum protocol that provides a bidirectional link between the FC and the receiver, allowing the user to get FC telemetry data and basic settings on Spektrum Gen 2 airware TX. SRXL2 is supported in INAV 2.6 and later. It offers improved performance and features compared to earlier Spektrum RX.
|
||||||
|
|
||||||
#### Wiring
|
#### Wiring
|
||||||
|
|
||||||
|
@ -162,7 +162,7 @@ Signal pin on receiver (labeled "S") must be wired to a **UART TX** pin on the F
|
||||||
|
|
||||||
#### Configuration
|
#### Configuration
|
||||||
|
|
||||||
Selection of SXRL2 is provided in the inav 2.6 and later configurators. It is necessary to complete the configuration via the CLI; the following settings are recommended:
|
Selection of SXRL2 is provided in the INAV 2.6 and later configurators. It is necessary to complete the configuration via the CLI; the following settings are recommended:
|
||||||
|
|
||||||
```
|
```
|
||||||
feature TELEMETRY
|
feature TELEMETRY
|
||||||
|
|
|
@ -20,7 +20,7 @@ The safehome operating mode is set using ```safehome_usage_mode```. If ```OFF``
|
||||||
|
|
||||||
If you frequently use RTH to return back to the arming point, you may not want the aircraft to fly to the safehome. Let it do this at least once to confirm safehomes is working as expected. Afterward, `set safehome_usage_mode = RTH_FS` and the safehome will only be used for failsafe.
|
If you frequently use RTH to return back to the arming point, you may not want the aircraft to fly to the safehome. Let it do this at least once to confirm safehomes is working as expected. Afterward, `set safehome_usage_mode = RTH_FS` and the safehome will only be used for failsafe.
|
||||||
|
|
||||||
When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the iNav failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions.
|
When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the INAV failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions.
|
||||||
|
|
||||||
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.
|
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.
|
||||||
|
|
||||||
|
|
|
@ -9,7 +9,7 @@ As many can attest, multirotors and RC models in general can be very dangerous,
|
||||||
Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md)
|
Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md)
|
||||||
pages for further important information.
|
pages for further important information.
|
||||||
|
|
||||||
You are highly advised to use the Receiver tab in the CleanFlight Configurator, making sure your Rx channel
|
You are highly advised to use the Receiver tab in the INAV Configurator, making sure your Rx channel
|
||||||
values are centered at 1500 (1520 for Futaba RC) with minimum & maximums of 1000 and 2000 (respectively)
|
values are centered at 1500 (1520 for Futaba RC) with minimum & maximums of 1000 and 2000 (respectively)
|
||||||
are reached when controls are operated. Failure to configure these ranges properly can create
|
are reached when controls are operated. Failure to configure these ranges properly can create
|
||||||
problems, such as inability to arm (because you can't reach the endpoints) or immediate activation of
|
problems, such as inability to arm (because you can't reach the endpoints) or immediate activation of
|
||||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 10 KiB |
BIN
docs/Screenshots/programming_disable_gps_sensor_fix.png
Normal file
BIN
docs/Screenshots/programming_disable_gps_sensor_fix.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 15 KiB |
274
docs/Settings.md
274
docs/Settings.md
|
@ -338,7 +338,7 @@ Internal (configurator) hint. Should not be changed manually
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 0 | 0 | 4 |
|
| 0 | 0 | 99 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -902,13 +902,13 @@ What failsafe procedure to initiate in Stage 2 when craft is closer to home than
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### failsafe_mission
|
### failsafe_mission_delay
|
||||||
|
|
||||||
If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode
|
Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end.
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| ON | OFF | ON |
|
| 0 | -1 | 600 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1622,163 +1622,13 @@ Power draw at zero throttle used for remaining flight time/distance estimation i
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### imu2_align_pitch
|
|
||||||
|
|
||||||
Pitch alignment for Secondary IMU. 1/10 of a degree
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -1800 | 3600 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_align_roll
|
|
||||||
|
|
||||||
Roll alignment for Secondary IMU. 1/10 of a degree
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -1800 | 3600 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_align_yaw
|
|
||||||
|
|
||||||
Yaw alignment for Secondary IMU. 1/10 of a degree
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -1800 | 3600 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_acc_x
|
|
||||||
|
|
||||||
Secondary IMU ACC calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_acc_y
|
|
||||||
|
|
||||||
Secondary IMU ACC calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_acc_z
|
|
||||||
|
|
||||||
Secondary IMU ACC calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_mag_x
|
|
||||||
|
|
||||||
Secondary IMU MAG calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_mag_y
|
|
||||||
|
|
||||||
Secondary IMU MAG calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_gain_mag_z
|
|
||||||
|
|
||||||
Secondary IMU MAG calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_hardware
|
|
||||||
|
|
||||||
Selection of a Secondary IMU hardware type. NONE disables this functionality
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| NONE | | |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_radius_acc
|
|
||||||
|
|
||||||
Secondary IMU MAG calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_radius_mag
|
|
||||||
|
|
||||||
Secondary IMU MAG calibration data
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | -32768 | 32767 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_use_for_osd_ahi
|
|
||||||
|
|
||||||
If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| OFF | OFF | ON |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_use_for_osd_heading
|
|
||||||
|
|
||||||
If set to ON, Secondary IMU data will be used for Analog OSD heading
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| OFF | OFF | ON |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu2_use_for_stabilized
|
|
||||||
|
|
||||||
If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH)
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| OFF | OFF | ON |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### imu_acc_ignore_rate
|
### imu_acc_ignore_rate
|
||||||
|
|
||||||
Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes
|
Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 0 | 0 | 20 |
|
| 15 | 0 | 30 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1788,7 +1638,7 @@ Half-width of the interval to gradually reduce accelerometer weight. Centered at
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 0 | 0 | 5 |
|
| 5 | 0 | 10 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1808,7 +1658,7 @@ Inertial Measurement Unit KI Gain for compass measurements
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 0 | | 65535 |
|
| 50 | | 65535 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1818,7 +1668,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 1000 | | 65535 |
|
| 2000 | | 65535 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1828,13 +1678,33 @@ Inertial Measurement Unit KP Gain for compass measurements
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 5000 | | 65535 |
|
| 2000 | | 65535 |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### imu_gps_yaw_windcomp
|
||||||
|
|
||||||
|
Wind compensation in heading estimation from gps groundcourse(fixed wing only)
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| ON | OFF | ON |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### imu_inertia_comp_method
|
||||||
|
|
||||||
|
Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| VELNED | | |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### inav_allow_dead_reckoning
|
### inav_allow_dead_reckoning
|
||||||
|
|
||||||
Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation
|
Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
|
@ -1934,7 +1804,7 @@ _// TODO_
|
||||||
|
|
||||||
### inav_use_gps_velned
|
### inav_use_gps_velned
|
||||||
|
|
||||||
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.
|
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.
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
|
@ -2822,6 +2692,16 @@ Maximum climb/descent rate that UAV is allowed to reach during navigation modes.
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
### nav_auto_disarm_delay
|
||||||
|
|
||||||
|
Delay before craft disarms when `nav_disarm_on_landing` is set (ms)
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| 2000 | 100 | 10000 |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
### nav_auto_speed
|
### nav_auto_speed
|
||||||
|
|
||||||
Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]
|
Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]
|
||||||
|
@ -2834,7 +2714,7 @@ Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no speci
|
||||||
|
|
||||||
### nav_disarm_on_landing
|
### nav_disarm_on_landing
|
||||||
|
|
||||||
If set to ON, iNav disarms the FC after landing
|
If set to ON, INAV disarms the FC after landing
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
|
@ -2872,16 +2752,6 @@ Enable the possibility to manually increase the throttle in auto throttle contro
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### nav_fw_auto_disarm_delay
|
|
||||||
|
|
||||||
Delay before plane disarms when `nav_disarm_on_landing` is set (ms)
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 2000 | 100 | 10000 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### nav_fw_bank_angle
|
### nav_fw_bank_angle
|
||||||
|
|
||||||
Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll
|
Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll
|
||||||
|
@ -3352,6 +3222,16 @@ Deadband for heading trajectory PID controller. When heading error is below the
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
### nav_land_detect_sensitivity
|
||||||
|
|
||||||
|
Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases.
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| 5 | 1 | 15 |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
### nav_land_maxalt_vspd
|
### nav_land_maxalt_vspd
|
||||||
|
|
||||||
Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]
|
Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]
|
||||||
|
@ -3442,16 +3322,6 @@ Max allowed above the ground altitude for terrain following mode
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### nav_mc_auto_disarm_delay
|
|
||||||
|
|
||||||
Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (ms)
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 2000 | 100 | 10000 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### nav_mc_bank_angle
|
### nav_mc_bank_angle
|
||||||
|
|
||||||
Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude
|
Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude
|
||||||
|
@ -3942,6 +3812,16 @@ If set to ON, waypoints will be automatically loaded from EEPROM to the FC durin
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
### nav_wp_max_safe_distance
|
||||||
|
|
||||||
|
First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check.
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| 100 | 0 | 1500 |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
### nav_wp_mission_restart
|
### nav_wp_mission_restart
|
||||||
|
|
||||||
Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint.
|
Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint.
|
||||||
|
@ -3954,11 +3834,11 @@ Sets restart behaviour for a WP mission when interrupted mid mission. START from
|
||||||
|
|
||||||
### nav_wp_multi_mission_index
|
### nav_wp_multi_mission_index
|
||||||
|
|
||||||
Index of mission selected from multi mission WP entry loaded in flight controller. 1 is the first useable WP mission in the entry. Limited to a maximum of 9 missions. Set index to 0 to display current active WP count in OSD Mission field.
|
Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions.
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 1 | 0 | 9 |
|
| 1 | 1 | 9 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -3972,16 +3852,6 @@ Waypoint radius [cm]. Waypoint would be considered reached if machine is within
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### nav_wp_safe_distance
|
|
||||||
|
|
||||||
First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check.
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 10000 | | 65000 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### opflow_hardware
|
### opflow_hardware
|
||||||
|
|
||||||
Selection of OPFLOW hardware.
|
Selection of OPFLOW hardware.
|
||||||
|
@ -4042,6 +3912,16 @@ Max pitch, in degrees, for OSD artificial horizon
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
### osd_ahi_pitch_interval
|
||||||
|
|
||||||
|
Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD)
|
||||||
|
|
||||||
|
| Default | Min | Max |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| 0 | 0 | 30 |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
### osd_ahi_reverse_roll
|
### osd_ahi_reverse_roll
|
||||||
|
|
||||||
Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement.
|
Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement.
|
||||||
|
@ -4834,7 +4714,7 @@ IMPERIAL, METRIC, UK
|
||||||
|
|
||||||
### osd_video_system
|
### osd_video_system
|
||||||
|
|
||||||
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD`
|
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO` and 'DJIWTF'
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
|
@ -5944,7 +5824,7 @@ VTX RF power level to use. The exact number of mw depends on the VTX hardware.
|
||||||
|
|
||||||
### vtx_smartaudio_alternate_softserial_method
|
### vtx_smartaudio_alternate_softserial_method
|
||||||
|
|
||||||
Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier.
|
Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier.
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
|
|
|
@ -212,7 +212,7 @@ The INAV implementation of LTM implements the following frames:
|
||||||
* S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item suffixed '+' not implemented in INAV.
|
* S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item suffixed '+' not implemented in INAV.
|
||||||
* O-FRAME: Origin (home position, lat, long, altitude, fix)
|
* O-FRAME: Origin (home position, lat, long, altitude, fix)
|
||||||
|
|
||||||
In addition, in iNav:
|
In addition, in INAV:
|
||||||
|
|
||||||
* N-FRAME: Navigation information (GPS mode, Nav mode, Nav action, Waypoint number, Nav Error, Nav Flags).
|
* N-FRAME: Navigation information (GPS mode, Nav mode, Nav action, Waypoint number, Nav Error, Nav Flags).
|
||||||
* X-FRAME: Extra information. Currently HDOP is reported.
|
* X-FRAME: Extra information. Currently HDOP is reported.
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
## Overview
|
## Overview
|
||||||
|
|
||||||
iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card).
|
INAV (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card).
|
||||||
|
|
||||||
When MSC mode is used with **internal flash** there are a few differences compared to **SD card** as it's a virtual file system:
|
When MSC mode is used with **internal flash** there are a few differences compared to **SD card** as it's a virtual file system:
|
||||||
|
|
||||||
|
@ -62,7 +62,7 @@ $ md5sum /tmp/{msc,sdc}logs/LOG00035.TXT
|
||||||
7cd259777ba4f29ecbde2f76882b1840 /tmp/msclogs/LOG00035.TXT
|
7cd259777ba4f29ecbde2f76882b1840 /tmp/msclogs/LOG00035.TXT
|
||||||
7cd259777ba4f29ecbde2f76882b1840 /tmp/sdclogs/LOG00035.TXT
|
7cd259777ba4f29ecbde2f76882b1840 /tmp/sdclogs/LOG00035.TXT
|
||||||
```
|
```
|
||||||
You should also be able to run blackbox utilities (e.g. the iNav specific `blackbox_decode`) without errors on the files, e.g.
|
You should also be able to run blackbox utilities (e.g. the INAV specific `blackbox_decode`) without errors on the files, e.g.
|
||||||
|
|
||||||
```
|
```
|
||||||
$ blackbox_decode --stdout --merge-gps > /dev/null /tmp/msclogs/LOG00035.TXT
|
$ blackbox_decode --stdout --merge-gps > /dev/null /tmp/msclogs/LOG00035.TXT
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
# Wireless connections
|
# Wireless connections
|
||||||
|
|
||||||
From iNav 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP).
|
From INAV 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP).
|
||||||
|
|
||||||
## BLE
|
## BLE
|
||||||
|
|
||||||
|
@ -13,7 +13,7 @@ The following adapters are supported:
|
||||||
Flightcontrollers with BLE should also work, if you have an adapter/FC that doesn't work, open an issue here on Github and we will add it.
|
Flightcontrollers with BLE should also work, if you have an adapter/FC that doesn't work, open an issue here on Github and we will add it.
|
||||||
|
|
||||||
### Configuring the BLE modules
|
### Configuring the BLE modules
|
||||||
Activate MSP in iNav on a free UART port and set the Bluetooth module to the appropriate baud rate.
|
Activate MSP in INAV on a free UART port and set the Bluetooth module to the appropriate baud rate.
|
||||||
|
|
||||||
Example for a HM-10 module:
|
Example for a HM-10 module:
|
||||||
|
|
||||||
|
@ -22,7 +22,7 @@ Standard baud rate is 115200 baud, CR+LF
|
||||||
|
|
||||||
```
|
```
|
||||||
AT+BAUD4
|
AT+BAUD4
|
||||||
AT+NAMEiNav
|
AT+NAMEINAV
|
||||||
```
|
```
|
||||||
|
|
||||||
The baud rate values:
|
The baud rate values:
|
||||||
|
@ -46,8 +46,8 @@ Allows connections via Wifi.
|
||||||
|
|
||||||
Hardware:
|
Hardware:
|
||||||
- DIY, ESP8266 based:
|
- DIY, ESP8266 based:
|
||||||
This project can be used to make iNav Wifi enabled: https://github.com/Scavanger/MSPWifiBridge
|
This project can be used to make INAV Wifi enabled: https://github.com/Scavanger/MSPWifiBridge
|
||||||
A small ESP01S module should still fit anywhere.
|
A small ESP01S module should still fit anywhere.
|
||||||
|
|
||||||
- ExpressLRS Wifi:
|
- ExpressLRS Wifi:
|
||||||
Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in iNav.
|
Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in INAV.
|
||||||
|
|
16
docs/boards/Matek F722PX-WPX-HD.md
Normal file
16
docs/boards/Matek F722PX-WPX-HD.md
Normal file
|
@ -0,0 +1,16 @@
|
||||||
|
# Board - MATEKSYS F722-PX/WPX/HD
|
||||||
|
|
||||||
|
## Vendor Information / specification
|
||||||
|
http://www.mateksys.com/?portfolio=f722-px
|
||||||
|
http://www.mateksys.com/?portfolio=f722-wpx
|
||||||
|
http://www.mateksys.com/?portfolio=f722-hd
|
||||||
|
|
||||||
|
## Firmware
|
||||||
|
|
||||||
|
Three firmware variants are available.
|
||||||
|
|
||||||
|
* `inav_x.y.z_MATEKF722PX.hex`
|
||||||
|
* `inav_x.y.z_MATEKF722WPX.hex`
|
||||||
|
* `inav_x.y.z_MATEKF722PX_PINIO.hex`
|
||||||
|
|
||||||
|
The WPX vairant is for the MATEK F722-WPX wing flight controller. The PX variants are for the MATEK F722-PX and MATEK F722-HD flight controllers. The PINIO variant adds USER 3 PINIO as a replacement to UART 5 TX and USER 4 PINIO as a replacement to UART 5 RX.
|
|
@ -18,6 +18,11 @@
|
||||||
* SBUS pin is connected to UART2
|
* SBUS pin is connected to UART2
|
||||||
* SmartPort telemetry can be setup with `SoftwareSerial` feature turned on, SmartPort configured in SoftwareSerial1 and receiver connected to UART2 TX pad
|
* SmartPort telemetry can be setup with `SoftwareSerial` feature turned on, SmartPort configured in SoftwareSerial1 and receiver connected to UART2 TX pad
|
||||||
|
|
||||||
|
### Alternate targets
|
||||||
|
|
||||||
|
#### MATEKF045SE_PINIO
|
||||||
|
`MATEKF045SE_PINIO` replaces UART 6 with a PINIO interface. TX6 for PINIO USER 1 and RX6 for PINIO USER 2
|
||||||
|
|
||||||
## Where to buy:
|
## Where to buy:
|
||||||
|
|
||||||
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)
|
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING)
|
||||||
|
|
|
@ -44,7 +44,7 @@ Due to differences on the board (I2C - see below), there are two firmware varian
|
||||||
### I2C
|
### I2C
|
||||||
|
|
||||||
The F405-AIO, STD, CTR boards expose dedicated I2C pads.
|
The F405-AIO, STD, CTR boards expose dedicated I2C pads.
|
||||||
The F405-OSD does not expose I2C. For iNav there is a software I2C provision using the USART3 pads, as:
|
The F405-OSD does not expose I2C. For INAV there is a software I2C provision using the USART3 pads, as:
|
||||||
|
|
||||||
* SDA => RX3, SCL => TX3
|
* SDA => RX3, SCL => TX3
|
||||||
* Do not assign any serial function to USART3
|
* Do not assign any serial function to USART3
|
||||||
|
|
|
@ -71,7 +71,6 @@ More target options:
|
||||||
* Integrated current meter
|
* Integrated current meter
|
||||||
* Uses target **OMNIBUSF4PRO**
|
* Uses target **OMNIBUSF4PRO**
|
||||||
* Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_LEDSTRIPM5** target (LED strip on M5 pin instead of incorrectly wired dedicated connection)
|
* Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_LEDSTRIPM5** target (LED strip on M5 pin instead of incorrectly wired dedicated connection)
|
||||||
* If you want to power your servos from the servo rail you will have to bridge the 5v to another 5v pad from the board or take it from the esc
|
|
||||||
|
|
||||||
### Omnibus F4 Pro Corner
|
### Omnibus F4 Pro Corner
|
||||||
|
|
||||||
|
@ -195,9 +194,24 @@ SmartPort / FPort is possible without a hardware inverter by using one of the OM
|
||||||
* [Omnibus F4 Pro](https://inavflight.com/shop/p/OMNIBUSF4PRO)
|
* [Omnibus F4 Pro](https://inavflight.com/shop/p/OMNIBUSF4PRO)
|
||||||
* [Omnibus F4 Nano V6](https://inavflight.com/shop/s/bg/1320256)
|
* [Omnibus F4 Nano V6](https://inavflight.com/shop/s/bg/1320256)
|
||||||
|
|
||||||
|
## Powering servos and FC (fixed wing)
|
||||||
|
These boards have a set of diodes which allow you to power servos
|
||||||
|
and the flight controller in three different ways, without back EMF
|
||||||
|
from the servos damaging the electronics. Most commonly an ESC
|
||||||
|
connected to the servo rail provides 5V power for the servos.
|
||||||
|
|
||||||
|
If your opto-isolated ESC doesn't provide 5V and you have servos,
|
||||||
|
connect a 5 BEC to the servo rail (any of the servo outputs 1-4).
|
||||||
|
|
||||||
|
The BEC can also power the board electronics, through a protective diode.
|
||||||
|
|
||||||
|
Do NOT bridge any other 5V pad to the servo rail, or connect servos
|
||||||
|
to any other 5V pad on the board. The back EMF from a a servo can
|
||||||
|
destroy the chips on the board.
|
||||||
|
|
||||||
# Wiring diagrams for Omnibus F4 Pro
|
# Wiring diagrams for Omnibus F4 Pro
|
||||||
|
|
||||||
Following diagrams applies to _Pro_ version with integrated current meter and JST connectors only
|
Following diagrams apply to _Pro_ version with integrated current meter and JST connectors only
|
||||||
|
|
||||||
## Board layout
|
## Board layout
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,7 @@ Then follow this : https://pixhawk.org/dev/bootloader_update
|
||||||
|
|
||||||
### Interface and Ports
|
### Interface and Ports
|
||||||
|
|
||||||
Total UARTS Recognized by iNav -> 8
|
Total UARTS Recognized by INAV -> 8
|
||||||
|
|
||||||
#### USART1
|
#### USART1
|
||||||
* Location : Top
|
* Location : Top
|
||||||
|
|
3
docs/boards/SPEEDYBEEF405V3.md
Normal file
3
docs/boards/SPEEDYBEEF405V3.md
Normal file
|
@ -0,0 +1,3 @@
|
||||||
|
# SpeedyBee F405 V3
|
||||||
|
|
||||||
|
> Notice: At the moment, DSHOT is not supported on SpeedyBe F405 V3. Use Multishot instead
|
|
@ -1,11 +1,8 @@
|
||||||
# Blackbox logging internals
|
# Blackbox logging internals
|
||||||
|
|
||||||
The Blackbox is designed to record the raw internal state of the flight controller at near-maximum rate. By logging the
|
The Blackbox is designed to record the raw internal state of the flight controller at near-maximum rate. By logging the raw inputs and outputs of key flight systems, the Blackbox log aims to allow the offline bench-top simulation, debugging, and testing of flight control algorithms using data collected from real flights.
|
||||||
raw inputs and outputs of key flight systems, the Blackbox log aims to allow the offline bench-top simulation, debugging,
|
|
||||||
and testing of flight control algorithms using data collected from real flights.
|
|
||||||
|
|
||||||
A typical logging regime might capture 30 different state variables (for an average of 28 bytes per frame) at a sample
|
A typical logging regime might capture 30 different state variables (for an average of 28 bytes per frame) at a sample rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with a typical 8-N-1 serial encoding.
|
||||||
rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with a typical 8-N-1 serial encoding.
|
|
||||||
|
|
||||||
## References
|
## References
|
||||||
|
|
||||||
|
@ -14,163 +11,118 @@ Please refer to the source code to clarify anything this document leaves unclear
|
||||||
* INAV's Blackbox logger: [blackbox.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox.c),
|
* INAV's Blackbox logger: [blackbox.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox.c),
|
||||||
[blackbox_io.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_io.c),
|
[blackbox_io.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_io.c),
|
||||||
[blackbox_fielddefs.h](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_fielddefs.h)
|
[blackbox_fielddefs.h](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_fielddefs.h)
|
||||||
* [C implementation of the Blackbox log decoder](https://github.com/cleanflight/blackbox-tools/blob/master/src/parser.c)
|
* [C implementation of the Blackbox log decoder](https://github.com/iNavFlight/blackbox-tools)
|
||||||
* [JavaScript implementation of the Blackbox log decoder](https://github.com/cleanflight/blackbox-log-viewer/blob/master/js/flightlog_parser.js)
|
* [JavaScript implementation of the Blackbox log decoder](https://github.com/iNavFlight/blackbox-log-viewer)
|
||||||
|
|
||||||
## Logging cycle
|
## Logging cycle
|
||||||
Blackbox is designed for flight controllers that are based around the concept of a "main loop". During each main loop
|
|
||||||
iteration, the flight controller will read some state from sensors, run some flight control algorithms, and produce some
|
Blackbox is designed for flight controllers that are based around the concept of a "main loop". During each main loop iteration, the flight controller will read some state from sensors, run some flight control algorithms, and produce some outputs. For each of these loop iterations, a Blackbox "logging iteration" will be executed. This will read data that was stored during the execution of the main loop and log this data to an attached logging device. The data will include
|
||||||
outputs. For each of these loop iterations, a Blackbox "logging iteration" will be executed. This will read data that
|
algorithm inputs such as sensor and RC data, intermediate results from flight control algorithms, and algorithm outputs such as motor commands.
|
||||||
was stored during the execution of the main loop and log this data to an attached logging device. The data will include
|
|
||||||
algorithm inputs such as sensor and RC data, intermediate results from flight control algorithms, and algorithm outputs
|
|
||||||
such as motor commands.
|
|
||||||
|
|
||||||
## Log frame types
|
## Log frame types
|
||||||
Each event which is recorded to the log is packaged as a "log frame". Blackbox only uses a handful of different types of
|
|
||||||
log frames. Each frame type is identified by a single capital letter.
|
Each event which is recorded to the log is packaged as a "log frame". Blackbox only uses a handful of different types of log frames. Each frame type is identified by a single capital letter.
|
||||||
|
|
||||||
### Main frames: I, P
|
### Main frames: I, P
|
||||||
The most basic kind of logged frames are the "main frames". These record the primary state of the flight controller (RC
|
|
||||||
input, gyroscopes, flight control algorithm intermediates, motor outputs), and are logged during every logging
|
|
||||||
iteration.
|
|
||||||
|
|
||||||
Each main frame must contain at least two fields, "loopIteration" which records the index of the current main loop
|
The most basic kind of logged frames are the "main frames". These record the primary state of the flight controller (RC input, gyroscopes, flight control algorithm intermediates, motor outputs), and are logged during every logging iteration.
|
||||||
iteration (starting at zero for the first logged iteration), and "time" which records the timestamp of the beginning of
|
|
||||||
the main loop in microseconds (this needn't start at zero, on INAV it represents the system uptime).
|
|
||||||
|
|
||||||
There are two kinds of main frames, "I" and "P". "I", or "intra" frames are like video keyframes. They can be decoded
|
Each main frame must contain at least two fields, "loopIteration" which records the index of the current main loop iteration (starting at zero for the first logged iteration), and "time" which records the timestamp of the beginning of the main loop in microseconds (this needn't start at zero, on INAV it represents the system uptime).
|
||||||
without reference to any previous frame, so they allow log decoding to be resynchronized in the event of log damage. "P"
|
|
||||||
or "inter" frames use an encoding which references previously logged frames in order to reduce the required datarate.
|
There are two kinds of main frames, "I" and "P". "I", or "intra" frames are like video keyframes. They can be decoded without reference to any previous frame, so they allow log decoding to be resynchronized in the event of log damage. "P" or "inter" frames use an encoding which references previously logged frames in order to reduce the required datarate. When one interframe fails to decode, all following interframes will be undecodable up until the next intraframe.
|
||||||
When one interframe fails to decode, all following interframes will be undecodable up until the next intraframe.
|
|
||||||
|
|
||||||
### GPS frames: G, H
|
### GPS frames: G, H
|
||||||
Because the GPS is updated so infrequently, GPS data is logged in its own dedicated frames. These are recorded whenever
|
|
||||||
the GPS data changes (not necessarily alongside every main frame). Like the main frames, the GPS frames have their own
|
|
||||||
intra/inter encoding system.
|
|
||||||
|
|
||||||
The "H" or "home" frame records the lat/lon of a reference point. The "G" or "GPS" frame records the current state of
|
Because the GPS is updated so infrequently, GPS data is logged in its own dedicated frames. These are recorded whenever the GPS data changes (not necessarily alongside every main frame). Like the main frames, the GPS frames have their own intra/inter encoding system.
|
||||||
the GPS system (current position, altitude etc.) based on the reference point. The reference point can be updated
|
|
||||||
(infrequently) during the flight, and is logged whenever it changes.
|
|
||||||
|
|
||||||
To allow "G" frames to continue be decoded in the event that an "H" update is dropped from the log, the "H" frame is
|
The "H" or "home" frame records the lat/lon of a reference point. The "G" or "GPS" frame records the current state of the GPS system (current position, altitude etc.) based on the reference point. The reference point can be updated (infrequently) during the flight, and is logged whenever it changes.
|
||||||
logged periodically even if it has not changed (say, every 10 seconds). This caps the duration of unreadble "G" frames
|
|
||||||
that will result from a single missed "H" change.
|
To allow "G" frames to continue be decoded in the event that an "H" update is dropped from the log, the "H" frame is logged periodically even if it has not changed (say, every 10 seconds). This caps the duration of unreadble "G" frames that will result from a single missed "H" change.
|
||||||
|
|
||||||
### Slow frames: S
|
### Slow frames: S
|
||||||
Some flight controller state is updated very infrequently (on the order of once or twice a minute). Logging the fact
|
|
||||||
that this data had not been updated during every single logging iteration would be a waste of bandwidth, so these frames
|
|
||||||
are only logged when the "slow" state actually changes.
|
|
||||||
|
|
||||||
All Slow frames are logged as intraframes. An interframe encoding scheme can't be used for Slow frames, because one
|
Some flight controller state is updated very infrequently (on the order of once or twice a minute). Logging the fact that this data had not been updated during every single logging iteration would be a waste of bandwidth, so these frames are only logged when the "slow" state actually changes.
|
||||||
damaged frame causes all subsequent interframes to be undecodable. Because Slow frames are written so infrequently, one
|
|
||||||
missing Slow frame could invalidate minutes worth of Slow state.
|
|
||||||
|
|
||||||
On INAV, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe
|
All Slow frames are logged as intraframes. An interframe encoding scheme can't be used for Slow frames, because one damaged frame causes all subsequent interframes to be undecodable. Because Slow frames are written so infrequently, one missing Slow frame could invalidate minutes worth of Slow state.
|
||||||
state.
|
|
||||||
|
On INAV, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe state.
|
||||||
|
|
||||||
### Event frames: E
|
### Event frames: E
|
||||||
Some flight controller data is updated so infrequently or exists so transiently that we do not log it as a flight
|
|
||||||
controller "state". Instead, we log it as a state *transition* . This data is logged in "E" or "event" frames. Each event
|
Some flight controller data is updated so infrequently or exists so transiently that we do not log it as a flight controller "state". Instead, we log it as a state *transition* . This data is logged in "E" or "event" frames. Each event frame payload begins with a single byte "event type" field. The format of the rest of the payload is not encoded in the
|
||||||
frame payload begins with a single byte "event type" field. The format of the rest of the payload is not encoded in the
|
|
||||||
flight log, so its interpretation is left up to an agreement of the writer and the decoder.
|
flight log, so its interpretation is left up to an agreement of the writer and the decoder.
|
||||||
|
|
||||||
For example, one event that INAV logs is that the user has adjusted a system setting (such as a PID setting)
|
For example, one event that INAV logs is that the user has adjusted a system setting (such as a PID setting) using INAV's inflight adjustments feature. The event payload notes which setting was adjusted and the new value for the setting.
|
||||||
using INAV's inflight adjustments feature. The event payload notes which setting was adjusted and the new value
|
|
||||||
for the setting.
|
|
||||||
|
|
||||||
Because these setting updates are so rare, it would be wasteful to treat the settings as "state" and log the fact that
|
Because these setting updates are so rare, it would be wasteful to treat the settings as "state" and log the fact that the setting had not been changed during every logging iteration. It would be infeasible to periodically log the system settings using an intra/interframe scheme, because the intraframes would be so large. Instead we only log the transitions as events, accept the small probability that any one of those events will be damaged/absent in the log, and leave it up to log readers to decide the extent to which they are willing to assume that the state of the setting between successfully-decoded transition events was truly unchanged.
|
||||||
the setting had not been changed during every logging iteration. It would be infeasible to periodically log the system
|
|
||||||
settings using an intra/interframe scheme, because the intraframes would be so large. Instead we only log the
|
|
||||||
transitions as events, accept the small probability that any one of those events will be damaged/absent in the log, and
|
|
||||||
leave it up to log readers to decide the extent to which they are willing to assume that the state of the setting
|
|
||||||
between successfully-decoded transition events was truly unchanged.
|
|
||||||
|
|
||||||
## Log field format
|
## Log field format
|
||||||
|
|
||||||
For every field in a given frame type, there is an associated name, predictor, and encoding.
|
For every field in a given frame type, there is an associated name, predictor, and encoding.
|
||||||
|
|
||||||
When a field is written, the chosen predictor is computed for the field, then this predictor value is subtracted from
|
When a field is written, the chosen predictor is computed for the field, then this predictor value is subtracted from the raw field value. Finally, the encoder is used to transform the value into bytes to be written to the logging device.
|
||||||
the raw field value. Finally, the encoder is used to transform the value into bytes to be written to the logging device.
|
|
||||||
|
|
||||||
### Field predictors
|
### Field predictors
|
||||||
The job of the predictor is to bring the value to be encoded as close to zero as possible. The predictor may be based
|
|
||||||
on the values seen for the field in a previous frame, or some other value such as a fixed value or a value recorded in
|
The job of the predictor is to bring the value to be encoded as close to zero as possible. The predictor may be based on the values seen for the field in a previous frame, or some other value such as a fixed value or a value recorded in the log headers. For example, the battery voltage values in "I" intraframes in INAV use a reference voltage that is logged as part of the headers as a predictor. This assumes that battery voltages will be broadly similar to the initial pack voltage of the flight (e.g. 4S battery voltages are likely to lie within a small range for the whole flight). In "P" interframes, the battery voltage will instead use the previously-logged voltage as a predictor, because the correlation between successive voltage readings is high.
|
||||||
the log headers. For example, the battery voltage values in "I" intraframes in INAV use a reference voltage that
|
|
||||||
is logged as part of the headers as a predictor. This assumes that battery voltages will be broadly similar to the
|
|
||||||
initial pack voltage of the flight (e.g. 4S battery voltages are likely to lie within a small range for the whole
|
|
||||||
flight). In "P" interframes, the battery voltage will instead use the previously-logged voltage as a predictor, because
|
|
||||||
the correlation between successive voltage readings is high.
|
|
||||||
|
|
||||||
These predictors are presently available:
|
These predictors are presently available:
|
||||||
|
|
||||||
#### Predict zero (0)
|
#### Predict zero (0)
|
||||||
This predictor is the null-predictor which doesn't modify the field value at all. It is a common choice for fields
|
|
||||||
which are already close to zero, or where no better history is available (e.g. in intraframes which may not rely on the
|
This predictor is the null-predictor which doesn't modify the field value at all. It is a common choice for fields which are already close to zero, or where no better history is available (e.g. in intraframes which may not rely on the previous value of fields).
|
||||||
previous value of fields).
|
|
||||||
|
|
||||||
#### Predict last value (1)
|
#### Predict last value (1)
|
||||||
This is the most common predictor in interframes. The last-logged value of the field will be used as the predictor, and
|
|
||||||
subtracted from the raw field value. For fields which don't change very often, this will make their encoded value be
|
This is the most common predictor in interframes. The last-logged value of the field will be used as the predictor, and subtracted from the raw field value. For fields which don't change very often, this will make their encoded value be normally zero. Most fields have some time-correlation, so this predictor should reduce the magnitude of all but the noisiest fields.
|
||||||
normally zero. Most fields have some time-correlation, so this predictor should reduce the magnitude of all but the
|
|
||||||
noisiest fields.
|
|
||||||
|
|
||||||
#### Predict straight line (2)
|
#### Predict straight line (2)
|
||||||
This predictor assumes that the slope between the current measurement and the previous one will be similar to the
|
|
||||||
slope between the previous measurement and the one before that. This is common for fields which increase at a steady rate,
|
This predictor assumes that the slope between the current measurement and the previous one will be similar to the slope between the previous measurement and the one before that. This is common for fields which increase at a steady rate, such as the "time" field. The predictor is `history_age_2 - 2 * history_age_1`.
|
||||||
such as the "time" field. The predictor is `history_age_2 - 2 * history_age_1`.
|
|
||||||
|
|
||||||
#### Predict average 2 (3)
|
#### Predict average 2 (3)
|
||||||
This predictor is the average of the two previously logged values of the field (i.e. `(history_age_1 + history_age_2) / 2`
|
|
||||||
). It is used when there is significant random noise involved in the field, which means that the average of the recent
|
This predictor is the average of the two previously logged values of the field (i.e. `(history_age_1 + history_age_2) / 2` ). It is used when there is significant random noise involved in the field, which means that the average of the recent history is a better predictor of the next value than the previous value on its own would be (for example, in gyroscope or motor measurements).
|
||||||
history is a better predictor of the next value than the previous value on its own would be (for example, in gyroscope
|
|
||||||
or motor measurements).
|
|
||||||
|
|
||||||
#### Predict minthrottle (4)
|
#### Predict minthrottle (4)
|
||||||
This predictor subtracts the value of "minthrottle" which is included in the log header. In INAV, motors always
|
|
||||||
lie in the range of `[minthrottle ... maxthrottle]` when the craft is armed, so this predictor is used for the first
|
This predictor subtracts the value of "minthrottle" which is included in the log header. In INAV, motors always lie in the range of `[minthrottle ... maxthrottle]` when the craft is armed, so this predictor is used for the first motor value in intraframes.
|
||||||
motor value in intraframes.
|
|
||||||
|
|
||||||
#### Predict motor[0] (5)
|
#### Predict motor[0] (5)
|
||||||
This predictor is set to the value of `motor[0]` which was decoded earlier within the current frame. It is used in
|
|
||||||
intraframes for every motor after the first one, because the motor commands typically lie in a tight grouping.
|
This predictor is set to the value of `motor[0]` which was decoded earlier within the current frame. It is used in intraframes for every motor after the first one, because the motor commands typically lie in a tight grouping.
|
||||||
|
|
||||||
#### Predict increment (6)
|
#### Predict increment (6)
|
||||||
This predictor assumes that the field will be incremented by 1 unit for every main loop iteration. This is used to
|
|
||||||
predict the `loopIteration` field, which increases by 1 for every loop iteration.
|
This predictor assumes that the field will be incremented by 1 unit for every main loop iteration. This is used to predict the `loopIteration` field, which increases by 1 for every loop iteration.
|
||||||
|
|
||||||
#### Predict home-coord (7)
|
#### Predict home-coord (7)
|
||||||
This predictor is set to the corresponding latitude or longitude field from the GPS home coordinate (which was logged in
|
|
||||||
a preceding "H" frame). If no preceding "H" frame exists, the value is marked as invalid.
|
This predictor is set to the corresponding latitude or longitude field from the GPS home coordinate (which was logged in a preceding "H" frame). If no preceding "H" frame exists, the value is marked as invalid.
|
||||||
|
|
||||||
#### Predict 1500 (8)
|
#### Predict 1500 (8)
|
||||||
This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these
|
|
||||||
typically lie close to the midpoint of 1500us.
|
This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these typically lie close to the midpoint of 1500us.
|
||||||
|
|
||||||
#### Predict vbatref (9)
|
#### Predict vbatref (9)
|
||||||
This predictor is set to the "vbatref" field written in the log header. It is used when logging intraframe battery
|
|
||||||
voltages in INAV, since these are expected to be broadly similar to the first battery voltage seen during
|
This predictor is set to the "vbatref" field written in the log header. It is used when logging intraframe battery voltages in INAV, since these are expected to be broadly similar to the first battery voltage seen during
|
||||||
arming.
|
arming.
|
||||||
|
|
||||||
#### Predict last main-frame time (10)
|
#### Predict last main-frame time (10)
|
||||||
This predictor is set to the last logged `time` field from the main frame. This is used when predicting timestamps of
|
|
||||||
non-main frames (e.g. that might be logging the timing of an event that happened during the main loop cycle, like a GPS
|
This predictor is set to the last logged `time` field from the main frame. This is used when predicting timestamps of non-main frames (e.g. that might be logging the timing of an event that happened during the main loop cycle, like a GPS
|
||||||
reading).
|
reading).
|
||||||
|
|
||||||
### Field encoders
|
### Field encoders
|
||||||
The field encoder's job is to use fewer bits to represent values which are closer to zero than for values that are
|
|
||||||
further from zero. Blackbox supports a range of different encoders, which should be chosen on a per-field basis in order
|
The field encoder's job is to use fewer bits to represent values which are closer to zero than for values that are further from zero. Blackbox supports a range of different encoders, which should be chosen on a per-field basis in order to minimize the encoded data size. The choice of best encoder is based on the probability distribution of the values which are to be encoded. For example, if a field is almost always zero, then an encoding should be chosen for it which can encode that case into a very small number of bits, such as one. Conversely, if a field is normally 8-16 bits large, it would be wasteful to use an encoder which provided a special short encoded representation for zero values, because this will increase the encoded length of larger values.
|
||||||
to minimize the encoded data size. The choice of best encoder is based on the probability distribution of the values
|
|
||||||
which are to be encoded. For example, if a field is almost always zero, then an encoding should be chosen for it which
|
|
||||||
can encode that case into a very small number of bits, such as one. Conversely, if a field is normally 8-16 bits large,
|
|
||||||
it would be wasteful to use an encoder which provided a special short encoded representation for zero values, because
|
|
||||||
this will increase the encoded length of larger values.
|
|
||||||
|
|
||||||
These encoders are presently available:
|
These encoders are presently available:
|
||||||
|
|
||||||
#### Unsigned variable byte (1)
|
#### Unsigned variable byte (1)
|
||||||
This is the most straightforward encoding. This encoding uses the lower 7 bits of an encoded byte to store the lower 7
|
|
||||||
bits of the field's value. The high bit of that encoded byte is set to one if more than 7 bits are required to store the
|
This is the most straightforward encoding. This encoding uses the lower 7 bits of an encoded byte to store the lower 7 bits of the field's value. The high bit of that encoded byte is set to one if more than 7 bits are required to store the value. If the value did exceed 7 bits, the lower 7 bits of the value (which were written to the log) are removed from the value (by right shift), and the encoding process begins again with the new value.
|
||||||
value. If the value did exceed 7 bits, the lower 7 bits of the value (which were written to the log) are removed from
|
|
||||||
the value (by right shift), and the encoding process begins again with the new value.
|
|
||||||
|
|
||||||
This can be represented by the following algorithm:
|
This can be represented by the following algorithm:
|
||||||
|
|
||||||
|
@ -194,17 +146,14 @@ Here are some example values encoded using variable-byte encoding:
|
||||||
| 23456 | 0xA0 0xB7 0x01 |
|
| 23456 | 0xA0 0xB7 0x01 |
|
||||||
|
|
||||||
#### Signed variable byte (0)
|
#### Signed variable byte (0)
|
||||||
This encoding applies a pre-processing step to fold negative values into positive ones, then the resulting unsigned
|
|
||||||
number is encoded using unsigned variable byte encoding. The folding is accomplished by "ZigZag" encoding, which is
|
This encoding applies a pre-processing step to fold negative values into positive ones, then the resulting unsigned number is encoded using unsigned variable byte encoding. The folding is accomplished by "ZigZag" encoding, which is represented by:
|
||||||
represented by:
|
|
||||||
|
|
||||||
```c
|
```c
|
||||||
unsigned32 = (signed32 << 1) ^ (signed32 >> 31)
|
unsigned32 = (signed32 << 1) ^ (signed32 >> 31)
|
||||||
```
|
```
|
||||||
|
|
||||||
ZigZag encoding is preferred against simply casting the signed integer to unsigned, because casting would cause small
|
ZigZag encoding is preferred against simply casting the signed integer to unsigned, because casting would cause small negative quantities to appear to be very large unsigned integers, causing the encoded length to be similarly large. ZigZag encoding ensures that values near zero are still near zero after encoding.
|
||||||
negative quantities to appear to be very large unsigned integers, causing the encoded length to be similarly large.
|
|
||||||
ZigZag encoding ensures that values near zero are still near zero after encoding.
|
|
||||||
|
|
||||||
Here are some example integers encoded using ZigZag encoding:
|
Here are some example integers encoded using ZigZag encoding:
|
||||||
|
|
||||||
|
@ -218,26 +167,18 @@ Here are some example integers encoded using ZigZag encoding:
|
||||||
| -2147483648 | 4294967295 |
|
| -2147483648 | 4294967295 |
|
||||||
|
|
||||||
#### Neg 14-bit (3)
|
#### Neg 14-bit (3)
|
||||||
The value is negated, treated as an unsigned 14 bit integer, then encoded using unsigned variable byte encoding. This
|
|
||||||
bizarre encoding is used in INAV for battery pack voltages. This is because battery voltages are measured using a
|
|
||||||
14-bit ADC, with a predictor which is set to the battery voltage during arming, which is expected to be higher than any
|
|
||||||
voltage experienced during flight. After the predictor is subtracted, the battery voltage will almost certainly be below
|
|
||||||
zero.
|
|
||||||
|
|
||||||
This results in small encoded values when the voltage is closely below the initial one, at the expense of very large
|
The value is negated, treated as an unsigned 14 bit integer, then encoded using unsigned variable byte encoding. This bizarre encoding is used in INAV for battery pack voltages. This is because battery voltages are measured using a 14-bit ADC, with a predictor which is set to the battery voltage during arming, which is expected to be higher than any voltage experienced during flight. After the predictor is subtracted, the battery voltage will almost certainly be below zero.
|
||||||
encoded values if the voltage rises higher than the initial one.
|
|
||||||
|
This results in small encoded values when the voltage is closely below the initial one, at the expense of very large encoded values if the voltage rises higher than the initial one.
|
||||||
|
|
||||||
#### Elias delta unsigned 32-bit (4)
|
#### Elias delta unsigned 32-bit (4)
|
||||||
Because this encoding produces a bitstream, this is the only encoding for which the encoded value might not be a whole
|
|
||||||
number of bytes. If the bitstream isn't aligned on a byte boundary by the time the next non-Elias Delta field arrives,
|
|
||||||
or the end of the frame is reached, the final byte is padded with zeros byte-align the stream. This encoding requires
|
|
||||||
more CPU time than the other encodings because of the bit juggling involved in writing the bitstream.
|
|
||||||
|
|
||||||
When this encoder is chosen to encode all of the values in INAV interframes, it saves about 10% bandwidth
|
Because this encoding produces a bitstream, this is the only encoding for which the encoded value might not be a whole number of bytes. If the bitstream isn't aligned on a byte boundary by the time the next non-Elias Delta field arrives, or the end of the frame is reached, the final byte is padded with zeros byte-align the stream. This encoding requires more CPU time than the other encodings because of the bit juggling involved in writing the bitstream.
|
||||||
compared to using a mixture of the other encodings, but uses too much CPU time to be practical.
|
|
||||||
|
|
||||||
[The basic encoding algorithm is defined on Wikipedia](https://en.wikipedia.org/wiki/Elias_delta_coding). Given these
|
When this encoder is chosen to encode all of the values in INAV interframes, it saves about 10% bandwidth compared to using a mixture of the other encodings, but uses too much CPU time to be practical.
|
||||||
utility functions:
|
|
||||||
|
[The basic encoding algorithm is defined on Wikipedia](https://en.wikipedia.org/wiki/Elias_delta_coding). Given these utility functions:
|
||||||
|
|
||||||
```c
|
```c
|
||||||
/* Write `bitCount` bits from the least-significant end of the `bits` integer to the bitstream. The most-significant bit
|
/* Write `bitCount` bits from the least-significant end of the `bits` integer to the bitstream. The most-significant bit
|
||||||
|
@ -318,23 +259,17 @@ Here are some reference encoded bit patterns produced by writeU32EliasDelta:
|
||||||
| 4294967294 | 0000010000011111111111111111111111111111110 |
|
| 4294967294 | 0000010000011111111111111111111111111111110 |
|
||||||
| 4294967295 | 0000010000011111111111111111111111111111111 |
|
| 4294967295 | 0000010000011111111111111111111111111111111 |
|
||||||
|
|
||||||
Note that the very common value of zero encodes to a single bit, medium-sized values like 225 encode to 14 bits (an
|
Note that the very common value of zero encodes to a single bit, medium-sized values like 225 encode to 14 bits (an overhead of 4 bits over writing a plain 8 bit value), and typical 32-bit values like 4294967293 encode into 42 bits, an overhead of 10 bits.
|
||||||
overhead of 4 bits over writing a plain 8 bit value), and typical 32-bit values like 4294967293 encode into 42 bits, an
|
|
||||||
overhead of 10 bits.
|
|
||||||
|
|
||||||
#### Elias delta signed 32-bit (5)
|
#### Elias delta signed 32-bit (5)
|
||||||
|
|
||||||
The value is first converted to unsigned using ZigZag encoding, then unsigned Elias-delta encoding is applied.
|
The value is first converted to unsigned using ZigZag encoding, then unsigned Elias-delta encoding is applied.
|
||||||
|
|
||||||
#### TAG8_8SVB (6)
|
#### TAG8_8SVB (6)
|
||||||
First, an 8-bit (one byte) header is written. This header has its bits set to zero when the corresponding field (from a
|
|
||||||
maximum of 8 fields) is set to zero, otherwise the bit is set to one. The least-signficant bit in the header corresponds
|
|
||||||
to the first field to be written. This header is followed by the values of only the fields which are non-zero, written
|
|
||||||
using signed variable byte encoding.
|
|
||||||
|
|
||||||
This encoding is preferred for groups of fields in interframes which are infrequently updated by the flight controller.
|
First, an 8-bit (one byte) header is written. This header has its bits set to zero when the corresponding field (from a maximum of 8 fields) is set to zero, otherwise the bit is set to one. The least-signficant bit in the header corresponds to the first field to be written. This header is followed by the values of only the fields which are non-zero, written using signed variable byte encoding.
|
||||||
This will mean that their predictions are usually perfect, and so the value to be encoded for each field will normally
|
|
||||||
be zero. This is common for values like RC inputs and barometer readings, which are updated in only a fraction of main
|
This encoding is preferred for groups of fields in interframes which are infrequently updated by the flight controller. This will mean that their predictions are usually perfect, and so the value to be encoded for each field will normally be zero. This is common for values like RC inputs and barometer readings, which are updated in only a fraction of main loop iterations.
|
||||||
loop iterations.
|
|
||||||
|
|
||||||
For example, given these field values to encode:
|
For example, given these field values to encode:
|
||||||
|
|
||||||
|
@ -349,8 +284,8 @@ This would be encoded:
|
||||||
```
|
```
|
||||||
|
|
||||||
#### TAG2_3S32 (7)
|
#### TAG2_3S32 (7)
|
||||||
A 2-bit header is written, followed by 3 signed field values of up to 32 bits each. The header value is based on the
|
|
||||||
maximum size in bits of the three values to be encoded as follows:
|
A 2-bit header is written, followed by 3 signed field values of up to 32 bits each. The header value is based on the maximum size in bits of the three values to be encoded as follows:
|
||||||
|
|
||||||
| Header value | Maximum field value size | Field range |
|
| Header value | Maximum field value size | Field range |
|
||||||
| ------------ | ------------------------ | -------------------------- |
|
| ------------ | ------------------------ | -------------------------- |
|
||||||
|
@ -359,9 +294,7 @@ maximum size in bits of the three values to be encoded as follows:
|
||||||
| 2 | 6 bits | [-32...31] |
|
| 2 | 6 bits | [-32...31] |
|
||||||
| 3 | Up to 32 bits | [-2147483648...2147483647] |
|
| 3 | Up to 32 bits | [-2147483648...2147483647] |
|
||||||
|
|
||||||
If any of the three values requires more than 6 bits to encode, a second, 6-bit header value is written in the lower
|
If any of the three values requires more than 6 bits to encode, a second, 6-bit header value is written in the lower bits of the initial header byte. This second header has 2 bits for each of the encoded values which represents how many bytes are required to encode that value. The least-significant bits of the header represent the first field which is
|
||||||
bits of the initial header byte. This second header has 2 bits for each of the encoded values which represents how many
|
|
||||||
bytes are required to encode that value. The least-significant bits of the header represent the first field which is
|
|
||||||
encoded. The values for each possibility are as follows:
|
encoded. The values for each possibility are as follows:
|
||||||
|
|
||||||
| Header value | Field size | Field range |
|
| Header value | Field size | Field range |
|
||||||
|
@ -371,12 +304,9 @@ encoded. The values for each possibility are as follows:
|
||||||
| 2 | 3 bytes | [-8388608...8388607] |
|
| 2 | 3 bytes | [-8388608...8388607] |
|
||||||
| 3 | 4 bytes | [-2147483648...2147483647] |
|
| 3 | 4 bytes | [-2147483648...2147483647] |
|
||||||
|
|
||||||
This header is followed by the actual field values in order, written least-significant byte first, using the byte
|
This header is followed by the actual field values in order, written least-significant byte first, using the byte lengths specified in the header.
|
||||||
lengths specified in the header.
|
|
||||||
|
|
||||||
So bringing it all together, these encoded bit patterns are possible, where "0" and "1" mean bits fixed to be those
|
So bringing it all together, these encoded bit patterns are possible, where "0" and "1" mean bits fixed to be those values, "A", "B", and "C" represent the first, second and third fields, and "s" represents the bits of the secondary header in the case that any field is larger than 6 bits:
|
||||||
values, "A", "B", and "C" represent the first, second and third fields, and "s" represents the bits of the secondary
|
|
||||||
header in the case that any field is larger than 6 bits:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
00AA BBCC,
|
00AA BBCC,
|
||||||
|
@ -385,13 +315,11 @@ header in the case that any field is larger than 6 bits:
|
||||||
11ss ssss (followed by fields of byte lengths specified in the "s" header)
|
11ss ssss (followed by fields of byte lengths specified in the "s" header)
|
||||||
```
|
```
|
||||||
|
|
||||||
This encoding is useful for fields like 3-axis gyroscopes, which are frequently small and typically have similar
|
This encoding is useful for fields like 3-axis gyroscopes, which are frequently small and typically have similar magnitudes.
|
||||||
magnitudes.
|
|
||||||
|
|
||||||
#### TAG8_4S16 (8)
|
#### TAG8_4S16 (8)
|
||||||
An 8-bit header is written, followed by 4 signed field values of up to 16 bits each. The 8-bit header value has 2 bits
|
|
||||||
for each of the encoded fields (the least-significant bits represent the first field) which represent the
|
An 8-bit header is written, followed by 4 signed field values of up to 16 bits each. The 8-bit header value has 2 bits for each of the encoded fields (the least-significant bits represent the first field) which represent the number of bits required to encode that field as follows:
|
||||||
number of bits required to encode that field as follows:
|
|
||||||
|
|
||||||
| Header value | Field value size | Field range |
|
| Header value | Field value size | Field range |
|
||||||
| ------------ | ---------------- | ---------------- |
|
| ------------ | ---------------- | ---------------- |
|
||||||
|
@ -400,9 +328,7 @@ number of bits required to encode that field as follows:
|
||||||
| 2 | 8 bits | [-128...127] |
|
| 2 | 8 bits | [-128...127] |
|
||||||
| 3 | 16 bits | [-32768...32767] |
|
| 3 | 16 bits | [-32768...32767] |
|
||||||
|
|
||||||
This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the
|
This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the most-significant bit of the first field ending up in the most-significant bits of the first written byte. If the number of nibbles written is odd, the final byte has its least-significant nibble set to zero.
|
||||||
most-significant bit of the first field ending up in the most-significant bits of the first written byte. If the number
|
|
||||||
of nibbles written is odd, the final byte has its least-significant nibble set to zero.
|
|
||||||
|
|
||||||
For example, given these field values:
|
For example, given these field values:
|
||||||
|
|
||||||
|
@ -429,72 +355,58 @@ So the header and fields would be encoded together as:
|
||||||
```
|
```
|
||||||
|
|
||||||
#### NULL (9)
|
#### NULL (9)
|
||||||
This encoding does not write any bytes to the file. It is used when the predictor will always perfectly predict the
|
|
||||||
value of the field, so the remainder is always zero. In practice this is only used for the "loopIteration" field in
|
This encoding does not write any bytes to the file. It is used when the predictor will always perfectly predict the value of the field, so the remainder is always zero. In practice this is only used for the "loopIteration" field in interframes, which is always perfectly predictable based on the logged frame's position in the sequence of frames and the "P interval" setting from the header.
|
||||||
interframes, which is always perfectly predictable based on the logged frame's position in the sequence of frames and
|
|
||||||
the "P interval" setting from the header.
|
|
||||||
|
|
||||||
## Log file structure
|
## Log file structure
|
||||||
A logging session begins with a log start marker, then a header section which describes the format of the log, then the
|
|
||||||
log payload data, and finally an optional "log end" event ("E" frame).
|
|
||||||
|
|
||||||
A single log file can be comprised of one or more logging sessions. Each session may be preceded and followed by any
|
A logging session begins with a log start marker, then a header section which describes the format of the log, then the log payload data, and finally an optional "log end" event ("E" frame).
|
||||||
amount of non-Blackbox data. This data is ignored by the Blackbox log decoding tools. This allows for the logging device
|
|
||||||
to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a
|
A single log file can be comprised of one or more logging sessions. Each session may be preceded and followed by any amount of non-Blackbox data. This data is ignored by the Blackbox log decoding tools. This allows for the logging device to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a separate log file for each separate activity.
|
||||||
separate log file for each separate activity.
|
|
||||||
|
|
||||||
### Log start marker
|
### Log start marker
|
||||||
The log start marker is "H Product:Blackbox flight data recorder by Nicholas Sherlock\n". This marker is
|
|
||||||
used to discover the beginning of the flight log if the log begins partway through a file. Because it is such a long
|
The log start marker is `H Product:Blackbox flight data recorder by Nicholas Sherlock\n`. This marker is used to discover the beginning of the flight log if the log begins partway through a file. Because it is such a long string, it is not expected to occur by accident in any sequence of random bytes from other log device users.
|
||||||
string, it is not expected to occur by accident in any sequence of random bytes from other log device users.
|
|
||||||
|
|
||||||
### Log header
|
### Log header
|
||||||
The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value`
|
|
||||||
and ends with a '\n'. The overall header does not have a terminator to separate it from the log payload
|
The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value` and ends with a `'\n'`. The overall header does not have a terminator to separate it from the log payload (the header implicitly ends when a line does not begin with an 'H' character).
|
||||||
(the header implicitly ends when a line does not begin with an 'H' character).
|
|
||||||
|
|
||||||
The header can contain some of these fields:
|
The header can contain some of these fields:
|
||||||
|
|
||||||
#### Data version (required)
|
#### Data version (required)
|
||||||
When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is
|
|
||||||
incremented to allow backwards-compatibility in the decoder:
|
When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is incremented to allow backwards-compatibility in the decoder:
|
||||||
|
|
||||||
```
|
```
|
||||||
H Data version:2
|
H Data version:2
|
||||||
```
|
```
|
||||||
|
|
||||||
#### Logging interval
|
#### Logging interval
|
||||||
Not every main loop iteration needs to result in a Blackbox logging iteration. When a loop iteration is not logged,
|
|
||||||
Blackbox is not called, no state is read from the flight controller, and nothing is written to the log. Two header lines
|
Not every main loop iteration needs to result in a Blackbox logging iteration. When a loop iteration is not logged, Blackbox is not called, no state is read from the flight controller, and nothing is written to the log. Two header lines are included to note which main loop iterations will be logged:
|
||||||
are included to note which main loop iterations will be logged:
|
|
||||||
|
|
||||||
##### I interval
|
##### I interval
|
||||||
This header notes which of the main loop iterations will record an "I" intraframe to the log. If main loop iterations
|
|
||||||
with indexes divisible by 32 will be logged as "I" frames, the header will be:
|
This header notes which of the main loop iterations will record an "I" intraframe to the log. If main loop iterations with indexes divisible by 32 will be logged as "I" frames, the header will be:
|
||||||
|
|
||||||
```
|
```
|
||||||
H I interval: 32
|
H I interval: 32
|
||||||
```
|
```
|
||||||
|
|
||||||
The first main loop iteration seen by Blackbox will be numbered with index 0, so the first main loop iteration will
|
The first main loop iteration seen by Blackbox will be numbered with index 0, so the first main loop iteration will always be logged as an intraframe.
|
||||||
always be logged as an intraframe.
|
|
||||||
|
|
||||||
##### P interval
|
##### P interval
|
||||||
Not every "P" interframe needs to be logged. Blackbox will log a portion of iterations in order to bring the total
|
|
||||||
portion of logged main frames to a user-chosen fraction. This fraction is called the logging rate. The smallest possible
|
Not every "P" interframe needs to be logged. Blackbox will log a portion of iterations in order to bring the total portion of logged main frames to a user-chosen fraction. This fraction is called the logging rate. The smallest possible logging rate is `(1/I interval)` which corresponds to logging only "I" frames at the "I" interval and discarding all other loop iterations. The maximum logging rate is `1/1`, where every main loop iteration that is not an "I" frame is logged as a "P" frame. The header records the logging rate fraction in `numerator/denominator` format like so:
|
||||||
logging rate is `(1/I interval)` which corresponds to logging only "I" frames at the "I" interval and discarding all
|
|
||||||
other loop iterations. The maximum logging rate is `1/1`, where every main loop iteration that is not an "I" frame is
|
|
||||||
logged as a "P" frame. The header records the logging rate fraction in `numerator/denominator` format like so:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
H P interval:1/2
|
H P interval:1/2
|
||||||
```
|
```
|
||||||
|
|
||||||
The logging fraction given by `num/denom` should be simplified (i.e. rather than 2/6, a logging rate of 1/3 should
|
The logging fraction given by `num/denom` should be simplified (i.e. rather than 2/6, a logging rate of 1/3 should be used).
|
||||||
be used).
|
|
||||||
|
|
||||||
Given a logging rate of `num/denom` and an I-frame interval of `I_INTERVAL`, the frame type to log for an iteration
|
Given a logging rate of `num/denom` and an I-frame interval of `I_INTERVAL`, the frame type to log for an iteration of index `iteration` is given by:
|
||||||
of index `iteration` is given by:
|
|
||||||
|
|
||||||
```c
|
```c
|
||||||
if (iteration % I_INTERVAL == 0)
|
if (iteration % I_INTERVAL == 0)
|
||||||
|
@ -520,8 +432,8 @@ For an I-interval of 32, these are the resulting logging patterns at some differ
|
||||||
|
|
||||||
|
|
||||||
#### Firmware type (optional)
|
#### Firmware type (optional)
|
||||||
Because Blackbox records the internal flight controller state, the interpretation of the logged data will depend
|
|
||||||
on knowing which flight controller recorded it. To accomodate this, the name of the flight controller should be recorded:
|
Because Blackbox records the internal flight controller state, the interpretation of the logged data will depend on knowing which flight controller recorded it. To accommodate this, the name of the flight controller should be recorded:
|
||||||
|
|
||||||
```
|
```
|
||||||
H Firmware type:INAV
|
H Firmware type:INAV
|
||||||
|
@ -535,24 +447,25 @@ H Firmware date:Aug 28 2015 16:49:11
|
||||||
```
|
```
|
||||||
|
|
||||||
#### Field X name (required)
|
#### Field X name (required)
|
||||||
|
|
||||||
This header is a comma-separated list of the names for the fields in the 'X' frame type:
|
This header is a comma-separated list of the names for the fields in the 'X' frame type:
|
||||||
|
|
||||||
```
|
```
|
||||||
H Field I name:loopIteration,time,axisP[0],axisP[1]...
|
H Field I name:loopIteration,time,axisP[0],axisP[1]...
|
||||||
```
|
```
|
||||||
|
|
||||||
The decoder assumes that the fields in the 'P' frame type will all have the same names as those in the 'I' frame, so
|
The decoder assumes that the fields in the 'P' frame type will all have the same names as those in the 'I' frame, so a "Field P name" header does not need to be supplied.
|
||||||
a "Field P name" header does not need to be supplied.
|
|
||||||
|
|
||||||
#### Field X signed (optional)
|
#### Field X signed (optional)
|
||||||
This is a comma-separated list of integers which are set to '1' when their corresponding field's value should be
|
|
||||||
interpreted as signed after decoding, or '0' otherwise:
|
This is a comma-separated list of integers which are set to '1' when their corresponding field's value should be interpreted as signed after decoding, or '0' otherwise:
|
||||||
|
|
||||||
```
|
```
|
||||||
H Field I signed:0,0,1,1...
|
H Field I signed:0,0,1,1...
|
||||||
```
|
```
|
||||||
|
|
||||||
#### Field X predictor (required)
|
#### Field X predictor (required)
|
||||||
|
|
||||||
This is a comma-separated list of integers which specify the predictors for each field in the specified frame type:
|
This is a comma-separated list of integers which specify the predictors for each field in the specified frame type:
|
||||||
|
|
||||||
```
|
```
|
||||||
|
@ -560,6 +473,7 @@ H Field I predictor:0,0,0,0...
|
||||||
```
|
```
|
||||||
|
|
||||||
#### Field X encoding (required)
|
#### Field X encoding (required)
|
||||||
|
|
||||||
This is a comma-separated list of integers which specify the encoding used for each field in the specified frame type:
|
This is a comma-separated list of integers which specify the encoding used for each field in the specified frame type:
|
||||||
|
|
||||||
```
|
```
|
||||||
|
@ -567,19 +481,18 @@ H Field X encoding:1,1,0,0...
|
||||||
```
|
```
|
||||||
|
|
||||||
#### vbatref
|
#### vbatref
|
||||||
|
|
||||||
This header provides the reference voltage that will be used by predictor #9.
|
This header provides the reference voltage that will be used by predictor #9.
|
||||||
|
|
||||||
#### minthrottle
|
#### minthrottle
|
||||||
|
|
||||||
This header provides the minimum value sent by INAV to the ESCs when armed, it is used by predictor #4.
|
This header provides the minimum value sent by INAV to the ESCs when armed, it is used by predictor #4.
|
||||||
|
|
||||||
#### Additional headers
|
#### Additional headers
|
||||||
The decoder ignores headers that it does not understand, so you can freely add any headers that you require in order to
|
|
||||||
properly interpret the meaning of the logged values.
|
|
||||||
|
|
||||||
For example, to create a graphical displays of RC sticks and motor percentages, the Blackbox rendering tool requires
|
The decoder ignores headers that it does not understand, so you can freely add any headers that you require in order to properly interpret the meaning of the logged values.
|
||||||
the additional headers "rcRate" and "maxthrottle". In order to convert raw gyroscope, accelerometer and voltage readings
|
|
||||||
into real-world units, the Blackbox decoder requires the calibration constants "gyro.scale", "acc_1G" and "vbatscale".
|
For example, to create a graphical displays of RC sticks and motor percentages, the Blackbox rendering tool requires the additional headers "rcRate" and "maxthrottle". In order to convert raw gyroscope, accelerometer and voltage readings into real-world units, the Blackbox decoder requires the calibration constants "gyro.scale", "acc_1G" and "vbatscale". These headers might look like:
|
||||||
These headers might look like:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
H rcRate:100
|
H rcRate:100
|
||||||
|
@ -591,16 +504,11 @@ H vbatscale:110
|
||||||
|
|
||||||
### Log payload
|
### Log payload
|
||||||
|
|
||||||
The log payload is a concatenated sequence of logged frames. Each frame type which is present in the log payload must
|
The log payload is a concatenated sequence of logged frames. Each frame type which is present in the log payload must have been previously described in the log header (with Frame X name, etc. headers). Each frame begins with a single capital letter to specify the type of frame (I, P, etc), which is immediately followed by the frame's field data. There is no frame length field, checksum, or trailer.
|
||||||
have been previously described in the log header (with Frame X name, etc. headers). Each frame begins with a single
|
|
||||||
capital letter to specify the type of frame (I, P, etc), which is immediately followed by the frame's field data. There
|
|
||||||
is no frame length field, checksum, or trailer.
|
|
||||||
|
|
||||||
The field data is encoded by taking an array of raw field data, computing the predictor for each field, subtrating this
|
The field data is encoded by taking an array of raw field data, computing the predictor for each field, subtracting this predictor from the field, then applying the field encoders to each field in sequence to serialize them to the log.
|
||||||
predictor from the field, then applying the field encoders to each field in sequence to serialize them to the log.
|
|
||||||
|
|
||||||
For example, imagine that we are encoding three fields in an intraframe, are using zero-predictors for each field (#0),
|
For example, imagine that we are encoding three fields in an intraframe, are using zero-predictors for each field (#0), and are encoding the values using the unsigned variable byte encoding (#1). For these field values:
|
||||||
and are encoding the values using the unsigned variable byte encoding (#1). For these field values:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
1, 2, 3
|
1, 2, 3
|
||||||
|
@ -612,9 +520,7 @@ We would encode a frame:
|
||||||
'I', 0x01, 0x02, 0x03
|
'I', 0x01, 0x02, 0x03
|
||||||
```
|
```
|
||||||
|
|
||||||
Imagine that we are encoding an array of motor commands in an interframe. We will use the previous motor commands as a
|
Imagine that we are encoding an array of motor commands in an interframe. We will use the previous motor commands as a predictor, and encode the resulting values using signed variable byte encoding. The motor command values seen in the previous logged iteration were:
|
||||||
predictor, and encode the resulting values using signed variable byte encoding. The motor command values seen in the
|
|
||||||
previous logged iteration were:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
1430, 1500, 1470, 1490
|
1430, 1500, 1470, 1490
|
||||||
|
@ -645,30 +551,31 @@ We will use unsigned variable byte encoding to write the resulting values to the
|
||||||
```
|
```
|
||||||
|
|
||||||
### Log end marker
|
### Log end marker
|
||||||
The log end marker is an optional Event ("E") frame of type 0xFF whose payload is the string "End of log\0". The
|
|
||||||
payload ensures that random data does not look like an end-of-log marker by chance. This event signals the tidy ending
|
The log end marker is an optional Event ("E") frame of type 0xFF whose payload is the string `End of log\0` or more recently, `End of log (disarm reason:X)\0` (X is a number, see below). The payload ensures that random data does not look like an end-of-log marker by chance. This event signals the tidy ending of the log. All following bytes until the next log-begin marker (or end of file) should be ignored by the log decoder.
|
||||||
of the log. All following bytes until the next log-begin marker (or end of file) should be ignored by the log
|
|
||||||
decoder.
|
|
||||||
|
|
||||||
```
|
```
|
||||||
'E', 0xFF, "End of log |