Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into mmosca-sbus2-telemetry
Browse files Browse the repository at this point in the history
  • Loading branch information
mmosca committed Jul 10, 2024
2 parents 6da4f35 + 904794d commit d01e762
Show file tree
Hide file tree
Showing 32 changed files with 978 additions and 271 deletions.
44 changes: 43 additions & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,50 @@ jobs:
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
name: ${{ env.BUILD_NAME }}.${{ matrix.id }}
name: matrix-${{ env.BUILD_NAME }}.${{ matrix.id }}
path: ./build/*.hex
retention-days: 1

upload-artifacts:
runs-on: ubuntu-latest
needs: [build]
steps:
- uses: actions/checkout@v4
- name: Setup environment
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
run: |
# This is the hash of the commit for the PR
# when the action is triggered by PR, empty otherwise
COMMIT_ID=${{ github.event.pull_request.head.sha }}
# This is the hash of the commit when triggered by push
# but the hash of refs/pull/<n>/merge, which is different
# from the hash of the latest commit in the PR, that's
# why we try github.event.pull_request.head.sha first
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
- name: Download artifacts
uses: actions/download-artifact@v4
with:
pattern: matrix-inav-*
merge-multiple: true
path: binaries
- name: Build target list
run: |
ls -1 binaries/*.hex | cut -d/ -f2 > targets.txt
- name: Upload firmware images
uses: actions/upload-artifact@v4
with:
name: ${{ env.BUILD_NAME }}
path: binaries/*.hex
- name: Upload firmware images
uses: actions/upload-artifact@v4
with:
name: targets
path: targets.txt

build-SITL-Linux:
runs-on: ubuntu-latest
Expand Down
9 changes: 9 additions & 0 deletions docs/OSD.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@

The On Screen Display, or OSD, is a feature that overlays flight data over the video image. This can be done on the flight controller, using the analogue MAX7456 chip. Digital systems take the OSD data, via MSP DisplayPort, send it to the video receiver; which combines the data with the image. You can specify what elements are displayed, and their locations on the image. Most systems are character based, and use the MAX7456 analogue setup, or MSP DisplayPort. However, there are some different systems which are also supported. Such as the canvas based FrSKY PixelOSD on analogue. Canvas OSDs draw shapes on the image. Whereas character based OSDs use font characters to display the data.


General OSD information is in this document. Other documents cover specific OSD-related topics:
* [Custom OSD Messages](https://github.com/iNavFlight/inav/wiki/OSD-custom-messages)
* [OSD Hud and ESP32 radars](https://github.com/iNavFlight/inav/wiki/OSD-Hud-and-ESP32-radars)
* [OSD Joystick](https://github.com/iNavFlight/inav/blob/master/docs/OSD%20Joystick.md)
* [DJI compatible OSD.md](https://github.com/iNavFlight/inav/blob/master/docs/DJI%20compatible%20OSD.md)
* [Pixel OSD FAQ](https://github.com/iNavFlight/inav/wiki/Pixel-OSD-FAQs)


## Features and Limitations
Not all OSDs are created equally. This table shows the differences between the different systems available.

Expand Down
17 changes: 9 additions & 8 deletions docs/Programming Framework.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
# INAV Programming Framework

INAV Programming Framework (IPF) is a mechanism that allows you to to create
INAV Programming Framework (IPF) is a mechanism that allows you to to create
custom functionality in INAV. You can choose for certain actions to be done,
based on custom conditions you select.

Logic conditions can be based on things such as RC channel values, switches, altitude,
Logic conditions can be based on things such as RC channel values, switches, altitude,
distance, timers, etc. The conditions you create can also make use of other conditions
you've entered previously.
The results can be used in:
Expand Down Expand Up @@ -56,8 +56,8 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
| 9 | XOR | `true` if `Operand A` or `Operand B` is `true`, but not both |
| 10 | NAND | `false` if `Operand A` and `Operand B` are both `true`|
| 11 | NOR | `true` if `Operand A` and `Operand B` are both `false` |
| 12 | NOT | The boolean opposite to `Operand A` |
| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`|
| 12 | NOT | The boolean opposite to `Operand A` |
| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`|
| 14 | Basic: Add | Add `Operand A` to `Operand B` and returns the result |
| 15 | Basic: Subtract | Substract `Operand B` from `Operand A` and returns the result |
| 16 | Basic: Multiply | Multiply `Operand A` by `Operand B` and returns the result |
Expand Down Expand Up @@ -147,7 +147,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
| 26 | Stabilized Pitch | Pitch PID controller output `[-500:500]` |
| 27 | Stabilized Yaw | Yaw PID controller output `[-500:500]` |
| 28 | 3D home distance [m] | 3D distance to home in `meters`. Calculated from Home distance and Altitude using Pythagorean theorem |
| 29 | CRSF LQ | Link quality as returned by the CRSF protocol |
| 29 | CRSF LQ | Link quality as returned by the CRSF protocol |
| 30 | CRSF SNR | SNR as returned by the CRSF protocol |
| 31 | GPS Valid Fix | Boolean `0`/`1`. True when the GPS has a valid 3D Fix |
| 32 | Loiter Radius [cm] | The current loiter radius in cm. |
Expand All @@ -161,6 +161,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
| 40 | Yaw [deg] | Current heading (yaw) in `degrees` |
| 41 | FW Land Sate | Integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare |
| 42 | Current battery profile | The active battery profile. Integer `[1..MAX_PROFILE_COUNT]` |
| 43 | Flown Loiter Radius [m] | The actual loiter radius flown by a fixed wing during hold modes, in `meters` |

#### FLIGHT_MODE

Expand All @@ -183,7 +184,7 @@ The flight mode operands return `true` when the mode is active. These are modes
| 12 | USER 3 | `true` when the **USER 3** mode is active. |
| 13 | USER 4 | `true` when the **USER 4** mode is active. |
| 14 | Acro | `true` when you are in the **Acro** flight mode. |
| 15 | Waypoint Mission | `true` when you are in the **WP Mission** flight mode. |
| 15 | Waypoint Mission | `true` when you are in the **WP Mission** flight mode. |

#### WAYPOINTS

Expand Down Expand Up @@ -216,7 +217,7 @@ The flight mode operands return `true` when the mode is active. These are modes
| JUMP | 6 |
| SET_HEAD | 7 |
| LAND | 8 |

### Flags

All flags are reseted on ARM and DISARM event.
Expand Down Expand Up @@ -333,7 +334,7 @@ Steps:

## Common issues / questions about IPF

One common mistake involves setting RC channel values. To override (set) the
One common mistake involves setting RC channel values. To override (set) the
value of a specific RC channel, choose "Override RC value", then for operand A
choose *value* and enter the channel number. Choosing "get RC value" is a common mistake,
which does something other than what you probably want.
Expand Down
2 changes: 1 addition & 1 deletion docs/Rx.md
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ Note:

## SIM (SITL) Joystick

Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL).
Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL.md).

## Configuration

Expand Down
56 changes: 56 additions & 0 deletions docs/Serial Gimbal.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# Serial Gimbal
INAV 8.0 introduces support for serial Gimbals. Currently, it is compatible with the protocol used by the Walksnail GM series gimbals.

While these gimbals also support PWM as input, using the Serial protocol gives it more flexibility and saves up to 4 PWM channels. The downside of the Serial protocol vs PWM input is that you don't have access to the full power of INAV's mixers. The main advantage is that you gain easy control of gimbal functions using INAV's modes.

# Axis Input
The Serial Gimbal supports 2 differents inputs.

## PWM Channels
This is the simplest way to control the Gimbal, as you can use your radio mixer and sliders to Control the gimbal by assigning RC channels to functions in the ```Configuration``` tab. You can control all 3 gimbal axis and unlike the raw PWM input, gimbal modes are controlled by INAV modes and you can control roll channel as well, instead of wiring 4 servo outputs. If an rc channel is set to 0, that input will be ignore and will be equivalent to a centered RC channel. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab.

## Headtracker Input
Headtracker input is only used when you have a Headtracker device configured and the ```Gimbal Headtracker``` mode is active.
A Headtracker device is a device that transmits headtracker information by a side channel, instead of relying on your rc link.

In head tracker mode, the Serial Gimbal will ignore the axis rc channel inputs and replace it with the inputs coming from the Headtracker device.

# Gimbal Modes
## No Gimbal mode selected
Like ACRO is the default mode for flight modes, the Gimbal will default to ```FPV Mode``` or ```Follow Mode``` when no mode is selected. The gimbal will try to stablized the footag and will follow the aircraft pitch, roll and yaw movements and use user inputs to point the camera where the user wants.

## Gimbal Center
This locks the gimbal camera to the center position and ignores any user input. Useful to reset the camera if you loose orientation.

## Gimbal Headtracker
Switches inputs to the configured Headtracker device. If no device is configured it will behave like Gimbal Center.

## Gimbal Level Tilt
This mode locks the camera tilt (pitch axis) and keeps it level with the horizon. Pitching the aircraft up and down, will move the camera so it stays pointing at the horizon. It can be combined with ```Gimbal Level Roll```.

## Gimbal Level Roll
This mode locks the camera roll and keeps it level with the horizon. Rolling the aircraft will move the camera so it stays level with the horizon. It can be combined with ```Gimbal Level Tilt```.

# Advanced settings
The gimbal also supports some advanced settings not exposed in the configurator.

## Gimbal Trim
You can set a trim setting for the gimbal, the idea is that it will shift the notion of center of the gimbal, like a trim and let you setup a fixed camera up tilt, like you would have in a traditional fpv quad setup.

```
gimbal_pan_trim = 0
Allowed range: -500 - 500
gimbal_tilt_trim = 0
Allowed range: -500 - 500
gimbal_roll_trim = 0
Allowed range: -500 - 500
```

## Gimbal and Headtracker on a single uart
As INAV does not process any inputs from the Walksnail Gimbal, it is possible to share the uard with the Walksnail Headtracking output by connect the fc TX to the gimbal and RX to receive the headtracker input.
```
gimbal_serial_single_uart = OFF
Allowed values: OFF, ON
```
16 changes: 13 additions & 3 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -1594,7 +1594,7 @@ Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS pos

### gps_provider

Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N).
Which GPS protocol to be used.

| Default | Min | Max |
| --- | --- | --- |
Expand All @@ -1614,7 +1614,7 @@ Which SBAS mode to be used

### gps_ublox_nav_hz

Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer.
Navigation update rate for UBLOX receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer.

| Default | Min | Max |
| --- | --- | --- |
Expand Down Expand Up @@ -1782,13 +1782,23 @@ Specifies the type of the software LPF of the gyro signals.

---

### gyro_lulu_enabled

Enable/disable gyro LULU filter

| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |

---

### gyro_lulu_sample_count

Gyro lulu sample count, in number of samples.

| Default | Min | Max |
| --- | --- | --- |
| 3 | | 15 |
| 3 | 1 | 15 |

---

Expand Down
12 changes: 12 additions & 0 deletions readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,18 @@

> The filtering settings for the ICM426xx has changed to match what is used by Ardupilot and Betaflight in INAV 7.1. When upgrading from older versions you may need to recalibrate the Accelerometer and if you are not using INAV's default tune you may also want to check if the tune is still good.
# M7, M6 and older UBLOX GPS units PSA

> INAV 8.0 will mark those GPS as deprecated and INAV 9.0.0 will require UBLOX units with Protocol version 15.00 or newer. This means that you need a GPS unit based on UBLOX M8 or newer.
> If you want to check the protocol version of your unit, it is displayed in INAV's 7.0.0+ status cli command.
> INAV 8.0.0 will warn you if your GPS is too old.
> ```GPS: HW Version: Unknown Proto: 0.00 Baud: 115200 (UBLOX Proto >= 15.0 required)```

> M8, M9 and M10 GPS are the most common units in use today, are readly available and have similar capabilities.
>Mantaining and testing GPS changes across this many UBLOX versions is a challenge and takes a lot of time. Removing the support for older devices will simplify code.
![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png)

# PosHold, Navigation and RTH without compass PSA
Expand Down
4 changes: 3 additions & 1 deletion src/main/build/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,9 @@ typedef enum {
DEBUG_POS_EST,
DEBUG_ADAPTIVE_FILTER,
DEBUG_HEADTRACKING,
DEBUG_COUNT
DEBUG_GPS,
DEBUG_LULU,
DEBUG_COUNT // also update debugModeNames in cli.c
} debugType_e;

#ifdef SITL_BUILD
Expand Down
1 change: 1 addition & 0 deletions src/main/cms/cms_menu_osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -237,6 +237,7 @@ static const OSD_Entry menuOsdElemsEntries[] =
OSD_ELEMENT_ENTRY("RADAR", OSD_RADAR),
OSD_ELEMENT_ENTRY("MAP SCALE", OSD_MAP_SCALE),
OSD_ELEMENT_ENTRY("MAP REFERENCE", OSD_MAP_REFERENCE),
OSD_ELEMENT_ENTRY("FORMATION FLIGHT", OSD_FORMATION_FLIGHT),
#endif
OSD_ELEMENT_ENTRY("EXPO", OSD_RC_EXPO),
OSD_ELEMENT_ENTRY("YAW EXPO", OSD_RC_YAW_EXPO),
Expand Down
41 changes: 21 additions & 20 deletions src/main/common/lulu.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,17 @@ void luluFilterInit(luluFilter_t *filter, int N)

FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, int windowSize)
{
register float curVal = 0;
register float curValB = 0;
float curVal = 0;
float curValB = 0;
for (int N = 1; N <= filterN; N++)
{
int indexNeg = (index + windowSize - 2 * N) % windowSize;
register int curIndex = (indexNeg + 1) % windowSize;
register float prevVal = series[indexNeg];
register float prevValB = seriesB[indexNeg];
register int indexPos = (curIndex + N) % windowSize;
for (int i = windowSize - 2 * N; i < windowSize - N; i++)
int curIndex = (indexNeg + 1) % windowSize;
float prevVal = series[indexNeg];
float prevValB = seriesB[indexNeg];
int indexPos = (curIndex + N) % windowSize;

for (int i = windowSize - 2 * N; i < windowSize - N; i++)
{
if (indexPos >= windowSize)
{
Expand All @@ -50,16 +51,16 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i
// curIndex = (2 - 1) % 3 = 1
curVal = series[curIndex];
curValB = seriesB[curIndex];
register float nextVal = series[indexPos];
register float nextValB = seriesB[indexPos];
float nextVal = series[indexPos];
float nextValB = seriesB[indexPos];
// onbump (s, 1, 1, 3)
// if(onBump(series, curIndex, N, windowSize))
if (prevVal < curVal && curVal > nextVal)
{
float maxValue = MAX(prevVal, nextVal);

series[curIndex] = maxValue;
register int k = curIndex;
int k = curIndex;
for (int j = 1; j < N; j++)
{
if (++k >= windowSize)
Expand All @@ -76,7 +77,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i

curVal = maxValue;
seriesB[curIndex] = maxValue;
register int k = curIndex;
int k = curIndex;
for (int j = 1; j < N; j++)
{
if (++k >= windowSize)
Expand Down Expand Up @@ -109,16 +110,16 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i
// curIndex = (2 - 1) % 3 = 1
curVal = series[curIndex];
curValB = seriesB[curIndex];
register float nextVal = series[indexPos];
register float nextValB = seriesB[indexPos];
float nextVal = series[indexPos];
float nextValB = seriesB[indexPos];

if (prevVal > curVal && curVal < nextVal)
{
float minValue = MIN(prevVal, nextVal);

curVal = minValue;
series[curIndex] = minValue;
register int k = curIndex;
int k = curIndex;
for (int j = 1; j < N; j++)
{
if (++k >= windowSize)
Expand All @@ -134,7 +135,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i
float minValue = MIN(prevValB, nextValB);
curValB = minValue;
seriesB[curIndex] = minValue;
register int k = curIndex;
int k = curIndex;
for (int j = 1; j < N; j++)
{
if (++k >= windowSize)
Expand All @@ -156,13 +157,13 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i
FAST_CODE float luluFilterPartialApply(luluFilter_t *filter, float input)
{
// This is the value N of the LULU filter.
register int filterN = filter->N;
int filterN = filter->N;
// This is the total window size for the rolling buffer
register int filterWindow = filter->windowSize;
int filterWindow = filter->windowSize;

register int windowIndex = filter->windowBufIndex;
register float inputVal = input;
register int newIndex = (windowIndex + 1) % filterWindow;
int windowIndex = filter->windowBufIndex;
float inputVal = input;
int newIndex = (windowIndex + 1) % filterWindow;
filter->windowBufIndex = newIndex;
filter->luluInterim[windowIndex] = inputVal;
filter->luluInterimB[windowIndex] = -inputVal;
Expand Down
1 change: 1 addition & 0 deletions src/main/common/printf.c
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,7 @@ int tfp_nformat(void *putp, int size, void (*putf) (void *, char), const char *f
written += putchw(putp, end, putf, w, lz, bf);
break;
}
case 'i':
case 'd':{
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng)
Expand Down
Loading

0 comments on commit d01e762

Please sign in to comment.