Skip to content

Commit c36b5d7

Browse files
Merge pull request #11457 from iNavFlight/maintenance-9.x
Maintenance 9.x to Maintenance-10.x
2 parents 15e118f + 56fb9e4 commit c36b5d7

53 files changed

Lines changed: 2087 additions & 110 deletions

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

.github/workflows/ci.yml

Lines changed: 96 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,69 @@ on:
2626

2727

2828
jobs:
29+
detect:
30+
runs-on: ubuntu-latest
31+
outputs:
32+
single_target: ${{ steps.check.outputs.single_target }}
33+
target_names: ${{ steps.check.outputs.target_names }}
34+
steps:
35+
- uses: actions/checkout@v4
36+
with:
37+
fetch-depth: 0
38+
- name: Detect single-target PR
39+
id: check
40+
run: |
41+
if [ "${{ github.event_name }}" != "pull_request" ]; then
42+
echo "single_target=false" >> $GITHUB_OUTPUT
43+
exit 0
44+
fi
45+
46+
CHANGED=$(git diff --name-only origin/${{ github.base_ref }}...HEAD)
47+
48+
if [ -z "$CHANGED" ]; then
49+
echo "single_target=false" >> $GITHUB_OUTPUT
50+
exit 0
51+
fi
52+
53+
# Fail fast if any changed file is outside src/main/target/<dir>/
54+
NON_TARGET=$(echo "$CHANGED" | grep -Ev '^src/main/target/[^/]+/.+' | head -1)
55+
if [ -n "$NON_TARGET" ]; then
56+
echo "Non-target file changed: $NON_TARGET — full build required"
57+
echo "single_target=false" >> $GITHUB_OUTPUT
58+
exit 0
59+
fi
60+
61+
# Count how many distinct target directories were touched
62+
TARGET_DIRS=$(echo "$CHANGED" | sed -n 's|^src/main/target/\([^/]*\)/.*|\1|p' | sort -u)
63+
DIR_COUNT=$(echo "$TARGET_DIRS" | wc -l)
64+
if [ "$DIR_COUNT" != "1" ]; then
65+
echo "$DIR_COUNT target directories changed — full build required"
66+
echo "single_target=false" >> $GITHUB_OUTPUT
67+
exit 0
68+
fi
69+
70+
TARGET_DIR="$TARGET_DIRS"
71+
CMAKE="src/main/target/${TARGET_DIR}/CMakeLists.txt"
72+
if [ ! -f "$CMAKE" ]; then
73+
echo "No CMakeLists.txt for $TARGET_DIR — full build required"
74+
echo "single_target=false" >> $GITHUB_OUTPUT
75+
exit 0
76+
fi
77+
78+
TARGET_NAMES=$(grep -oP '(?<=\()[^)]+' "$CMAKE" | tr '\n' ' ' | xargs)
79+
if [ -z "$TARGET_NAMES" ]; then
80+
echo "No target names in CMakeLists.txt — full build required"
81+
echo "single_target=false" >> $GITHUB_OUTPUT
82+
exit 0
83+
fi
84+
85+
echo "Single-target PR: building $TARGET_NAMES"
86+
echo "single_target=true" >> $GITHUB_OUTPUT
87+
echo "target_names=$TARGET_NAMES" >> $GITHUB_OUTPUT
88+
2989
build:
90+
needs: [detect]
91+
if: needs.detect.outputs.single_target != 'true'
3092
runs-on: ubuntu-latest
3193
strategy:
3294
matrix:
@@ -66,9 +128,42 @@ jobs:
66128
path: ./build/*.hex
67129
retention-days: 1
68130

131+
build-single-target:
132+
needs: [detect]
133+
if: needs.detect.outputs.single_target == 'true'
134+
runs-on: ubuntu-latest
135+
steps:
136+
- uses: actions/checkout@v4
137+
- name: Install dependencies
138+
run: sudo apt-get update && sudo apt-get -y install ninja-build
139+
- name: Setup environment
140+
env:
141+
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
142+
run: |
143+
COMMIT_ID=${{ github.event.pull_request.head.sha }}
144+
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
145+
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
146+
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t)]/, "", $2); print $2 }')
147+
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
148+
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
149+
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
150+
- uses: actions/cache@v4
151+
with:
152+
path: downloads
153+
key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}}
154+
- name: Build targets (${{ needs.detect.outputs.target_names }})
155+
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j${{ env.NUM_CORES }} ${{ needs.detect.outputs.target_names }}
156+
- name: Upload artifacts
157+
uses: actions/upload-artifact@v4
158+
with:
159+
name: matrix-${{ env.BUILD_NAME }}.single
160+
path: ./build/*.hex
161+
retention-days: 1
162+
69163
upload-artifacts:
70164
runs-on: ubuntu-latest
71-
needs: [build]
165+
needs: [build, build-single-target]
166+
if: always() && !cancelled() && (needs.build.result == 'success' || needs.build-single-target.result == 'success')
72167
steps:
73168
- uses: actions/checkout@v4
74169
- name: Setup environment

docs/Cli.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
7171
| `batch` | Start or end a batch of commands |
7272
| `battery_profile` | Change battery profile |
7373
| `beeper` | Show/set beeper (buzzer) [usage](Buzzer.md) |
74+
| `bind_msp_rx` | Initiate binding for MSP receivers (mLRS) |
7475
| `bind_rx` | Initiate binding for SRXL2 or CRSF receivers |
7576
| `blackbox` | Configure blackbox fields |
7677
| `bootlog` | Show init logs from [serial_printf_debugging](./development/serial_printf_debugging.md) |

docs/Rx.md

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -185,14 +185,20 @@ set rssi_channel = 0
185185

186186
Setting these values differently may have an adverse effects on RSSI readings.
187187

188-
#### CLI Bind Command
188+
#### CLI Bind Commands
189189

190190
This command will put the receiver into bind mode without the need to reboot the FC as it was required with the older `spektrum_sat_bind` command.
191191

192192
```
193193
bind_rx
194194
```
195195

196+
This command will send a bind request to an MSP receiver on the specified port.
197+
198+
```
199+
bind_msp_rx <port>
200+
```
201+
196202
## MultiWii serial protocol (MSP RX)
197203

198204
Allows you to use MSP commands as the RC input. Up to 18 channels are supported.

docs/Settings.md

Lines changed: 15 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1734,11 +1734,11 @@ Which SBAS mode to be used
17341734

17351735
### gps_ublox_nav_hz
17361736

1737-
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.
1737+
Navigation update rate for UBLOX receivers. M9 modules limit satellite tracking to 16 satellites at 10Hz or higher, but use 32 satellites below 10Hz for better accuracy. M10 modules work well at 8Hz with 3 constellations. Some M10 devices with high-performance clock can do up to 25Hz with 4 constellations. 8Hz is a safe, accurate default for M8/M9/M10.
17381738

17391739
| Default | Min | Max |
17401740
| --- | --- | --- |
1741-
| 10 | 5 | 200 |
1741+
| 8 | 5 | 200 |
17421742

17431743
---
17441744

@@ -1748,7 +1748,7 @@ Enable use of Beidou satellites. This is at the expense of other regional conste
17481748

17491749
| Default | Min | Max |
17501750
| --- | --- | --- |
1751-
| OFF | OFF | ON |
1751+
| ON | OFF | ON |
17521752

17531753
---
17541754

@@ -1758,7 +1758,7 @@ Enable use of Galileo satellites. This is at the expense of other regional const
17581758

17591759
| Default | Min | Max |
17601760
| --- | --- | --- |
1761-
| OFF | OFF | ON |
1761+
| ON | OFF | ON |
17621762

17631763
---
17641764

@@ -5624,7 +5624,7 @@ Defines rotation rate on PITCH axis that UAV will try to archive on max. stick d
56245624

56255625
### pitot_hardware
56265626

5627-
Selection of pitot hardware.
5627+
Selection of pitot hardware. VIRTUAL only works if a GPS is enabled.
56285628

56295629
| Default | Min | Max |
56305630
| --- | --- | --- |
@@ -6052,6 +6052,16 @@ When feature SERIALRX is enabled, this allows connection to several receivers wh
60526052

60536053
---
60546054

6055+
### servo_autotrim_iterm_rate_limit
6056+
6057+
Maximum I-term rate of change (units/sec) for autotrim to be applied. Prevents trim updates during maneuver transitions when I-term is changing rapidly. Only applies when using `feature FW_AUTOTRIM`.
6058+
6059+
| Default | Min | Max |
6060+
| --- | --- | --- |
6061+
| 2 | 0 | 50 |
6062+
6063+
---
6064+
60556065
### servo_autotrim_rotation_limit
60566066

60576067
Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`.

docs/development/msp/README.md

Lines changed: 19 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -419,7 +419,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
419419
[8730 - MSP2_INAV_SET_GLOBAL_TARGET](#msp2_inav_set_global_target)
420420
[8731 - MSP2_INAV_NAV_TARGET](#msp2_inav_nav_target)
421421
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
422-
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
422+
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
423+
[12289 - MSP2_RX_BIND](#msp2_rx_bind)
423424

424425
## <a id="msp_api_version"></a>`MSP_API_VERSION (1 / 0x1)`
425426
**Description:** Provides the MSP protocol version and the INAV API version.
@@ -4648,3 +4649,20 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
46484649

46494650
**Notes:** Requires `rxConfig()->receiverType == RX_TYPE_SERIAL`. Requires `USE_SERIALRX_CRSF` or `USE_SERIALRX_SRXL2`. Calls `crsfBind()` or `srxl2Bind()` respectively. Returns error if receiver type or provider is not supported for binding.
46504651

4652+
## <a id="msp2_rx_bind"></a>`MSP2_RX_BIND (12289 / 0x3001)`
4653+
**Description:** Initiates binding for MSP receivers (mLRS).
4654+
4655+
**Request Payload:**
4656+
|Field|C Type|Size (Bytes)|Description|
4657+
|---|---|---|---|
4658+
| `port_id` | `uint8_t` | 1 | Port ID |
4659+
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |
4660+
4661+
**Reply Payload:**
4662+
|Field|C Type|Size (Bytes)|Description|
4663+
|---|---|---|---|
4664+
| `port_id` | `uint8_t` | 1 | Port ID |
4665+
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |
4666+
4667+
**Notes:** Requires a receiver using MSP as the protocol, sends MSP2_RX_BIND to the receiver.
4668+

docs/development/msp/msp_messages.json

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4911,6 +4911,12 @@
49114911
"ctype": "uint16_t",
49124912
"desc": "Estimated Vertical Position Accuracy (`gpsSol.epv`)",
49134913
"units": "cm"
4914+
},
4915+
{
4916+
"name": "hwVersion",
4917+
"ctype": "uint32_t",
4918+
"desc": "GPS hardware version (`gpsState.hwVersion`). Values: 500=UBLOX5, 600=UBLOX6, 700=UBLOX7, 800=UBLOX8, 900=UBLOX9, 1000=UBLOX10, 0=UNKNOWN",
4919+
"units": "Version code"
49144920
}
49154921
]
49164922
},
@@ -11209,5 +11215,47 @@
1120911215
"reply": null,
1121011216
"notes": "Requires `rxConfig()->receiverType == RX_TYPE_SERIAL`. Requires `USE_SERIALRX_CRSF` or `USE_SERIALRX_SRXL2`. Calls `crsfBind()` or `srxl2Bind()` respectively. Returns error if receiver type or provider is not supported for binding.",
1121111217
"description": "Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2)."
11218+
},
11219+
"MSP2_RX_BIND": {
11220+
"code": 12289,
11221+
"mspv": 2,
11222+
"request": {
11223+
"payload": [
11224+
{
11225+
"name": "port_id",
11226+
"ctype": "uint8_t",
11227+
"desc": "Port ID",
11228+
"units": ""
11229+
},
11230+
{
11231+
"name": "reserved_for_custom_use",
11232+
"ctype": "uint8_t",
11233+
"desc": "Reserved for custom use",
11234+
"units": "",
11235+
"array": true,
11236+
"array_size": 3
11237+
}
11238+
]
11239+
},
11240+
"reply": {
11241+
"payload": [
11242+
{
11243+
"name": "port_id",
11244+
"ctype": "uint8_t",
11245+
"desc": "Port ID",
11246+
"units": ""
11247+
},
11248+
{
11249+
"name": "reserved_for_custom_use",
11250+
"ctype": "uint8_t",
11251+
"desc": "Reserved for custom use",
11252+
"units": "",
11253+
"array": true,
11254+
"array_size": 3
11255+
}
11256+
]
11257+
},
11258+
"notes": "Requires a receiver using MSP as the protocol, sends MSP2_RX_BIND to the receiver.",
11259+
"description": "Initiates binding for MSP receivers (mLRS)."
1121211260
}
1121311261
}

lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -125,6 +125,7 @@ extern USBD_Class_cb_TypeDef USBD_CDC_cb;
125125
/** @defgroup USB_CORE_Exported_Functions
126126
* @{
127127
*/
128+
void USBD_CDC_ReceivePacket(void *pdev);
128129
/**
129130
* @}
130131
*/

lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -674,7 +674,10 @@ uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum)
674674

675675
/* USB data will be immediately processed, this allow next USB traffic being
676676
NAKed till the end of the application Xfer */
677-
APP_FOPS.pIf_DataRx(USB_Rx_Buffer, USB_Rx_Cnt);
677+
if (APP_FOPS.pIf_DataRx(USB_Rx_Buffer, USB_Rx_Cnt) != USBD_OK)
678+
{
679+
return USBD_OK;
680+
}
678681

679682
/* Prepare Out endpoint to receive next packet */
680683
DCD_EP_PrepareRx(pdev,
@@ -685,6 +688,14 @@ uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum)
685688
return USBD_OK;
686689
}
687690

691+
void USBD_CDC_ReceivePacket(void *pdev)
692+
{
693+
DCD_EP_PrepareRx(pdev,
694+
CDC_OUT_EP,
695+
(uint8_t*)(USB_Rx_Buffer),
696+
CDC_DATA_OUT_PACKET_SIZE);
697+
}
698+
688699
/**
689700
* @brief usbd_audio_SOF
690701
* Start Of Frame event management
@@ -696,7 +707,7 @@ uint8_t usbd_cdc_SOF (void *pdev)
696707
{
697708
static uint32_t FrameCount = 0;
698709

699-
if (FrameCount++ == CDC_IN_FRAME_INTERVAL)
710+
if (FrameCount++ >= CDC_IN_FRAME_INTERVAL)
700711
{
701712
/* Reset the frame counter */
702713
FrameCount = 0;

src/main/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,8 @@ main_sources(COMMON_SRC
8787
drivers/accgyro/accgyro_icm20689.h
8888
drivers/accgyro/accgyro_icm42605.c
8989
drivers/accgyro/accgyro_icm42605.h
90+
drivers/accgyro/accgyro_icm45686.c
91+
drivers/accgyro/accgyro_icm45686.h
9092
drivers/accgyro/accgyro_mpu.c
9193
drivers/accgyro/accgyro_mpu.h
9294
drivers/accgyro/accgyro_mpu6000.c

src/main/blackbox/blackbox.c

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -504,7 +504,7 @@ typedef struct blackboxMainState_s {
504504
int16_t gyroPeaksYaw[DYN_NOTCH_PEAK_COUNT];
505505

506506
int16_t accADC[XYZ_AXIS_COUNT];
507-
int16_t accVib;
507+
uint16_t accVib;
508508
int16_t attitude[XYZ_AXIS_COUNT];
509509
int32_t debug[DEBUG32_VALUE_COUNT];
510510
int16_t motor[MAX_SUPPORTED_MOTORS];
@@ -1642,7 +1642,7 @@ static void loadMainState(timeUs_t currentTimeUs)
16421642
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
16431643
blackboxCurrent->axisPID_F[i] = axisPID_F[i];
16441644
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
1645-
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
1645+
blackboxCurrent->accADC[i] = constrain(lrintf(acc.accADCf[i] * acc.dev.acc_1G), -32678, 32767);
16461646
blackboxCurrent->gyroRaw[i] = lrintf(gyro.gyroRaw[i]);
16471647

16481648
#ifdef USE_DYNAMIC_FILTERS
@@ -1668,7 +1668,8 @@ static void loadMainState(timeUs_t currentTimeUs)
16681668
blackboxCurrent->mcVelAxisOutput[i] = lrintf(nav_pids->vel[i].output_constrained);
16691669
}
16701670
}
1671-
blackboxCurrent->accVib = lrintf(accGetVibrationLevel() * acc.dev.acc_1G);
1671+
1672+
blackboxCurrent->accVib = constrain(lrintf(accGetVibrationLevel() * acc.dev.acc_1G), 0, 65535);
16721673

16731674
if (STATE(FIXED_WING_LEGACY)) {
16741675

0 commit comments

Comments
 (0)