1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-15 20:35:29 +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:
Roman Lut 2022-12-10 19:26:08 +02:00
commit cb2d448911
379 changed files with 5433 additions and 3656 deletions

View file

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

View file

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

View file

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

View file

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

@ -0,0 +1,3 @@
#!/bin/bash
cd /src/
python3 src/utils/update_cli_docs.py

View file

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

View file

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

View file

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

View file

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

View file

@ -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
![](Screenshots/gps_off_box.png) ![](Screenshots/programming_disable_gps_sensor_fix.png)
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.*

View file

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

View file

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

View file

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

View file

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

View file

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

View file

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

View file

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

View file

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

View file

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

View file

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

View file

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

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

View file

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

View file

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

View file

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

View file

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

View file

@ -0,0 +1,3 @@
# SpeedyBee F405 V3
> Notice: At the moment, DSHOT is not supported on SpeedyBe F405 V3. Use Multishot instead

View file

@ -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", 0x00 'E', 0xFF, "End of log (disarm reason:4)\0", 0x00
``` ```
#### Disarm Reasons
<ol start="0">
<li> None</li>
<li> Timeout</li>
<li> Sticks</li>
<li> Switch_3D</li>
<li> Switch</li>
<li> Killswitch</li>
<li> Failsafe</li>
<li> Navigation</li>
</ol>
## Log validation ## Log validation
Any damage experienced to the log during recording is overwhelmingly due to subsequences of bytes being dropped by the
logging device due to overflowing buffers. Accordingly, Blackbox logs do not bother to include any checksums (bytes are Any damage experienced to the log during recording is overwhelmingly due to sub-sequences of bytes being dropped by the logging device due to overflowing buffers. Accordingly, Blackbox logs do not bother to include any checksums (bytes are not expected to be damaged by the logging device without changing the length of the message). Because of the tight bandwidth requirements of logging, neither a frame length field nor frame trailer is recorded that would allow for the
not expected to be damaged by the logging device without changing the length of the message). Because of the tight
bandwidth requirements of logging, neither a frame length field nor frame trailer is recorded that would allow for the
detection of missing bytes. detection of missing bytes.
Instead, the decoder uses a heuristic in order to detect damaged frames. The decoder reads an entire frame from the log Instead, the decoder uses a heuristic in order to detect damaged frames. The decoder reads an entire frame from the log (using the decoder for each field which is the counterpart of the encoder specified in the header), then it checks to see if the byte immediately following the frame, which should be the beginning of a next frame, is a recognized frame-type byte (e.g. 'I', 'P', 'E', etc). If that following byte represents a valid frame type, it is assumed that the decoded frame was the correct length (so was unlikely to have had random ranges of bytes removed from it, which would have likely altered the frame length). Otherwise, the frame is rejected, and a valid frame-type byte is looked for immediately after the frame-start byte of the frame that was rejected. A rejected frame causes all subsequent interframes to be rejected as well, up until the next intraframe.
(using the decoder for each field which is the counterpart of the encoder specified in the header), then it checks to
see if the byte immediately following the frame, which should be the beginning of a next frame, is a recognized
frame-type byte (e.g. 'I', 'P', 'E', etc). If that following byte represents a valid frame type, it is assumed that the
decoded frame was the correct length (so was unlikely to have had random ranges of bytes removed from it, which would
have likely altered the frame length). Otherwise, the frame is rejected, and a valid frame-type byte is looked for
immediately after the frame-start byte of the frame that was rejected. A rejected frame causes all subsequent
interframes to be rejected as well, up until the next intraframe.
A frame is also rejected if the "loopIteration" or "time" fields have made unreasonable leaps forward, or moved at A frame is also rejected if the "loopIteration" or "time" fields have made unreasonable leaps forward, or moved at all backwards. This suffices to detect almost all log corruption.
all backwards. This suffices to detect almost all log corruption.

View file

@ -39,4 +39,6 @@ You'll have to manually execute the same steps that the build script does:
+ Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build. + Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build.
+ Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image. + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image.
3. If you need to update `Settings.md`, run `docker run --entrypoint /src/cmake/docker_docs.sh --rm -it -u root -v <PATH_TO_REPO>:/src inav-build`
Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details.

View file

@ -1,17 +1,17 @@
# Generic Linux development tools # Generic Linux development tools
## Overview ## Overview
This article endeavours to provide a generic guide for compiling inav on Linux for inav 2.6 and later. This article endeavours to provide a generic guide for compiling INAV on Linux for INAV 2.6 and later.
inav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux). INAV requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux).
In order to provide a uniform and reasonably modern cross compiler, inav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The inav approach of providing a recommended compiler is however both sound and justified: In order to provide a uniform and reasonably modern cross compiler, INAV provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The INAV approach of providing a recommended compiler is however both sound and justified:
* The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers) * The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers)
* Disto cross-compilers are often older than the recommended inav compiler * Disto cross-compilers are often older than the recommended INAV compiler
* The installed cross-compiler is only used to build inav and it not obviously / generally available outside of the inav build environment. * The installed cross-compiler is only used to build INAV and it not obviously / generally available outside of the INAV build environment.
There are a however some specific cases for using the distro cross-compiler in preference to that installed by inav: There are a however some specific cases for using the distro cross-compiler in preference to that installed by INAV:
* You are using a distro that installs a more modern compiler (Arch) * You are using a distro that installs a more modern compiler (Arch)
* You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32). * You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32).
@ -20,13 +20,13 @@ There are a however some specific cases for using the distro cross-compiler in p
In addition to a cross-compiler, it is necessary to install some other tools: In addition to a cross-compiler, it is necessary to install some other tools:
* `git` : clone and manage the inav code repository * `git` : clone and manage the INAV code repository
* `cmake` : generate the build environment * `cmake` : generate the build environment
* `make` : run the firmware compilation * `make` : run the firmware compilation
* `ruby` : build some generated source files from JSON definitions * `ruby` : build some generated source files from JSON definitions
* `gcc` : native compiler used to generate settings and run tests * `gcc` : native compiler used to generate settings and run tests
Note that inav requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools. Note that INAV requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools.
Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does. Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does.
@ -67,7 +67,7 @@ The `git clone` creates an `inav` directory; we can enter this directory, config
## Build tooling ## Build tooling
For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplifies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build environment with `cmake` before we can build any firmware. For 2.6 and later, INAV uses `cmake` as its primary build tool. `cmake` simplifies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build environment with `cmake` before we can build any firmware.
## Using `cmake` ## Using `cmake`
@ -82,7 +82,7 @@ cmake ..
# note the "..", this is required as it tells cmake where to find its ruleset # note the "..", this is required as it tells cmake where to find its ruleset
``` ```
`cmake` will check for the presence of an inav-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. `cmake` will check for the presence of an INAV-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler.
Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as: Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as:
@ -94,7 +94,7 @@ cmake -DCOMPILER_VERSION_CHECK=OFF ..
## Bulding the firmware ## Bulding the firmware
Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the INAV cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler.
The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`. The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`.
@ -142,7 +142,7 @@ It is unlikely that the typical user will need to employ these options, other th
## Building with ninja ## Building with ninja
`cmake` is not a build system, rather it generates build files for a build manager. The examples above use `make` as the build manager; this has been the legacy way of building inav. It is also possible to use other build systems; one popular cross-platform tool is [ninja](https://ninja-build.org/) which is both lightweight and executes parallel builds by default. `cmake` is not a build system, rather it generates build files for a build manager. The examples above use `make` as the build manager; this has been the legacy way of building INAV. It is also possible to use other build systems; one popular cross-platform tool is [ninja](https://ninja-build.org/) which is both lightweight and executes parallel builds by default.
* Install `ninja` from the distro tool (apt, dnf, pacman as appropriate) * Install `ninja` from the distro tool (apt, dnf, pacman as appropriate)
* Configure `cmake` to use `ninja` as the build system * Configure `cmake` to use `ninja` as the build system
@ -163,8 +163,8 @@ It is unlikely that the typical user will need to employ these options, other th
In order to update your local firmware build: In order to update your local firmware build:
* Navigate to the local inav repository * Navigate to the local INAV repository
* Use the following steps to pull the latest changes and rebuild your local version of inav firmware from the `build` directory: * Use the following steps to pull the latest changes and rebuild your local version of INAV firmware from the `build` directory:
``` ```
$ cd inav $ cd inav

View file

@ -74,13 +74,13 @@ This will download the entire INAV repository for you into a new folder called "
## Build the code ## Build the code
Assuming you've just cloned the source code, you can switch your current Assuming you've just cloned the source code, you can switch your current
directory to inav's source try by typing: directory to INAV's source try by typing:
```sh ```sh
cd inav cd inav
``` ```
Inside the inav directory, create a new directory to store the built files. This Inside the INAV directory, create a new directory to store the built files. This
helps keeping everything nice and tidy, separating source code from artifacts. By helps keeping everything nice and tidy, separating source code from artifacts. By
convention this directory is usually called `build`, but any name would work. Enter convention this directory is usually called `build`, but any name would work. Enter
the following command to create it and switch your working directory to it: the following command to create it and switch your working directory to it:
@ -95,7 +95,7 @@ Now we need to configure the build by using the following command:
cmake .. cmake ..
``` ```
This will automatically download the required compiler for inav, so it This will automatically download the required compiler for INAV, so it
might take a few minutes. Once it's finished without errors, you can might take a few minutes. Once it's finished without errors, you can
build the target that you want by typing `make target-name`. e.g.: build the target that you want by typing `make target-name`. e.g.:
@ -119,7 +119,7 @@ INAV Configurator.
## Updating to the latest source ## Updating to the latest source
If you want to erase your local changes and update to the latest version of the INAV source, enter your If you want to erase your local changes and update to the latest version of the INAV source, enter your
inav directory and run these commands to first erase your local changes, fetch and merge the latest INAV directory and run these commands to first erase your local changes, fetch and merge the latest
changes from the repository, then rebuild the firmware: changes from the repository, then rebuild the firmware:
```sh ```sh

View file

@ -14,7 +14,7 @@ Download and install Vagrant for you OS from here:
https://www.vagrantup.com/downloads.html https://www.vagrantup.com/downloads.html
``` ```
## Cloning iNav repository ## Cloning INAV repository
Using git (The preferred way!) Using git (The preferred way!)
``` ```
git clone https://github.com/iNavFlight/inav.git git clone https://github.com/iNavFlight/inav.git
@ -28,7 +28,7 @@ and extract it to folder of your choosing.
## Running the virtual machine ## Running the virtual machine
Open up a terminal or command line interface (In windows search for CMD.exe and run it as administrator!) Open up a terminal or command line interface (In windows search for CMD.exe and run it as administrator!)
Navigate in to the directory of your cloned/unzipped iNav repository. (Where the "Vagrantfile" is located.) and start the virtual machine. Navigate in to the directory of your cloned/unzipped INAV repository. (Where the "Vagrantfile" is located.) and start the virtual machine.
``` ```
vagrant up vagrant up
``` ```

View file

@ -32,9 +32,9 @@ Install python and python-yaml to allow updates to settings.md
To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71) To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71)
## Downloading the iNav repository (example): ## Downloading the INAV repository (example):
Mount MS windows C drive and clone iNav Mount MS windows C drive and clone INAV
1. `cd /mnt/c` 1. `cd /mnt/c`
1. `git clone https://github.com/iNavFlight/inav.git` 1. `git clone https://github.com/iNavFlight/inav.git`

View file

@ -54,8 +54,6 @@ Edit file `./.vscode/c_cpp_properties.json` to setup enabled `defines`
"USE_RPM_FILTER", "USE_RPM_FILTER",
"USE_GLOBAL_FUNCTIONS", "USE_GLOBAL_FUNCTIONS",
"USE_DYNAMIC_FILTERS", "USE_DYNAMIC_FILTERS",
"USE_IMU_BNO055",
"USE_SECONDARY_IMU",
"USE_DSHOT", "USE_DSHOT",
"FLASH_SIZE 480", "FLASH_SIZE 480",
"USE_I2C_IO_EXPANDER", "USE_I2C_IO_EXPANDER",

View file

@ -249,8 +249,6 @@ sudo udevadm control --reload-rules
"USE_RPM_FILTER", "USE_RPM_FILTER",
"USE_GLOBAL_FUNCTIONS", "USE_GLOBAL_FUNCTIONS",
"USE_DYNAMIC_FILTERS", "USE_DYNAMIC_FILTERS",
"USE_IMU_BNO055",
"USE_SECONDARY_IMU",
"USE_DSHOT", "USE_DSHOT",
"FLASH_SIZE 480", "FLASH_SIZE 480",
"USE_I2C_IO_EXPANDER", "USE_I2C_IO_EXPANDER",

View file

@ -2,7 +2,7 @@
## Overview ## Overview
inav offers a function to use serial `printf` style debugging. INAV offers a function to use serial `printf` style debugging.
This provides a simple and intuitive debugging facility. This facility is only available after the serial sub-system has been initialised, which should be adequate for all but the most hard-core debugging requirements. This provides a simple and intuitive debugging facility. This facility is only available after the serial sub-system has been initialised, which should be adequate for all but the most hard-core debugging requirements.
@ -44,7 +44,7 @@ Log levels are defined in `src/main/common/log.h`, at the time of writing these
These are used at both compile time and run time. These are used at both compile time and run time.
At compile time, a maximum level may be defined. As of inav 2.3, for F3 targets the maximum level is ERROR, for F4/F7 the maximum level is DEBUG. At compile time, a maximum level may be defined. As of INAV 2.3, for F3 targets the maximum level is ERROR, for F4/F7 the maximum level is DEBUG.
At run time, the level defines the level that will be displayed, so for a F4 or F7 target that has compile time suport for all log levels, if the CLI sets At run time, the level defines the level that will be displayed, so for a F4 or F7 target that has compile time suport for all log levels, if the CLI sets
``` ```
@ -98,7 +98,7 @@ Log messages are transmitted through the `FUNCTION_LOG` serial port as MSP messa
* msp-tool https://github.com/fiam/msp-tool * msp-tool https://github.com/fiam/msp-tool
* mwp https://github.com/stronnag/mwptools * mwp https://github.com/stronnag/mwptools
* inav Configurator * INAV Configurator
For example, with the final lines of `src/main/fc/fc_init.c` set to: For example, with the final lines of `src/main/fc/fc_init.c` set to:

View file

@ -2,13 +2,13 @@
## Overview ## Overview
Historically, mission planners interoperating with inav (and multiwii) missions have used the XML mission file format defined by EOSBandi for MultiWii 2.3 (2013). Historically, mission planners interoperating with INAV (and multiwii) missions have used the XML mission file format defined by EOSBandi for MultiWii 2.3 (2013).
The format is defined the XSD schema here. The format is defined the XSD schema here.
* Lower case tags are preferred by inav. Older tools may prefer uppercase (the original MW usage). * Lower case tags are preferred by INAV. Older tools may prefer uppercase (the original MW usage).
* For inav 4.0 and later, the `missionitem/flags` attribute is required for "fly-by home" waypoints and multi-mission files. * For INAV 4.0 and later, the `missionitem/flags` attribute is required for "fly-by home" waypoints and multi-mission files.
* For inav 4.0 and later, multi-mission files; mission segments are delimited by a flag value of `165` (the MSP protocol 'last WP' value). * For INAV 4.0 and later, multi-mission files; mission segments are delimited by a flag value of `165` (the MSP protocol 'last WP' value).
* For multi-mission files, the waypoints may be numbered either sequentially across the whole file, or "reset-numbering" within each mission segment. The latter may (or not) be considered to be more "human readable", particularly where `JUMP` is used. * For multi-mission files, the waypoints may be numbered either sequentially across the whole file, or "reset-numbering" within each mission segment. The latter may (or not) be considered to be more "human readable", particularly where `JUMP` is used.
* The `mwp` tag was introduced by the eponymous mission planner. Other mission planners may consider that reusing some of the tags (`cx`, `cy` - centre location, `zoom` TMS zoom level, `home-x`, `home-y` - home location) is useful. * The `mwp` tag was introduced by the eponymous mission planner. Other mission planners may consider that reusing some of the tags (`cx`, `cy` - centre location, `zoom` TMS zoom level, `home-x`, `home-y` - home location) is useful.
* `meta` may be used as a synonym for `mwp`. * `meta` may be used as a synonym for `mwp`.

View file

@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<!-- XSchema for MW / iNav missions <!-- XSchema for MW / INAV missions
This file is part of inav This file is part of INAV
usage e.g. xmllint --noout --schema mw-mission.xsd example.mission usage e.g. xmllint --noout --schema mw-mission.xsd example.mission
Updated 2021-11-12 for 'meta' substitution. Updated 2021-11-12 for 'meta' substitution.
--> -->

View file

@ -10,7 +10,7 @@ Please search for existing issues *before* creating new ones.
When submitting an issue the general rule is to include: When submitting an issue the general rule is to include:
1. What is your setup and a detailed explanation of the issue, also include last working version of iNav. 1. What is your setup and a detailed explanation of the issue, also include last working version of INAV.
1. status dump from cli. 1. status dump from cli.
1. bootlog dump from cli. 1. bootlog dump from cli.
1. dump dump from cli. 1. dump dump from cli.

View file

@ -48,7 +48,7 @@ Users of OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use IN
### OSD layout Copy, Move, or Replace helper tool ### OSD layout Copy, Move, or Replace helper tool
[Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in iNav. Choose the from and to OSD layouts, and the method of transfering the layouts. [Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in INAV. Choose the from and to OSD layouts, and the method of transfering the layouts.
## Installation ## Installation

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software. You can redistribute this software * INAV is free software. You can redistribute this software
* and/or modify this software under the terms of the * and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav is distributed in the hope that they will be * INAV is distributed in the hope that they will be
* useful, but WITHOUT ANY WARRANTY; without even the implied * useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -92,8 +92,6 @@ main_sources(COMMON_SRC
drivers/accgyro/accgyro_mpu6500.h drivers/accgyro/accgyro_mpu6500.h
drivers/accgyro/accgyro_mpu9250.c drivers/accgyro/accgyro_mpu9250.c
drivers/accgyro/accgyro_mpu9250.h drivers/accgyro/accgyro_mpu9250.h
drivers/accgyro/accgyro_bno055_serial.c
drivers/accgyro/accgyro_bno055_serial.h
drivers/adc.c drivers/adc.c
drivers/adc.h drivers/adc.h
@ -302,8 +300,6 @@ main_sources(COMMON_SRC
flight/failsafe.c flight/failsafe.c
flight/failsafe.h flight/failsafe.h
flight/hil.c
flight/hil.h
flight/imu.c flight/imu.c
flight/imu.h flight/imu.h
flight/kalman.c flight/kalman.c
@ -335,8 +331,6 @@ main_sources(COMMON_SRC
flight/secondary_dynamic_gyro_notch.h flight/secondary_dynamic_gyro_notch.h
flight/dynamic_lpf.c flight/dynamic_lpf.c
flight/dynamic_lpf.h flight/dynamic_lpf.h
flight/secondary_imu.c
flight/secondary_imu.h
io/beeper.c io/beeper.c
io/beeper.h io/beeper.h
@ -484,8 +478,8 @@ main_sources(COMMON_SRC
io/displayport_msp.h io/displayport_msp.h
io/displayport_oled.c io/displayport_oled.c
io/displayport_oled.h io/displayport_oled.h
io/displayport_hdzero_osd.c io/displayport_msp_osd.c
io/displayport_hdzero_osd.h io/displayport_msp_osd.h
io/displayport_srxl.c io/displayport_srxl.c
io/displayport_srxl.h io/displayport_srxl.h
io/displayport_hott.c io/displayport_hott.c

View file

@ -66,11 +66,11 @@ typedef enum {
DEBUG_PCF8574, DEBUG_PCF8574,
DEBUG_DYNAMIC_GYRO_LPF, DEBUG_DYNAMIC_GYRO_LPF,
DEBUG_AUTOLEVEL, DEBUG_AUTOLEVEL,
DEBUG_IMU2,
DEBUG_ALTITUDE, DEBUG_ALTITUDE,
DEBUG_AUTOTRIM, DEBUG_AUTOTRIM,
DEBUG_AUTOTUNE, DEBUG_AUTOTUNE,
DEBUG_RATE_DYNAMICS, DEBUG_RATE_DYNAMICS,
DEBUG_LANDING, DEBUG_LANDING,
DEBUG_POS_EST,
DEBUG_COUNT DEBUG_COUNT
} debugType_e; } debugType_e;

View file

@ -167,8 +167,10 @@ displayPort_t *cmsDisplayPortGetCurrent(void)
// 30 cols x 13 rows // 30 cols x 13 rows
// HoTT Telemetry Screen // HoTT Telemetry Screen
// 21 cols x 8 rows // 21 cols x 8 rows
// HD // HDZERO
// 50 cols x 18 rows // 50 cols x 18 rows
// DJIWTF
// 60 cols x 22 rows
// //
#define NORMAL_SCREEN_MIN_COLS 18 // Less is a small screen #define NORMAL_SCREEN_MIN_COLS 18 // Less is a small screen

View file

@ -191,11 +191,11 @@ static const OSD_Entry cmsx_menuMissionSettingsEntries[] =
OSD_LABEL_ENTRY("-- MISSIONS --"), OSD_LABEL_ENTRY("-- MISSIONS --"),
OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN), OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN),
OSD_SETTING_ENTRY("MISSION FAILSAFE", SETTING_FAILSAFE_MISSION), OSD_SETTING_ENTRY("WP FAILSAFE DELAY", SETTING_FAILSAFE_MISSION_DELAY),
OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT), OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT),
OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS), OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS),
OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE), OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE),
OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_SAFE_DISTANCE), OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_MAX_SAFE_DISTANCE),
#ifdef USE_MULTI_MISSION #ifdef USE_MULTI_MISSION
OSD_SETTING_ENTRY("MULTI MISSION NUMBER", SETTING_NAV_WP_MULTI_MISSION_INDEX), OSD_SETTING_ENTRY("MULTI MISSION NUMBER", SETTING_NAV_WP_MULTI_MISSION_INDEX),
#endif #endif

View file

@ -215,6 +215,8 @@ static const OSD_Entry menuOsdElemsEntries[] =
OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED), OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED),
OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE), OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE),
OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH), OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH),
OSD_ELEMENT_ENTRY("GRD COURSE", OSD_GROUND_COURSE),
OSD_ELEMENT_ENTRY("X TRACK ERR", OSD_CROSS_TRACK_ERROR),
#endif // GPS #endif // GPS
OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING), OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING),
OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH), OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH),

View file

@ -27,6 +27,7 @@ FILE_COMPILE_FOR_SPEED
#include "common/filter.h" #include "common/filter.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "common/time.h"
// NULL filter // NULL filter
float nullFilterApply(void *filter, float input) float nullFilterApply(void *filter, float input)
@ -319,7 +320,7 @@ FAST_CODE void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint
FUNCTION_COMPILE_FOR_SIZE FUNCTION_COMPILE_FOR_SIZE
void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFrequency, const uint32_t refreshRate) { void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFrequency, const uint32_t refreshRate) {
const float dT = refreshRate * 1e-6f; const float dT = US2S(refreshRate);
if (cutoffFrequency) { if (cutoffFrequency) {
if (filterType == FILTER_PT1) { if (filterType == FILTER_PT1) {

View file

@ -96,7 +96,7 @@ void logInit(void)
} }
} }
// Initialization done // Initialization done
LOG_I(SYSTEM, "%s/%s %s %s / %s (%s)", LOG_INFO(SYSTEM, "%s/%s %s %s / %s (%s)",
FC_FIRMWARE_NAME, FC_FIRMWARE_NAME,
targetName, targetName,
FC_VERSION_STRING, FC_VERSION_STRING,

View file

@ -48,41 +48,41 @@ void _logf(logTopic_e topic, unsigned level, const char *fmt, ...) __attribute__
void _logBufferHex(logTopic_e topic, unsigned level, const void *buffer, size_t size); void _logBufferHex(logTopic_e topic, unsigned level, const void *buffer, size_t size);
#if defined(USE_LOG) #if defined(USE_LOG)
#define LOG_E(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, fmt, ##__VA_ARGS__) #define LOG_ERROR(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, fmt, ##__VA_ARGS__)
#define LOG_BUFFER_E(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, buf, size) #define LOG_BUFFER_ERROR(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, buf, size)
#else #else
#define LOG_E(...) #define LOG_ERROR(...)
#define LOG_BUFFER_E(...) #define LOG_BUFFER_ERROR(...)
#endif #endif
#if defined(USE_LOG) #if defined(USE_LOG)
#define LOG_W(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, fmt, ##__VA_ARGS__) #define LOG_WARNING(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, fmt, ##__VA_ARGS__)
#define LOG_BUF_W(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, buf, size) #define LOG_BUF_WARNING(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, buf, size)
#else #else
#define LOG_W(...) #define LOG_WARNING(...)
#define LOG_BUF_W(...) #define LOG_BUF_WARNING(...)
#endif #endif
#if defined(USE_LOG) #if defined(USE_LOG)
#define LOG_I(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, fmt, ##__VA_ARGS__) #define LOG_INFO(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, fmt, ##__VA_ARGS__)
#define LOG_BUF_I(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, buf, size) #define LOG_BUF_INFO(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, buf, size)
#else #else
#define LOG_I(...) #define LOG_INFO(...)
#define LOG_BUF_I(...) #define LOG_BUF_INFO(...)
#endif #endif
#if defined(USE_LOG) #if defined(USE_LOG)
#define LOG_V(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, fmt, ##__VA_ARGS__) #define LOG_VERBOSE(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, fmt, ##__VA_ARGS__)
#define LOG_BUF_V(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, buf, size) #define LOG_BUF_VERBOSE(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, buf, size)
#else #else
#define LOG_V(...) #define LOG_VERBOSE(...)
#define LOG_BUF_V(...) #define LOG_BUF_VERBOSE(...)
#endif #endif
#if defined(USE_LOG) #if defined(USE_LOG)
#define LOG_D(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, fmt, ##__VA_ARGS__) #define LOG_DEBUG(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, fmt, ##__VA_ARGS__)
#define LOG_BUF_D(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, buf, size) #define LOG_BUF_DEBUG(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, buf, size)
#else #else
#define LOG_D(...) #define LOG_DEBUG(...)
#define LOG_BUF_D(...) #define LOG_BUF_DEBUG(...)
#endif #endif

View file

@ -52,11 +52,11 @@ void * memAllocate(size_t wantedSize, resourceOwner_e owner)
retPointer = &dynHeap[dynHeapFreeWord]; retPointer = &dynHeap[dynHeapFreeWord];
dynHeapFreeWord += wantedWords; dynHeapFreeWord += wantedWords;
dynHeapUsage[owner] += wantedWords * sizeof(uint32_t); dynHeapUsage[owner] += wantedWords * sizeof(uint32_t);
LOG_D(SYSTEM, "Memory allocated. Free memory = %d", memGetAvailableBytes()); LOG_DEBUG(SYSTEM, "Memory allocated. Free memory = %d", memGetAvailableBytes());
} }
else { else {
// OOM // OOM
LOG_E(SYSTEM, "Out of memory"); LOG_ERROR(SYSTEM, "Out of memory");
ENABLE_ARMING_FLAG(ARMING_DISABLED_OOM); ENABLE_ARMING_FLAG(ARMING_DISABLED_OOM);
} }

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software. You can redistribute this software * INAV is free software. You can redistribute this software
* and/or modify this software under the terms of the * and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav is distributed in the hope that they will be * INAV is distributed in the hope that they will be
* useful, but WITHOUT ANY WARRANTY; without even the implied * useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -22,6 +22,7 @@
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
#define ARRAYEND(x) (&(x)[ARRAYLEN(x)]) #define ARRAYEND(x) (&(x)[ARRAYLEN(x)])
#define ZERO_FARRAY(a) memset(a, 0, sizeof(a))
#define CONST_CAST(type, value) ((type)(value)) #define CONST_CAST(type, value) ((type)(value))
@ -92,9 +93,9 @@ static inline int32_t cmp32(uint32_t a, uint32_t b) { return a-b; }
#ifdef UNIT_TEST #ifdef UNIT_TEST
// Call memcpy when building unittest - this is easier that asm symbol name mangling (symbols start with _underscore on win32) // Call memcpy when building unittest - this is easier that asm symbol name mangling (symbols start with _underscore on win32)
#include <string.h> #include <string.h>
static inline void memcpy_fn ( void * destination, const void * source, size_t num ) { memcpy(destination, source, num); }; static inline void memcpy_fn(void *destination, const void *source, size_t num) { memcpy(destination, source, num); };
#else #else
void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("memcpy"); void *memcpy_fn(void *destination, const void *source, size_t num) asm("memcpy");
#endif #endif
#if __GNUC__ > 6 #if __GNUC__ > 6

View file

@ -41,7 +41,7 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
} }
if (c->address == (uintptr_t)&eepromData[0]) { if (c->address == (uintptr_t)&eepromData[0]) {
memset(eepromData, 0, sizeof(eepromData)); ZERO_FARRAY(eepromData);
} }
config_streamer_buffer_align_type_t *destAddr = (config_streamer_buffer_align_type_t *)c->address; config_streamer_buffer_align_type_t *destAddr = (config_streamer_buffer_align_type_t *)c->address;

View file

@ -23,9 +23,9 @@
#define PG_MOTOR_MIXER 4 #define PG_MOTOR_MIXER 4
#define PG_BLACKBOX_CONFIG 5 #define PG_BLACKBOX_CONFIG 5
#define PG_MOTOR_CONFIG 6 #define PG_MOTOR_CONFIG 6
//#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in iNav //#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in INAV
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav //#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in INAV
//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav //#define PG_SENSOR_TRIMS 9 -- NOT USED in INAV
#define PG_GYRO_CONFIG 10 #define PG_GYRO_CONFIG 10
#define PG_BATTERY_PROFILES 11 #define PG_BATTERY_PROFILES 11
#define PG_CONTROL_RATE_PROFILES 12 #define PG_CONTROL_RATE_PROFILES 12
@ -85,7 +85,7 @@
// cleanflight v2 specific parameter group ids start at 256 // cleanflight v2 specific parameter group ids start at 256
#define PG_VTX_SETTINGS_CONFIG 259 #define PG_VTX_SETTINGS_CONFIG 259
// iNav specific parameter group ids start at 1000 // INAV specific parameter group ids start at 1000
#define PG_INAV_START 1000 #define PG_INAV_START 1000
#define PG_PITOTMETER_CONFIG 1000 #define PG_PITOTMETER_CONFIG 1000
#define PG_POSITION_ESTIMATION_CONFIG 1001 #define PG_POSITION_ESTIMATION_CONFIG 1001
@ -116,7 +116,7 @@
#define PG_SAFE_HOME_CONFIG 1026 #define PG_SAFE_HOME_CONFIG 1026
#define PG_DJI_OSD_CONFIG 1027 #define PG_DJI_OSD_CONFIG 1027
#define PG_PROGRAMMING_PID 1028 #define PG_PROGRAMMING_PID 1028
#define PG_SECONDARY_IMU 1029 #define PG_UNUSED_1 1029
#define PG_POWER_LIMITS_CONFIG 1030 #define PG_POWER_LIMITS_CONFIG 1030
#define PG_OSD_COMMON_CONFIG 1031 #define PG_OSD_COMMON_CONFIG 1031
#define PG_INAV_END 1031 #define PG_INAV_END 1031

View file

@ -30,9 +30,7 @@
#include "common/utils.h" #include "common/utils.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/exti.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/system.h" #include "drivers/system.h"
@ -62,7 +60,7 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t
} }
} }
LOG_V(GYRO, "GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X", LOG_VERBOSE(GYRO, "GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X",
desiredLpf, desiredRateHz, desiredLpf, desiredRateHz,
candidate->gyroLpf, candidate->gyroRateHz, candidate->gyroLpf, candidate->gyroRateHz,
candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]); candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]);
@ -70,50 +68,6 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t
return candidate; return candidate;
} }
/*
* Gyro interrupt service routine
*/
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
static void gyroIntExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
gyro->dataReady = true;
if (gyro->updateFn) {
gyro->updateFn(gyro);
}
}
#endif
void gyroIntExtiInit(gyroDev_t *gyro)
{
if (!gyro->busDev->irqPin) {
return;
}
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = IORead(gyro->busDev->irqPin);
if (status) {
return;
}
#endif
#if defined (STM32F7) || defined (STM32H7)
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
#else
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
IOConfigGPIO(gyro->busDev->irqPin, IOCFG_IN_FLOATING);
EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(gyro->busDev->irqPin, true);
#endif
#endif
}
bool gyroCheckDataReady(gyroDev_t* gyro) bool gyroCheckDataReady(gyroDev_t* gyro)
{ {
bool ret; bool ret;

View file

@ -19,7 +19,6 @@
#include "platform.h" #include "platform.h"
#include "common/axis.h" #include "common/axis.h"
#include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#define GYRO_LPF_256HZ 0 #define GYRO_LPF_256HZ 0
@ -44,7 +43,6 @@ typedef struct gyroDev_s {
sensorGyroReadDataFuncPtr temperatureFn; // read temperature if available sensorGyroReadDataFuncPtr temperatureFn; // read temperature if available
sensorGyroInterruptStatusFuncPtr intStatusFn; sensorGyroInterruptStatusFuncPtr intStatusFn;
sensorGyroUpdateFuncPtr updateFn; sensorGyroUpdateFuncPtr updateFn;
extiCallbackRec_t exti;
float scale; // scalefactor float scale; // scalefactor
int16_t gyroADCRaw[XYZ_AXIS_COUNT]; int16_t gyroADCRaw[XYZ_AXIS_COUNT];
int16_t gyroZero[XYZ_AXIS_COUNT]; int16_t gyroZero[XYZ_AXIS_COUNT];
@ -67,5 +65,4 @@ typedef struct accDev_s {
} accDev_t; } accDev_t;
const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count); const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count);
void gyroIntExtiInit(struct gyroDev_s *gyro);
bool gyroCheckDataReady(struct gyroDev_s *gyro); bool gyroCheckDataReady(struct gyroDev_s *gyro);

View file

@ -35,7 +35,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -86,8 +85,6 @@
static void bmi088GyroInit(gyroDev_t *gyro) static void bmi088GyroInit(gyroDev_t *gyro)
{ {
gyroIntExtiInit(gyro);
busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION);
// Soft reset // Soft reset

View file

@ -35,7 +35,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -106,8 +105,8 @@ typedef struct __attribute__ ((__packed__)) bmi160ContextData_s {
STATIC_ASSERT(sizeof(bmi160ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); STATIC_ASSERT(sizeof(bmi160ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small);
static const gyroFilterAndRateConfig_t gyroConfigs[] = { static const gyroFilterAndRateConfig_t gyroConfigs[] = {
{ GYRO_LPF_256HZ, 3200, { BMI160_BWP_NORMAL | BMI160_ODR_3200_Hz} }, { GYRO_LPF_256HZ, 3200, { BMI160_BWP_OSR4 | BMI160_ODR_3200_Hz} },
{ GYRO_LPF_256HZ, 1600, { BMI160_BWP_NORMAL | BMI160_ODR_1600_Hz} }, { GYRO_LPF_256HZ, 1600, { BMI160_BWP_OSR2 | BMI160_ODR_1600_Hz} },
{ GYRO_LPF_256HZ, 800, { BMI160_BWP_NORMAL | BMI160_ODR_800_Hz } }, { GYRO_LPF_256HZ, 800, { BMI160_BWP_NORMAL | BMI160_ODR_800_Hz } },
{ GYRO_LPF_188HZ, 800, { BMI160_BWP_OSR2 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 128 Hz { GYRO_LPF_188HZ, 800, { BMI160_BWP_OSR2 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 128 Hz
@ -123,7 +122,6 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = {
static void bmi160AccAndGyroInit(gyroDev_t *gyro) static void bmi160AccAndGyroInit(gyroDev_t *gyro)
{ {
uint8_t value; uint8_t value;
gyroIntExtiInit(gyro);
busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION);

View file

@ -34,7 +34,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -132,8 +131,8 @@ typedef struct __attribute__ ((__packed__)) bmi270ContextData_s {
STATIC_ASSERT(sizeof(bmi270ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); STATIC_ASSERT(sizeof(bmi270ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small);
static const gyroFilterAndRateConfig_t gyroConfigs[] = { static const gyroFilterAndRateConfig_t gyroConfigs[] = {
{ GYRO_LPF_256HZ, 3200, { BMI270_BWP_NORM | BMI270_ODR_3200} }, { GYRO_LPF_256HZ, 3200, { BMI270_BWP_OSR4 | BMI270_ODR_3200} },
{ GYRO_LPF_256HZ, 1600, { BMI270_BWP_NORM | BMI270_ODR_1600} }, { GYRO_LPF_256HZ, 1600, { BMI270_BWP_OSR2 | BMI270_ODR_1600} },
{ GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } }, { GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } },
{ GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } }, { GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } },
@ -197,8 +196,6 @@ static void bmi270AccAndGyroInit(gyroDev_t *gyro)
{ {
busDevice_t * busDev = gyro->busDev; busDevice_t * busDev = gyro->busDev;
gyroIntExtiInit(gyro);
// Perform a soft reset to set all configuration to default // Perform a soft reset to set all configuration to default
// Delay 100ms before continuing configuration // Delay 100ms before continuing configuration
busWrite(busDev, BMI270_REG_CMD, BMI270_CMD_SOFTRESET); busWrite(busDev, BMI270_REG_CMD, BMI270_CMD_SOFTRESET);
@ -234,10 +231,8 @@ static void bmi270AccAndGyroInit(gyroDev_t *gyro)
delay(1); delay(1);
// Configure the gyro data ready interrupt // Configure the gyro data ready interrupt
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(busDev, BMI270_REG_INT_MAP_DATA, BMI270_INT_MAP_DATA_DRDY_INT1); busWrite(busDev, BMI270_REG_INT_MAP_DATA, BMI270_INT_MAP_DATA_DRDY_INT1);
delay(1); delay(1);
#endif
// Configure the behavior of the INT1 pin // Configure the behavior of the INT1 pin
busWrite(busDev, BMI270_REG_INT1_IO_CTRL, BMI270_INT1_IO_CTRL_ACTIVE_HIGH | BMI270_INT1_IO_CTRL_OUTPUT_EN); busWrite(busDev, BMI270_REG_INT1_IO_CTRL, BMI270_INT1_IO_CTRL_ACTIVE_HIGH | BMI270_INT1_IO_CTRL_OUTPUT_EN);

View file

@ -1,180 +0,0 @@
/*
* This file is part of INAV.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#include <stdbool.h>
#include <stdint.h>
#include "drivers/bus.h"
#include "drivers/time.h"
#include "build/debug.h"
#include "common/vector.h"
#ifdef USE_IMU_BNO055
static busDevice_t *busDev;
static bool deviceDetect(busDevice_t *busDev)
{
for (int retry = 0; retry < 5; retry++)
{
uint8_t sig;
delay(150);
bool ack = busRead(busDev, 0x00, &sig);
if (ack)
{
return true;
}
};
return false;
}
static void bno055SetMode(uint8_t mode)
{
busWrite(busDev, BNO055_ADDR_OPR_MODE, mode);
delay(25);
}
static void bno055SetCalibrationData(bno055CalibrationData_t data)
{
uint8_t buf[12];
//Prepare gains
//We do not restore gyro offsets, they are quickly calibrated at startup
uint8_t bufferBit = 0;
for (uint8_t sensorIndex = 0; sensorIndex < 2; sensorIndex++)
{
for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++)
{
buf[bufferBit] = (uint8_t)(data.offset[sensorIndex][axisIndex] & 0xff);
buf[bufferBit + 1] = (uint8_t)((data.offset[sensorIndex][axisIndex] >> 8 ) & 0xff);
bufferBit += 2;
}
}
busWriteBuf(busDev, BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 12);
//Prepare radius
buf[0] = (uint8_t)(data.radius[ACC] & 0xff);
buf[1] = (uint8_t)((data.radius[ACC] >> 8 ) & 0xff);
buf[2] = (uint8_t)(data.radius[MAG] & 0xff);
buf[3] = (uint8_t)((data.radius[MAG] >> 8 ) & 0xff);
//Write to the device
busWriteBuf(busDev, BNO055_ADDR_ACC_RADIUS_LSB, buf, 4);
}
bool bno055Init(bno055CalibrationData_t calibrationData, bool setCalibration)
{
busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_BNO055, 0, 0);
if (busDev == NULL)
{
return false;
}
if (!deviceDetect(busDev))
{
busDeviceDeInit(busDev);
return false;
}
busWrite(busDev, BNO055_ADDR_PWR_MODE, BNO055_PWR_MODE_NORMAL); //Set power mode NORMAL
delay(25);
if (setCalibration) {
bno055SetMode(BNO055_OPR_MODE_CONFIG);
bno055SetCalibrationData(calibrationData);
}
bno055SetMode(BNO055_OPR_MODE_NDOF);
return true;
}
void bno055FetchEulerAngles(int16_t *buffer)
{
uint8_t buf[6];
busReadBuf(busDev, BNO055_ADDR_EUL_YAW_LSB, buf, 6);
buffer[0] = ((int16_t)((buf[3] << 8) | buf[2])) / 1.6f;
buffer[1] = ((int16_t)((buf[5] << 8) | buf[4])) / -1.6f; //Pitch has to be reversed to match INAV notation
buffer[2] = ((int16_t)((buf[1] << 8) | buf[0])) / 1.6f;
}
fpVector3_t bno055GetEurlerAngles(void)
{
fpVector3_t eurlerAngles;
uint8_t buf[6];
busReadBuf(busDev, BNO055_ADDR_EUL_YAW_LSB, buf, 6);
eurlerAngles.x = ((int16_t)((buf[3] << 8) | buf[2])) / 16;
eurlerAngles.y = ((int16_t)((buf[5] << 8) | buf[4])) / 16;
eurlerAngles.z = ((int16_t)((buf[1] << 8) | buf[0])) / 16;
return eurlerAngles;
}
bno055CalibStat_t bno055GetCalibStat(void)
{
bno055CalibStat_t stats;
uint8_t buf;
busRead(busDev, BNO055_ADDR_CALIB_STAT, &buf);
stats.mag = buf & 0b00000011;
stats.acc = (buf >> 2) & 0b00000011;
stats.gyr = (buf >> 4) & 0b00000011;
stats.sys = (buf >> 6) & 0b00000011;
return stats;
}
bno055CalibrationData_t bno055GetCalibrationData(void)
{
bno055CalibrationData_t data;
uint8_t buf[22];
bno055SetMode(BNO055_OPR_MODE_CONFIG);
busReadBuf(busDev, BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 22);
bno055SetMode(BNO055_OPR_MODE_NDOF);
uint8_t bufferBit = 0;
for (uint8_t sensorIndex = 0; sensorIndex < 3; sensorIndex++)
{
for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++)
{
data.offset[sensorIndex][axisIndex] = (int16_t)((buf[bufferBit + 1] << 8) | buf[bufferBit]);
bufferBit += 2;
}
}
data.radius[ACC] = (int16_t)((buf[19] << 8) | buf[18]);
data.radius[MAG] = (int16_t)((buf[21] << 8) | buf[20]);
return data;
}
#endif

View file

@ -1,270 +0,0 @@
/*
* This file is part of INAV.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#include "platform.h"
#ifdef USE_IMU_BNO055
#define BNO055_BAUD_RATE 115200
#define BNO055_FRAME_MAX_TIME_MS 10
#include <stdbool.h>
#include <stdint.h>
#include "io/serial.h"
#include "build/debug.h"
#include "drivers/time.h"
#include "flight/secondary_imu.h"
static serialPort_t * bno055SerialPort = NULL;
static uint8_t receiveBuffer[22];
typedef enum {
BNO055_RECEIVE_IDLE,
BNO055_RECEIVE_HEADER,
BNO055_RECEIVE_LENGTH,
BNO055_RECEIVE_PAYLOAD,
BNO055_RECEIVE_ACK,
} bno055ReceiveState_e;
typedef enum {
BNO055_FRAME_ACK,
BNO055_FRAME_DATA,
} bno055FrameType_e;
typedef enum {
BNO055_DATA_TYPE_NONE,
BNO055_DATA_TYPE_EULER,
BNO055_DATA_TYPE_CALIBRATION_STATS,
} bno055DataType_e;
static uint8_t bno055ProtocolState = BNO055_RECEIVE_IDLE;
static uint8_t bno055FrameType;
static uint8_t bno055FrameLength;
static uint8_t bno055FrameIndex;
static timeMs_t bno055FrameStartAtMs = 0;
static uint8_t bno055DataType = BNO055_DATA_TYPE_NONE;
static void bno055SerialWriteBuffer(const uint8_t reg, const uint8_t *data, const uint8_t count) {
bno055ProtocolState = BNO055_RECEIVE_IDLE;
serialWrite(bno055SerialPort, 0xAA); // Start Byte
serialWrite(bno055SerialPort, 0x00); // Write command
serialWrite(bno055SerialPort, reg);
serialWrite(bno055SerialPort, count);
for (uint8_t i = 0; i < count; i++) {
serialWrite(bno055SerialPort, data[i]);
}
}
static void bno055SerialWrite(const uint8_t reg, const uint8_t data) {
uint8_t buff[1];
buff[0] = data;
bno055SerialWriteBuffer(reg, buff, 1);
}
static void bno055SerialRead(const uint8_t reg, const uint8_t len) {
bno055ProtocolState = BNO055_RECEIVE_IDLE;
serialWrite(bno055SerialPort, 0xAA); // Start Byte
serialWrite(bno055SerialPort, 0x01); // Read command
serialWrite(bno055SerialPort, reg);
serialWrite(bno055SerialPort, len);
}
void bno055SerialDataReceive(uint16_t c, void *data) {
UNUSED(data);
const uint8_t incoming = (uint8_t) c;
//Failsafe for stuck frames
if (bno055ProtocolState != BNO055_RECEIVE_IDLE && millis() - bno055FrameStartAtMs > BNO055_FRAME_MAX_TIME_MS) {
bno055ProtocolState = BNO055_RECEIVE_IDLE;
}
if (bno055ProtocolState == BNO055_RECEIVE_IDLE && incoming == 0xEE) {
bno055FrameStartAtMs = millis();
bno055ProtocolState = BNO055_RECEIVE_HEADER;
bno055FrameType = BNO055_FRAME_ACK;
} else if (bno055ProtocolState == BNO055_RECEIVE_IDLE && incoming == 0xBB) {
bno055FrameStartAtMs = millis();
bno055ProtocolState = BNO055_RECEIVE_HEADER;
bno055FrameType = BNO055_FRAME_DATA;
} else if (bno055ProtocolState == BNO055_RECEIVE_HEADER && bno055FrameType == BNO055_FRAME_ACK) {
receiveBuffer[0] = incoming;
bno055ProtocolState = BNO055_RECEIVE_IDLE;
} else if (bno055ProtocolState == BNO055_RECEIVE_HEADER && bno055FrameType == BNO055_FRAME_DATA) {
bno055FrameLength = incoming;
bno055FrameIndex = 0;
bno055ProtocolState = BNO055_RECEIVE_LENGTH;
} else if (bno055ProtocolState == BNO055_RECEIVE_LENGTH) {
receiveBuffer[bno055FrameIndex] = incoming;
bno055FrameIndex++;
if (bno055FrameIndex == bno055FrameLength) {
bno055ProtocolState = BNO055_RECEIVE_IDLE;
if (bno055DataType == BNO055_DATA_TYPE_EULER) {
secondaryImuState.eulerAngles.raw[0] = ((int16_t)((receiveBuffer[3] << 8) | receiveBuffer[2])) / 1.6f;
secondaryImuState.eulerAngles.raw[1] = ((int16_t)((receiveBuffer[5] << 8) | receiveBuffer[4])) / -1.6f; //Pitch has to be reversed to match INAV notation
secondaryImuState.eulerAngles.raw[2] = ((int16_t)((receiveBuffer[1] << 8) | receiveBuffer[0])) / 1.6f;
secondaryImuProcess();
} else if (bno055DataType == BNO055_DATA_TYPE_CALIBRATION_STATS) {
secondaryImuState.calibrationStatus.mag = receiveBuffer[0] & 0b00000011;
secondaryImuState.calibrationStatus.acc = (receiveBuffer[0] >> 2) & 0b00000011;
secondaryImuState.calibrationStatus.gyr = (receiveBuffer[0] >> 4) & 0b00000011;
secondaryImuState.calibrationStatus.sys = (receiveBuffer[0] >> 6) & 0b00000011;
}
bno055DataType = BNO055_DATA_TYPE_NONE;
}
}
}
static void bno055SerialSetCalibrationData(bno055CalibrationData_t data)
{
uint8_t buf[12];
//Prepare gains
//We do not restore gyro offsets, they are quickly calibrated at startup
uint8_t bufferBit = 0;
for (uint8_t sensorIndex = 0; sensorIndex < 2; sensorIndex++)
{
for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++)
{
buf[bufferBit] = (uint8_t)(data.offset[sensorIndex][axisIndex] & 0xff);
buf[bufferBit + 1] = (uint8_t)((data.offset[sensorIndex][axisIndex] >> 8 ) & 0xff);
bufferBit += 2;
}
}
bno055SerialWriteBuffer(BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 12);
delay(25);
//Prepare radius
buf[0] = (uint8_t)(data.radius[ACC] & 0xff);
buf[1] = (uint8_t)((data.radius[ACC] >> 8 ) & 0xff);
buf[2] = (uint8_t)(data.radius[MAG] & 0xff);
buf[3] = (uint8_t)((data.radius[MAG] >> 8 ) & 0xff);
//Write to the device
bno055SerialWriteBuffer(BNO055_ADDR_ACC_RADIUS_LSB, buf, 4);
delay(25);
}
bool bno055SerialInit(bno055CalibrationData_t calibrationData, bool setCalibration) {
bno055SerialPort = NULL;
serialPortConfig_t * portConfig = findSerialPortConfig(FUNCTION_IMU2);
if (!portConfig) {
return false;
}
bno055SerialPort = openSerialPort(
portConfig->identifier,
FUNCTION_IMU2,
bno055SerialDataReceive,
NULL,
BNO055_BAUD_RATE,
MODE_RXTX,
SERIAL_NOT_INVERTED | SERIAL_UNIDIR | SERIAL_STOPBITS_1 | SERIAL_PARITY_NO
);
if (!bno055SerialPort) {
return false;
}
bno055SerialRead(0x00, 1); // Read ChipID
delay(5);
//Check ident
if (bno055FrameType != BNO055_FRAME_DATA || receiveBuffer[0] != 0xA0 || bno055ProtocolState != BNO055_RECEIVE_IDLE) {
return false; // Ident does not match, leave
}
bno055SerialWrite(BNO055_ADDR_PWR_MODE, BNO055_PWR_MODE_NORMAL); //Set power mode NORMAL
delay(25);
if (setCalibration) {
bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_CONFIG);
delay(25);
bno055SerialSetCalibrationData(calibrationData);
}
bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_NDOF);
delay(25);
return true;
}
/*
* This function is non-blocking and response will be processed by bno055SerialDataReceive
*/
void bno055SerialFetchEulerAngles() {
bno055DataType = BNO055_DATA_TYPE_EULER;
bno055SerialRead(BNO055_ADDR_EUL_YAW_LSB, 6);
}
/*
* This function is non-blocking and response will be processed by bno055SerialDataReceive
*/
void bno055SerialGetCalibStat(void) {
bno055DataType = BNO055_DATA_TYPE_CALIBRATION_STATS;
bno055SerialRead(BNO055_ADDR_CALIB_STAT, 1);
}
/*
* This function is blocking and should not be used during flight conditions!
*/
bno055CalibrationData_t bno055SerialGetCalibrationData(void) {
bno055CalibrationData_t data;
bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_CONFIG);
delay(25);
bno055SerialRead(BNO055_ADDR_ACC_OFFSET_X_LSB, 22);
delay(50);
uint8_t bufferBit = 0;
for (uint8_t sensorIndex = 0; sensorIndex < 3; sensorIndex++)
{
for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++)
{
data.offset[sensorIndex][axisIndex] = (int16_t)((receiveBuffer[bufferBit + 1] << 8) | receiveBuffer[bufferBit]);
bufferBit += 2;
}
}
data.radius[ACC] = (int16_t)((receiveBuffer[19] << 8) | receiveBuffer[18]);
data.radius[MAG] = (int16_t)((receiveBuffer[21] << 8) | receiveBuffer[20]);
bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_NDOF);
delay(25);
return data;
}
#endif

View file

@ -1,91 +0,0 @@
/*
* This file is part of INAV.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#include "common/vector.h"
#define BNO055_ADDR_PWR_MODE 0x3E
#define BNO055_ADDR_OPR_MODE 0x3D
#define BNO055_ADDR_CALIB_STAT 0x35
#define BNO055_PWR_MODE_NORMAL 0x00
#define BNO055_OPR_MODE_CONFIG 0x00
#define BNO055_OPR_MODE_NDOF 0x0C
#define BNO055_ADDR_EUL_YAW_LSB 0x1A
#define BNO055_ADDR_EUL_YAW_MSB 0x1B
#define BNO055_ADDR_EUL_ROLL_LSB 0x1C
#define BNO055_ADDR_EUL_ROLL_MSB 0x1D
#define BNO055_ADDR_EUL_PITCH_LSB 0x1E
#define BNO055_ADDR_EUL_PITCH_MSB 0x1F
#define BNO055_ADDR_MAG_RADIUS_MSB 0x6A
#define BNO055_ADDR_MAG_RADIUS_LSB 0x69
#define BNO055_ADDR_ACC_RADIUS_MSB 0x68
#define BNO055_ADDR_ACC_RADIUS_LSB 0x67
#define BNO055_ADDR_GYR_OFFSET_Z_MSB 0x66
#define BNO055_ADDR_GYR_OFFSET_Z_LSB 0x65
#define BNO055_ADDR_GYR_OFFSET_Y_MSB 0x64
#define BNO055_ADDR_GYR_OFFSET_Y_LSB 0x63
#define BNO055_ADDR_GYR_OFFSET_X_MSB 0x62
#define BNO055_ADDR_GYR_OFFSET_X_LSB 0x61
#define BNO055_ADDR_MAG_OFFSET_Z_MSB 0x60
#define BNO055_ADDR_MAG_OFFSET_Z_LSB 0x5F
#define BNO055_ADDR_MAG_OFFSET_Y_MSB 0x5E
#define BNO055_ADDR_MAG_OFFSET_Y_LSB 0x5D
#define BNO055_ADDR_MAG_OFFSET_X_MSB 0x5C
#define BNO055_ADDR_MAG_OFFSET_X_LSB 0x5B
#define BNO055_ADDR_ACC_OFFSET_Z_MSB 0x5A
#define BNO055_ADDR_ACC_OFFSET_Z_LSB 0x59
#define BNO055_ADDR_ACC_OFFSET_Y_MSB 0x58
#define BNO055_ADDR_ACC_OFFSET_Y_LSB 0x57
#define BNO055_ADDR_ACC_OFFSET_X_MSB 0x56
#define BNO055_ADDR_ACC_OFFSET_X_LSB 0x55
typedef enum {
ACC = 0,
MAG = 1,
GYRO = 2
} bno055Sensor_e;
typedef struct {
uint8_t sys;
uint8_t gyr;
uint8_t acc;
uint8_t mag;
} bno055CalibStat_t;
typedef struct {
int16_t radius[2];
int16_t offset[3][3];
} bno055CalibrationData_t;
bool bno055SerialInit(bno055CalibrationData_t calibrationData, bool setCalibration);
void bno055SerialFetchEulerAngles(void);
void bno055SerialGetCalibStat(void);
bno055CalibrationData_t bno055SerialGetCalibrationData(void);

View file

@ -31,7 +31,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
@ -93,8 +92,6 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro)
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
gyroIntExtiInit(gyro);
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
busWrite(busDev, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); busWrite(busDev, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET);
@ -112,15 +109,6 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro)
busWrite(busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); // Get Divider Drops busWrite(busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); // Get Divider Drops
delay(100); delay(100);
// Data ready interrupt configuration
busWrite(busDev, MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR, BYPASS_EN
delay(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(busDev, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
#endif
// Switch SPI to fast speed // Switch SPI to fast speed
busSetSpeed(busDev, BUS_SPEED_FAST); busSetSpeed(busDev, BUS_SPEED_FAST);
} }

View file

@ -29,7 +29,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
@ -156,8 +155,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro)
&icm42605GyroConfigs[0], ARRAYLEN(icm42605GyroConfigs)); &icm42605GyroConfigs[0], ARRAYLEN(icm42605GyroConfigs));
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
gyroIntExtiInit(gyro);
busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
busWrite(dev, ICM42605_RA_PWR_MGMT0, ICM42605_PWR_MGMT0_TEMP_DISABLE_OFF | ICM42605_PWR_MGMT0_ACCEL_MODE_LN | ICM42605_PWR_MGMT0_GYRO_MODE_LN); busWrite(dev, ICM42605_RA_PWR_MGMT0, ICM42605_PWR_MGMT0_TEMP_DISABLE_OFF | ICM42605_PWR_MGMT0_ACCEL_MODE_LN | ICM42605_PWR_MGMT0_GYRO_MODE_LN);
@ -180,7 +177,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro)
busWrite(dev, ICM42605_RA_INT_CONFIG0, ICM42605_UI_DRDY_INT_CLEAR_ON_SBR); busWrite(dev, ICM42605_RA_INT_CONFIG0, ICM42605_UI_DRDY_INT_CLEAR_ON_SBR);
delay(100); delay(100);
#ifdef USE_MPU_DATA_READY_SIGNAL
uint8_t intConfig1Value; uint8_t intConfig1Value;
busWrite(dev, ICM42605_RA_INT_SOURCE0, ICM42605_UI_DRDY_INT1_EN_ENABLED); busWrite(dev, ICM42605_RA_INT_SOURCE0, ICM42605_UI_DRDY_INT1_EN_ENABLED);
@ -193,7 +189,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro)
busWrite(dev, ICM42605_RA_INT_CONFIG1, intConfig1Value); busWrite(dev, ICM42605_RA_INT_CONFIG1, intConfig1Value);
delay(15); delay(15);
#endif
busSetSpeed(dev, BUS_SPEED_FAST); busSetSpeed(dev, BUS_SPEED_FAST);
} }

View file

@ -30,9 +30,7 @@
#include "common/utils.h" #include "common/utils.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/exti.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/system.h" #include "drivers/system.h"
@ -45,6 +43,8 @@
// Check busDevice scratchpad memory size // Check busDevice scratchpad memory size
STATIC_ASSERT(sizeof(mpuContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); STATIC_ASSERT(sizeof(mpuContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small);
#define int16_val(v, idx) ((int16_t)(((uint8_t)v[2 * idx] << 8) | v[2 * idx + 1]))
static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = { static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = {
{ GYRO_LPF_256HZ, 8000, { MPU_DLPF_256HZ, 0 } }, { GYRO_LPF_256HZ, 8000, { MPU_DLPF_256HZ, 0 } },
{ GYRO_LPF_256HZ, 4000, { MPU_DLPF_256HZ, 1 } }, { GYRO_LPF_256HZ, 4000, { MPU_DLPF_256HZ, 1 } },
@ -83,9 +83,9 @@ bool mpuGyroRead(gyroDev_t *gyro)
return false; return false;
} }
gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]); gyro->gyroADCRaw[X] = int16_val(data, 0);
gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]); gyro->gyroADCRaw[Y] = int16_val(data, 1);
gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]); gyro->gyroADCRaw[Z] = int16_val(data, 2);
return true; return true;
} }
@ -102,9 +102,9 @@ bool mpuGyroReadScratchpad(gyroDev_t *gyro)
mpuContextData_t * ctx = busDeviceGetScratchpadMemory(busDev); mpuContextData_t * ctx = busDeviceGetScratchpadMemory(busDev);
if (mpuUpdateSensorContext(busDev, ctx)) { if (mpuUpdateSensorContext(busDev, ctx)) {
gyro->gyroADCRaw[X] = (int16_t)((ctx->gyroRaw[0] << 8) | ctx->gyroRaw[1]); gyro->gyroADCRaw[X] = int16_val(ctx->gyroRaw, 0);
gyro->gyroADCRaw[Y] = (int16_t)((ctx->gyroRaw[2] << 8) | ctx->gyroRaw[3]); gyro->gyroADCRaw[Y] = int16_val(ctx->gyroRaw, 1);
gyro->gyroADCRaw[Z] = (int16_t)((ctx->gyroRaw[4] << 8) | ctx->gyroRaw[5]); gyro->gyroADCRaw[Z] = int16_val(ctx->gyroRaw, 2);
return true; return true;
} }
@ -116,9 +116,9 @@ bool mpuAccReadScratchpad(accDev_t *acc)
mpuContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev); mpuContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev);
if (ctx->lastReadStatus) { if (ctx->lastReadStatus) {
acc->ADCRaw[X] = (int16_t)((ctx->accRaw[0] << 8) | ctx->accRaw[1]); acc->ADCRaw[X] = int16_val(ctx->accRaw, 0);
acc->ADCRaw[Y] = (int16_t)((ctx->accRaw[2] << 8) | ctx->accRaw[3]); acc->ADCRaw[Y] = int16_val(ctx->accRaw, 1);
acc->ADCRaw[Z] = (int16_t)((ctx->accRaw[4] << 8) | ctx->accRaw[5]); acc->ADCRaw[Z] = int16_val(ctx->accRaw, 2);
return true; return true;
} }
@ -131,7 +131,7 @@ bool mpuTemperatureReadScratchpad(gyroDev_t *gyro, int16_t * data)
if (ctx->lastReadStatus) { if (ctx->lastReadStatus) {
// Convert to degC*10: degC = raw / 340 + 36.53 // Convert to degC*10: degC = raw / 340 + 36.53
*data = (int16_t)((ctx->tempRaw[0] << 8) | ctx->tempRaw[1]) / 34 + 365; *data = int16_val(ctx->tempRaw, 0) / 34 + 365;
return true; return true;
} }

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"

View file

@ -34,7 +34,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -75,8 +74,6 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
gyroIntExtiInit(gyro);
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
// Device Reset // Device Reset
@ -110,14 +107,6 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
busWrite(busDev, MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3); busWrite(busDev, MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
delayMicroseconds(15); delayMicroseconds(15);
busWrite(busDev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR
delayMicroseconds(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(busDev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
delayMicroseconds(15);
#endif
// Accel and Gyro DLPF Setting // Accel and Gyro DLPF Setting
busWrite(busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]); busWrite(busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]);
delayMicroseconds(1); delayMicroseconds(1);

View file

@ -26,7 +26,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
@ -71,8 +70,6 @@ static void mpu6500AccAndGyroInit(gyroDev_t *gyro)
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
gyroIntExtiInit(gyro);
busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
@ -99,15 +96,6 @@ static void mpu6500AccAndGyroInit(gyroDev_t *gyro)
busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
delay(100); delay(100);
// Data ready interrupt configuration
busWrite(dev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
delay(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
delay(15);
#endif
busSetSpeed(dev, BUS_SPEED_FAST); busSetSpeed(dev, BUS_SPEED_FAST);
} }

View file

@ -26,7 +26,6 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
@ -71,8 +70,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro)
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
gyroIntExtiInit(gyro);
busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
busWrite(dev, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
@ -99,15 +96,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro)
busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
delay(100); delay(100);
// Data ready interrupt configuration
busWrite(dev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
delay(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
delay(15);
#endif
busSetSpeed(dev, BUS_SPEED_FAST); busSetSpeed(dev, BUS_SPEED_FAST);
} }

View file

@ -20,8 +20,6 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*
* Copyright: INAVFLIGHT OU
*/ */
#include <stdbool.h> #include <stdbool.h>

View file

@ -20,8 +20,6 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*
* Copyright: INAVFLIGHT OU
*/ */
#pragma once #pragma once

View file

@ -28,7 +28,6 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/exti.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/barometer/barometer_bmp085.h" #include "drivers/barometer/barometer_bmp085.h"

View file

@ -1,5 +1,5 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* Cleanflight and Betaflight are free software. You can redistribute * Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
@ -18,7 +18,7 @@
* If not, see <http://www.gnu.org/licenses/>. * If not, see <http://www.gnu.org/licenses/>.
* *
* BMP388 Driver author: Dominic Clifton * BMP388 Driver author: Dominic Clifton
* iNav port: Michel Pastor * INAV port: Michel Pastor
*/ */
#include <stdbool.h> #include <stdbool.h>

View file

@ -20,8 +20,6 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*
* Copyright: INAVFLIGHT OU
*/ */
#include <stdbool.h> #include <stdbool.h>
@ -40,6 +38,8 @@
#include "drivers/barometer/barometer.h" #include "drivers/barometer/barometer.h"
#include "drivers/barometer/barometer_dps310.h" #include "drivers/barometer/barometer_dps310.h"
// See datasheet at https://www.infineon.com/dgdl/Infineon-DPS310-DataSheet-v01_02-EN.pdf?fileId=5546d462576f34750157750826c42242
#if defined(USE_BARO) && defined(USE_BARO_DPS310) #if defined(USE_BARO) && defined(USE_BARO_DPS310)
#define DPS310_REG_PSR_B2 0x00 #define DPS310_REG_PSR_B2 0x00
@ -77,7 +77,7 @@
#define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec.
#define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). #define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard).
#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) // #define DPS310_TMP_CFG_BIT_TMP_EXT (0x80)
#define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec.
#define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard). #define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard).
@ -188,7 +188,7 @@ static bool deviceConfigure(busDevice_t * busDev)
baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16);
// 0x1A c11 [15:8] + 0x1B c11 [7:0] // 0x1A c11 [15:8] + 0x1B c11 [7:0]
baroState.calib.c11 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); baroState.calib.c11 = getTwosComplement(((uint32_t)coef[10] << 8) | (uint32_t)coef[11], 16);
// 0x1C c20 [15:8] + 0x1D c20 [7:0] // 0x1C c20 [15:8] + 0x1D c20 [7:0]
baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16); baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16);
@ -266,10 +266,13 @@ static bool deviceReadMeasurement(baroDev_t *baro)
const float c21 = baroState.calib.c21; const float c21 = baroState.calib.c21;
const float c30 = baroState.calib.c30; const float c30 = baroState.calib.c30;
// See section 4.9.1, How to Calculate Compensated Pressure Values, of datasheet
baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21);
const float c0 = baroState.calib.c0; const float c0 = baroState.calib.c0;
const float c1 = baroState.calib.c1; const float c1 = baroState.calib.c1;
baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21); // See section 4.9.2, How to Calculate Compensated Temperature Values, of datasheet
baroState.temperature = c0 * 0.5f + c1 * Traw_sc; baroState.temperature = c0 * 0.5f + c1 * Traw_sc;
return true; return true;

View file

@ -20,8 +20,6 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*
* Copyright: INAVFLIGHT OU
*/ */
#pragma once #pragma once

View file

@ -1,5 +1,5 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* Cleanflight is free software: you can redistribute it and/or modify * Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by

View file

@ -1,5 +1,5 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* Cleanflight is free software: you can redistribute it and/or modify * Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by

View file

@ -32,7 +32,6 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"

View file

@ -32,7 +32,6 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"

View file

@ -32,7 +32,6 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"

View file

@ -1,18 +1,18 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software: you can redistribute it and/or modify * INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* iNav is distributed in the hope that it will be useful, * INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with iNav. If not, see <http://www.gnu.org/licenses/>. * along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "platform.h" #include "platform.h"

View file

@ -1,18 +1,18 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software: you can redistribute it and/or modify * INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* iNav is distributed in the hope that it will be useful, * INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with iNav. If not, see <http://www.gnu.org/licenses/>. * along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once

View file

@ -4,8 +4,6 @@
#include "platform.h" #include "platform.h"
#ifdef USE_EXTI
#include "build/assert.h" #include "build/assert.h"
#include "drivers/exti.h" #include "drivers/exti.h"
@ -200,5 +198,3 @@ _EXTI_IRQ_HANDLER(EXTI3_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); _EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler);
#endif // USE_EXTI

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software. You can redistribute * INAV is free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav is distributed in the hope that it * INAV is distributed in the hope that it
* will be useful, but WITHOUT ANY WARRANTY; without even the implied * will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software. You can redistribute * INAV is free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav is distributed in the hope that it * INAV is distributed in the hope that it
* will be useful, but WITHOUT ANY WARRANTY; without even the implied * will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav are free software. You can redistribute * INAV are free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav are distributed in the hope that they * INAV are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied * will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav are free software. You can redistribute * INAV are free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav are distributed in the hope that they * INAV are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied * will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -1,18 +1,18 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software: you can redistribute it and/or modify * INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* iNav is distributed in the hope that it will be useful, * INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with iNav. If not, see <http://www.gnu.org/licenses/>. * along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h> #include <stdbool.h>

View file

@ -1,18 +1,18 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav is free software: you can redistribute it and/or modify * INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* iNav is distributed in the hope that it will be useful, * INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with iNav. If not, see <http://www.gnu.org/licenses/>. * along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once

View file

@ -12,11 +12,8 @@
#define NVIC_PRIO_TIMER 3 #define NVIC_PRIO_TIMER 3
#define NVIC_PRIO_TIMER_DMA 3 #define NVIC_PRIO_TIMER_DMA 3
#define NVIC_PRIO_SDIO 3 #define NVIC_PRIO_SDIO 3
#define NVIC_PRIO_GYRO_INT_EXTI 4
#define NVIC_PRIO_USB 5 #define NVIC_PRIO_USB 5
#define NVIC_PRIO_SERIALUART 5 #define NVIC_PRIO_SERIALUART 5
#define NVIC_PRIO_SONAR_EXTI 7
// Use all available bits for priority and zero bits to sub-priority // Use all available bits for priority and zero bits to sub-priority
#ifdef USE_HAL_DRIVER #ifdef USE_HAL_DRIVER

View file

@ -45,7 +45,9 @@ typedef struct displayCanvas_s displayCanvas_t;
typedef enum { typedef enum {
VIDEO_SYSTEM_AUTO = 0, VIDEO_SYSTEM_AUTO = 0,
VIDEO_SYSTEM_PAL, VIDEO_SYSTEM_PAL,
VIDEO_SYSTEM_NTSC VIDEO_SYSTEM_NTSC,
VIDEO_SYSTEM_HDZERO,
VIDEO_SYSTEM_DJIWTF
} videoSystem_e; } videoSystem_e;
typedef enum { typedef enum {

View file

@ -171,9 +171,13 @@
#define SYM_AH_V_FT_1 0xD7 // 215 mAh/v-ft right #define SYM_AH_V_FT_1 0xD7 // 215 mAh/v-ft right
#define SYM_AH_V_M_0 0xD8 // 216 mAh/v-m left #define SYM_AH_V_M_0 0xD8 // 216 mAh/v-m left
#define SYM_AH_V_M_1 0xD9 // 217 mAh/v-m right #define SYM_AH_V_M_1 0xD9 // 217 mAh/v-m right
#define SYM_FLIGHT_MINS_REMAINING 0xDA // 218 Flight time (mins) remaining
#define SYM_FLIGHT_HOURS_REMAINING 0xDB // 219 Flight time (hours) remaining
#define SYM_GROUND_COURSE 0xDC // 220 Ground course
#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error
#define SYM_LOGO_START 0x101 // 257 to 280, INAV logo #define SYM_LOGO_START 0x101 // 257 to 297, INAV logo
#define SYM_LOGO_WIDTH 6 #define SYM_LOGO_WIDTH 10
#define SYM_LOGO_HEIGHT 4 #define SYM_LOGO_HEIGHT 4
#define SYM_AH_LEFT 0x12C // 300 Arrow left #define SYM_AH_LEFT 0x12C // 300 Arrow left
@ -220,6 +224,7 @@
#define SYM_HOME_DIST 0x165 // 357 DIST #define SYM_HOME_DIST 0x165 // 357 DIST
#define SYM_AH_CH_CENTER 0x166 // 358 Crossair center #define SYM_AH_CH_CENTER 0x166 // 358 Crossair center
#define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing
#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3 #define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3
#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4 #define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4

View file

@ -1,13 +1,13 @@
/* /*
* This file is part of iNav. * This file is part of INAV.
* *
* iNav free software. You can redistribute * INAV free software. You can redistribute
* this software and/or modify this software under the terms of the * this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software * GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) * Foundation, either version 3 of the License, or (at your option)
* any later version. * any later version.
* *
* iNav distributed in the hope that it * INAV distributed in the hope that it
* will be useful, but WITHOUT ANY WARRANTY; without even the implied * will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details. * See the GNU General Public License for more details.

View file

@ -64,12 +64,18 @@ static void virtualPitotCalculate(pitotDev_t *pitot, float *pressure, float *tem
UNUSED(pitot); UNUSED(pitot);
float airSpeed = 0.0f; float airSpeed = 0.0f;
if (pitotIsCalibrationComplete()) { if (pitotIsCalibrationComplete()) {
if (isEstimatedWindSpeedValid()) { if (isEstimatedWindSpeedValid() && STATE(GPS_FIX)) {
uint16_t windHeading; //centidegrees uint16_t windHeading; //centidegrees
float windSpeed = getEstimatedHorizontalWindSpeed(&windHeading); //cm/s float windSpeed = getEstimatedHorizontalWindSpeed(&windHeading); //cm/s
float horizontalWindSpeed = windSpeed * cos_approx(CENTIDEGREES_TO_RADIANS(windHeading - posControl.actualState.yaw)); //yaw int32_t centidegrees float horizontalWindSpeed = windSpeed * cos_approx(CENTIDEGREES_TO_RADIANS(windHeading - posControl.actualState.yaw)); //yaw int32_t centidegrees
airSpeed = posControl.actualState.velXY - horizontalWindSpeed; //float cm/s or gpsSol.groundSpeed int16_t cm/s airSpeed = posControl.actualState.velXY - horizontalWindSpeed; //float cm/s or gpsSol.groundSpeed int16_t cm/s
} else { airSpeed = calc_length_pythagorean_2D(airSpeed,getEstimatedActualVelocity(Z)+getEstimatedWindSpeed(Z));
}
else if (STATE(GPS_FIX))
{
airSpeed = calc_length_pythagorean_3D(gpsSol.velNED[X],gpsSol.velNED[Y],gpsSol.velNED[Z]);
}
else {
airSpeed = pidProfile()->fixedWingReferenceAirspeed; //float cm/s airSpeed = pidProfile()->fixedWingReferenceAirspeed; //float cm/s
} }
} }

View file

@ -230,6 +230,9 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU
timOutputs->maxTimMotorCount = 0; timOutputs->maxTimMotorCount = 0;
timOutputs->maxTimServoCount = 0; timOutputs->maxTimServoCount = 0;
uint8_t motorCount = getMotorCount();
uint8_t motorIdx = 0;
for (int idx = 0; idx < timerHardwareCount; idx++) { for (int idx = 0; idx < timerHardwareCount; idx++) {
timerHardware_t *timHw = &timerHardware[idx]; timerHardware_t *timHw = &timerHardware[idx];
@ -240,13 +243,20 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU
// Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC) // Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC)
if (checkPwmTimerConflicts(timHw)) { if (checkPwmTimerConflicts(timHw)) {
LOG_W(PWM, "Timer output %d skipped", idx); LOG_WARNING(PWM, "Timer output %d skipped", idx);
continue; continue;
} }
// Determine if timer belongs to motor/servo // Determine if timer belongs to motor/servo
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) {
// Multicopter // Multicopter
// Make sure first motorCount outputs get assigned to motor
if ((timHw->usageFlags & TIM_USE_MC_MOTOR) && (motorIdx < motorCount)) {
timHw->usageFlags = timHw->usageFlags & ~TIM_USE_MC_SERVO;
motorIdx += 1;
}
// We enable mapping to servos if mixer is actually using them // We enable mapping to servos if mixer is actually using them
if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO) { if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO) {
type = MAP_TO_SERVO_OUTPUT; type = MAP_TO_SERVO_OUTPUT;
@ -295,7 +305,7 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs)
// Check if too many motors // Check if too many motors
if (motorCount > MAX_MOTORS) { if (motorCount > MAX_MOTORS) {
pwmInitError = PWM_INIT_ERROR_TOO_MANY_MOTORS; pwmInitError = PWM_INIT_ERROR_TOO_MANY_MOTORS;
LOG_E(PWM, "Too many motors. Mixer requested %d, max %d", motorCount, MAX_MOTORS); LOG_ERROR(PWM, "Too many motors. Mixer requested %d, max %d", motorCount, MAX_MOTORS);
return; return;
} }
@ -304,14 +314,14 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs)
// Now if we need to configure individual motor outputs - do that // Now if we need to configure individual motor outputs - do that
if (!motorsUseHardwareTimers()) { if (!motorsUseHardwareTimers()) {
LOG_I(PWM, "Skipped timer init for motors"); LOG_INFO(PWM, "Skipped timer init for motors");
return; return;
} }
// If mixer requests more motors than we have timer outputs - throw an error // If mixer requests more motors than we have timer outputs - throw an error
if (motorCount > timOutputs->maxTimMotorCount) { if (motorCount > timOutputs->maxTimMotorCount) {
pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS; pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS;
LOG_E(PWM, "Not enough motor outputs. Mixer requested %d, outputs %d", motorCount, timOutputs->maxTimMotorCount); LOG_ERROR(PWM, "Not enough motor outputs. Mixer requested %d, outputs %d", motorCount, timOutputs->maxTimMotorCount);
return; return;
} }
@ -320,7 +330,7 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs)
const timerHardware_t *timHw = timOutputs->timMotors[idx]; const timerHardware_t *timHw = timOutputs->timMotors[idx];
if (!pwmMotorConfig(timHw, idx, feature(FEATURE_PWM_OUTPUT_ENABLE))) { if (!pwmMotorConfig(timHw, idx, feature(FEATURE_PWM_OUTPUT_ENABLE))) {
pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED; pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED;
LOG_E(PWM, "Timer allocation failed for motor %d", idx); LOG_ERROR(PWM, "Timer allocation failed for motor %d", idx);
return; return;
} }
} }
@ -331,14 +341,14 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs)
const int servoCount = getServoCount(); const int servoCount = getServoCount();
if (!isMixerUsingServos()) { if (!isMixerUsingServos()) {
LOG_I(PWM, "Mixer does not use servos"); LOG_INFO(PWM, "Mixer does not use servos");
return; return;
} }
// Check if too many servos // Check if too many servos
if (servoCount > MAX_SERVOS) { if (servoCount > MAX_SERVOS) {
pwmInitError = PWM_INIT_ERROR_TOO_MANY_SERVOS; pwmInitError = PWM_INIT_ERROR_TOO_MANY_SERVOS;
LOG_E(PWM, "Too many servos. Mixer requested %d, max %d", servoCount, MAX_SERVOS); LOG_ERROR(PWM, "Too many servos. Mixer requested %d, max %d", servoCount, MAX_SERVOS);
return; return;
} }
@ -348,14 +358,14 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs)
// Check if we need to init timer output for servos // Check if we need to init timer output for servos
if (!servosUseHardwareTimers()) { if (!servosUseHardwareTimers()) {
// External PWM servo driver // External PWM servo driver
LOG_I(PWM, "Skipped timer init for servos - using external servo driver"); LOG_INFO(PWM, "Skipped timer init for servos - using external servo driver");
return; return;
} }
// If mixer requests more servos than we have timer outputs - throw an error // If mixer requests more servos than we have timer outputs - throw an error
if (servoCount > timOutputs->maxTimServoCount) { if (servoCount > timOutputs->maxTimServoCount) {
pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS; pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS;
LOG_E(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount); LOG_ERROR(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount);
return; return;
} }
@ -365,7 +375,7 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs)
if (!pwmServoConfig(timHw, idx, servoConfig()->servoPwmRate, servoConfig()->servoCenterPulse, feature(FEATURE_PWM_OUTPUT_ENABLE))) { if (!pwmServoConfig(timHw, idx, servoConfig()->servoPwmRate, servoConfig()->servoCenterPulse, feature(FEATURE_PWM_OUTPUT_ENABLE))) {
pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED; pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED;
LOG_E(PWM, "Timer allocation failed for servo %d", idx); LOG_ERROR(PWM, "Timer allocation failed for servo %d", idx);
return; return;
} }
} }

View file

@ -130,7 +130,7 @@ static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uin
static pwmOutputPort_t *pwmOutAllocatePort(void) static pwmOutputPort_t *pwmOutAllocatePort(void)
{ {
if (allocatedOutputPortCount >= MAX_PWM_OUTPUT_PORTS) { if (allocatedOutputPortCount >= MAX_PWM_OUTPUT_PORTS) {
LOG_E(PWM, "Attempt to allocate PWM output beyond MAX_PWM_OUTPUT_PORTS"); LOG_ERROR(PWM, "Attempt to allocate PWM output beyond MAX_PWM_OUTPUT_PORTS");
return NULL; return NULL;
} }
@ -261,7 +261,7 @@ static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware,
// Configure timer DMA // Configure timer DMA
if (timerPWMConfigChannelDMA(port->tch, port->dmaBuffer, sizeof(port->dmaBuffer[0]), DSHOT_DMA_BUFFER_SIZE)) { if (timerPWMConfigChannelDMA(port->tch, port->dmaBuffer, sizeof(port->dmaBuffer[0]), DSHOT_DMA_BUFFER_SIZE)) {
// Only mark as DSHOT channel if DMA was set successfully // Only mark as DSHOT channel if DMA was set successfully
memset(port->dmaBuffer, 0, sizeof(port->dmaBuffer)); ZERO_FARRAY(port->dmaBuffer);
port->configured = true; port->configured = true;
} }

View file

@ -18,7 +18,7 @@
/* /*
* Cleanflight (or Baseflight): original * Cleanflight (or Baseflight): original
* jflyper: Mono-timer and single-wire half-duplex * jflyper: Mono-timer and single-wire half-duplex
* jflyper: Ported to iNav * jflyper: Ported to INAV
*/ */
#include <stdbool.h> #include <stdbool.h>

View file

@ -48,7 +48,7 @@ void systemBeep(bool onoff)
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
if (simulatorData.flags & SIMU_MUTE_BEEPER) { if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) {
onoff = false; onoff = false;
} }
} }

Some files were not shown because too many files have changed in this diff Show more