Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
| `batch` | Start or end a batch of commands |
| `battery_profile` | Change battery profile |
| `beeper` | Show/set beeper (buzzer) [usage](Buzzer.md) |
| `bind_msp_rx` | Initiate binding for MSP receivers (mLRS) |
| `bind_rx` | Initiate binding for SRXL2 or CRSF receivers |
| `blackbox` | Configure blackbox fields |
| `bootlog` | Show init logs from [serial_printf_debugging](./development/serial_printf_debugging.md) |
Expand Down
8 changes: 7 additions & 1 deletion docs/Rx.md
Original file line number Diff line number Diff line change
Expand Up @@ -185,14 +185,20 @@ set rssi_channel = 0

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

#### CLI Bind Command
#### CLI Bind Commands

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.

```
bind_rx
```

This command will send a bind request to an MSP receiver on the specified port.

```
bind_msp_rx <port>
```

## MultiWii serial protocol (MSP RX)

Allows you to use MSP commands as the RC input. Up to 18 channels are supported.
Expand Down
42 changes: 42 additions & 0 deletions docs/development/msp/msp_messages.json
Original file line number Diff line number Diff line change
Expand Up @@ -10925,5 +10925,47 @@
"reply": null,
"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.",
"description": "Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2)."
},
"MSP2_RX_BIND": {
"code": 12289,
"mspv": 2,
"request": {
"payload": [
{
"name": "port_id",
"ctype": "uint8_t",
"desc": "Port ID",
"units": ""
},
{
"name": "reserved_for_custom_use",
"ctype": "uint8_t",
"desc": "Reserved for custom use",
"units": "",
"array": true,
"array_size": 3
}
]
},
"reply": {
"payload": [
{
"name": "port_id",
"ctype": "uint8_t",
"desc": "Port ID",
"units": ""
},
{
"name": "reserved_for_custom_use",
"ctype": "uint8_t",
"desc": "Reserved for custom use",
"units": "",
"array": true,
"array_size": 3
}
]
},
"notes": "Requires a receiver using MSP as the protocol, sends MSP2_RX_BIND to the receiver.",
"description": "Initiates binding for MSP receivers (mLRS)."
}
}
20 changes: 19 additions & 1 deletion docs/development/msp/msp_ref.md
Original file line number Diff line number Diff line change
Expand Up @@ -413,7 +413,8 @@ For current generation code, see [documentation project](https://github.com/xznh
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
[8724 - MSP2_INAV_SET_GVAR](#msp2_inav_set_gvar)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
[12289 - MSP2_RX_BIND](#msp2_rx_bind)

## <a id="msp_api_version"></a>`MSP_API_VERSION (1 / 0x1)`
**Description:** Provides the MSP protocol version and the INAV API version.
Expand Down Expand Up @@ -4535,3 +4536,20 @@ For current generation code, see [documentation project](https://github.com/xznh

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

## <a id="msp2_rx_bind"></a>`MSP2_RX_BIND (12289 / 0x3001)`
**Description:** Initiates binding for MSP receivers (mLRS).

**Request Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
| `port_id` | `uint8_t` | 1 | Port ID |
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |

**Reply Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
| `port_id` | `uint8_t` | 1 | Port ID |
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |

**Notes:** Requires a receiver using MSP as the protocol, sends MSP2_RX_BIND to the receiver.

39 changes: 39 additions & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,9 @@ bool cliMode = false;
#include "rx/srxl2.h"
#include "rx/crsf.h"

#include "msp/msp_serial.h"
#include "msp/msp_protocol_v2_common.h"

#include "scheduler/scheduler.h"

#include "sensors/acceleration.h"
Expand Down Expand Up @@ -3600,6 +3603,41 @@ void cliRxBind(char *cmdline){
}
#endif

static void cliBindMspRx(char *cmdline)
{
if (isEmpty(cmdline)) {
cliShowParseError();
return;
}

int portIndex = fastA2I(cmdline);

if (portIndex < 0 || portIndex > 7) {
cliShowArgumentRangeError("port", 0, 7);
return;
}
Comment on lines +3613 to +3618
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestion: Replace fastA2I with strtol to ensure the entire port argument is a valid number, preventing partial parsing of non-numeric input. [possible issue, importance: 6]

Suggested change
int portIndex = fastA2I(cmdline);
if (portIndex < 0 || portIndex > 7) {
cliShowArgumentRangeError("port", 0, 7);
return;
}
char *endptr;
long portIndex = strtol(cmdline, &endptr, 10);
if (endptr == cmdline || *endptr != '\0') {
cliShowParseError();
return;
}
if (portIndex < 0 || portIndex > 7) {
cliShowArgumentRangeError("port", 0, 7);
return;
}


serialPortUsage_t *portUsage = findSerialPortUsageByIdentifier(portIndex);
if (!portUsage || !portUsage->serialPort) {
cliPrintErrorLinef("Serial port %d is not open", portIndex);
return;
}

mspPort_t *mspPort = mspSerialPortFind(portUsage->serialPort);
if (!mspPort) {
cliPrintErrorLinef("Serial port %d is not configured for MSP", portIndex);
return;
}

uint8_t payload[4] = { portIndex, 0, 0, 0 };
int sent = mspSerialPushPort(MSP2_RX_BIND, payload, sizeof(payload), mspPort, MSP_V2_NATIVE); // this is sent as a response
if (sent > 0) {
cliPrintLinef("Sent MSP2_RX_BIND to serial port %d", portIndex);
} else {
cliPrintErrorLinef("Failed to send MSP2_RX_BIND to serial port %d", portIndex);
}
}

static void cliExit(char *cmdline)
{
UNUSED(cmdline);
Expand Down Expand Up @@ -4829,6 +4867,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
"\t<+|->[name]", cliBeeper),
#endif
CLI_COMMAND_DEF("bind_msp_rx", "initiate binding for MSP receivers (mLRS)", "<port>", cliBindMspRx),
#if defined (USE_SERIALRX_SRXL2)
CLI_COMMAND_DEF("bind_rx", "initiate binding for RX SPI or SRXL2", NULL, cliRxBind),
#endif
Expand Down
1 change: 1 addition & 0 deletions src/main/msp/msp_protocol_v2_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,3 +39,4 @@
#define MSP2_COMMON_GET_RADAR_GPS 0x100F //get radar position for other planes

#define MSP2_BETAFLIGHT_BIND 0x3000
#define MSP2_RX_BIND 0x3001