mavRflyShell Interface Documentation¶
Introduction¶
Overview: This file implements a shell interaction feature on the drone side based on the MAVLink protocol, enabling access to the drone-side command-line shell via serial port connection.
This module belongs to the RflySimSDK cluster tools module and provides a channel for accessing the drone flight controller’s command-line shell from the ground station side. It supports transparent transmission of shell commands and flight controller response data through the MAVLink protocol.
This module is suitable for scenarios requiring remote debugging of the flight controller in simulation environments, executing custom commands on the flight controller side, and viewing flight controller runtime status logs. It helps developers quickly verify flight controller configurations and troubleshoot flight controller-side issues in cluster simulations. The ConnectNsh function enables rapid connection establishment, while the core MavRflyShell class integrates MAVLink communication and shell interaction logic, supporting stable command sending and receiving interactions.
Quick Start¶
Minimal runnable example; copy and modify minimal configuration to run.
from RflySimSDK.swarm import mavRflyShell
# Initialize MavRflyShell instance
mav_shell = mavRflyShell.MavRflyShell()
# 1. Get PX4 serial communication object
px4_com = mav_shell.getPX4Com()
print(f"Obtained PX4 serial object: {px4_com}")
# 2. Get local IP address
local_ip = mav_shell.getLocalIp()
print(f"Local IP address: {local_ip}")
# 3. Check whether the IP complies with RflySim drone networking specifications (starting with 192.168.151)
if local_ip:
is_valid = mav_shell.validate_ip(local_ip)
print(f"Is current IP compliant with networking specifications? {is_valid}")
else:
# Example: manually test custom IP validation
test_ip = "192.168.151.100"
is_valid_test = mav_shell.validate_ip(test_ip)
print(f"Is test IP {test_ip} compliant with specifications? {is_valid_test}")
Environment and Dependencies¶
- Python Environment:
>= 3.8.10 - Dependencies:
__future__,argparse,io,json,os,re,socket,subprocess,sys,time,timeit - Prerequisites: Before calling this interface, ensure that the MAVLink connection is ready and communication can be established.
Core Interface Description¶
The module mavRflyShell.py includes configuration variables, helper functions, and the core business class.
Global Constants and Enumerations¶
This section lists all globally accessible constants and enumeration definitions that can be directly referenced in the module.
Standalone Constants¶
None
Global/Standalone Functions¶
ConnectNsh()¶
Function Description: Connects to the NSH console of the PX4 simulation environment to enable command-line interaction control of the PX4 flight controller.
Parameters:
None
Return Value:
None
Exceptions:
None
MavlinkSerialPort Class¶
Implements serial port communication for the MAVLink protocol, supporting serial data reading/writing and debug output. Suitable for serial communication scenarios between drones and ground stations or external devices in RflySim.
__init__(portname, baudrate, devnum=0, debug=0)¶
Function Description: Initializes a Mavlink serial port object, opens the specified serial port, and configures communication parameters.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
portname |
Yes | - | Serial port name, specifying the serial device to open | |
baudrate |
Yes | - | Serial port baud rate, configuring the communication speed | |
devnum |
No | 0 |
Device number, used to distinguish between multiple serial port devices | |
debug |
No | 0 |
Debug switch; debug output is enabled when non-zero |
Return Value (Returns):
MavlinkSerialPortinstance object
Exceptions (Raises): None
debug(s, level=1)¶
Function Description: Writes debug text and outputs debug information based on the debug level and initialization configuration.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
s |
str |
Yes | - | Debug text content to output |
level |
int |
No | 1 |
Debug level; output occurs only when the level is greater than or equal to the initialized level |
Return Value (Returns):
- None
Exceptions (Raises): None
write(b)¶
Function Description: Writes byte data to the serial port, sending MAVLink or other binary data formats.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
b |
bytes |
Yes | - | Byte data to write to the serial port |
Return Value (Returns):
- None
Exceptions (Raises): None
close()¶
Function Description: Closes the currently opened serial port and releases serial port resources.
Return Value (Returns):
- None
Exceptions (Raises): None
read(n)¶
Function Description: Reads a specified number of bytes from the serial port.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
n |
int |
Yes | - | Number of bytes to read |
Return Value (Returns):
bytes: Byte data read from the serial port
Exceptions (Raises): None
Example:
# Initialize and open serial port
serial_port = MavlinkSerialPort("COM3", 115200, debug=1)
# Write byte data
data = bytes([0x01, 0x03, 0x00])
serial_port.write(data)
# Read returned data
recv_data = serial_port.read(10)
# Close serial port
serial_port.close()
---
### `RflyShell` Class
PX4 flight controller NuttX shell serial port interaction class, used to send commands, modify parameters, and reboot the PX4 flight controller via serial port, suitable for flight controller terminal control in RflySim simulation cluster scenarios.
#### `__init__(port, baudrate=115200)`
**Function Description**: Initialize the RflyShell serial port connection object.
**Parameters (Args)**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `port` | `str` | Yes | - | Serial port device name/port number, e.g., `COMx` on Windows, `/dev/ttyUSBx` on Linux |
| `baudrate` | `int` | No | `115200` | Serial communication baud rate; PX4 default baud rate is 115200 |
**Return Value (Returns)**:
- `RflyShell` instance object
**Exceptions (Raises)**:
- None
---
#### `is_prompt(data)`
**Function Description**: Check whether the received serial port data contains a complete shell prompt, used to determine if command output is complete.
**Parameters (Args)**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `data` | `bytes` | Yes | - | Raw byte data read from the serial port |
**Return Value (Returns)**:
- `bool`: Returns `True` if a complete prompt is found, otherwise returns `False`
**Exceptions (Raises)**:
- None
---
#### `SendCmdNsh(cmd)`
**Function Description**: Send a NuttX shell command to the PX4 flight controller and wait for the output response.
**Parameters (Args)**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `cmd` | `str` | Yes | - | NuttX shell command string to be sent |
**Return Value (Returns)**:
- `str`: Output string returned after command execution
**Exceptions (Raises)**:
- None
**Example**:
```python
from RflySimSDK.swarm import RflyShell
shell = RflyShell("COM3", 115200)
output = shell.SendCmdNsh("help")
print(output)
SendUpdateParam(ParamKey, ParamValue)¶
Function Description: Update a PX4 flight controller parameter value to the flight controller.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
ParamKey |
str |
Yes | - | Name of the PX4 parameter to be modified |
ParamValue |
int/float |
Yes | - | New value to be set for the parameter |
Return Value (Returns):
- None
Exceptions (Raises):
- None
SendCommitParam()¶
Function Description: Commit all modified PX4 parameters, saving the changes to the flight controller's flash memory.
Return Value (Returns):
- None
Exceptions (Raises):
- None
SendChangeParam(ParamKey, ParamValue)¶
Function Description: Modify and commit a single PX4 flight controller parameter, combining update and commit operations.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
ParamKey |
str |
Yes | - | Name of the PX4 parameter to be modified |
ParamValue |
int/float |
Yes | - | New value to be set for the parameter |
Return Value (Returns):
- None
Exceptions (Raises):
- None
Example:
shell = RflyShell("COM3", 115200)
# Modify PX4 firmware ID, corresponding to different aircraft models
shell.SendChangeParam("SYS_AUTOSTART", 4001)
SendShowParam(ParamKey)¶
Function Description: Query the current value of a specified PX4 flight controller parameter.
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
ParamKey |
str |
Yes | - | Name of the PX4 parameter to be queried |
Return Value (Returns):
str: Parameter query result string
Exceptions (Raises): - None
SendRebootPX4()¶
Function Description: Send a command to reboot the PX4 flight controller.
Return Value (Returns):
- None
Exceptions (Raises):
- None
Example:
shell = RflyShell("COM3", 115200)
shell.SendRebootPX4()
---
#### `SendClose()`
**Function Description**: Closes the serial port connection and releases resources.
**Returns**:
None
**Raises**:
None
---
#### `SendCmdNshS(ParamKey)`
**Function Description**: Sends a specified NuttX shell command without additional output or return.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `ParamKey` | `str` | Yes | - | NuttX shell command string to be sent |
**Returns**:
None
**Raises**:
None
---
#### `SendAirframe()`
**Function Description**: Sends a command to view the current airframe configuration.
**Returns**:
None
**Raises**:
None
---
### `MavRflyShell` Class
Manages serial communication, IP address configuration, and device detection for PX4 UAV flight controllers, supporting flight controller network and serial parameter configuration in multi-UAV networking scenarios.
---
#### `getPX4Com()`
**Function Description**: Retrieves the serial port device corresponding to the PX4 flight controller.
**Args**:
None
**Returns**:
- `str`: Path of the available PX4 flight controller serial port
**Raises**:
None
---
#### `getLocalIp()`
**Function Description**: Retrieves the local LAN IP address of the host machine.
**Args**:
None
**Returns**:
- `str`: Local LAN IP address as a string
**Raises**:
None
---
#### `validate_ip(ip)`
**Function Description**: Checks whether the IP address starts with `192.168.151`.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `ip` | `str` | Yes | - | IP address string to be validated |
**Returns**:
- `bool`: `True` if the format matches, otherwise `False`
**Raises**:
None
---
#### `auto_configure_ip(targetID)`
**Function Description**: Automatically configures the IP address of the flight controller.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `targetID` | `int` | Yes | - | Target flight controller ID to configure IP for |
**Returns**:
None
**Raises**:
None
---
#### `setSysIDIP(com, airplane_id, baud="921600", is_last=False)`
**Function Description**: Sets the system ID and corresponding IP address of the flight controller via serial port.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `com` | `str` | Yes | - | Target serial port device path |
| `airplane_id` | `int` | Yes | - | UAV system ID to be set |
| `baud` | `int` | No | `921600` | Serial communication baud rate |
| `is_last` | `bool` | No | `False` | Indicates whether this is the last UAV to be configured |
**Returns**:
None
**Raises**:
None
---
#### `monitorSerialPorts(com)`
**Function Description**: Monitors the connection status of a specified serial port.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `com` | `str` | Yes | - | Serial port device path to monitor |
**Returns**:
None
**Raises**:
None
---
#### `checkSerialAvailable(com)`
**Function Description**: Checks whether the current serial port is still available.
**Args**:
| Parameter Name | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `com` | `str` | Yes | - | Serial port device path to check |
**Returns**:
- `bool`: `True` if the serial port is available, otherwise `False`
**Raises**:
None
---
#### `getAvailableSerialPorts()`
**Function Description**: Retrieves the list of available serial ports on the current system.
**Args**:
None
**Returns**:
- `list[str]`: List of paths of all available serial port devices
**Raises**:
None
---
#### `waitForNewDevice()`
**Function Description**: Waits for the user to insert a new flight controller device.
**Args**:
None
**Returns**:
- `str`: Serial port path of the newly inserted device
**Raises**:
None
**Example**:
```python
from RflySimSDK.swarm import MavRflyShell
shell = MavRflyShell()
# Get all available serial ports
ports = shell.getAvailableSerialPorts()
# Wait for a new device to be inserted
new_port = shell.waitForNewDevice()
---
#### `check_udp_data(port)`
**Function Description**: Reads data from a specified UDP port
**Arguments (Args)**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `port` | `int` | Yes | - | UDP port number from which to read data |
**Returns**:
- `bytes`: Data read from the UDP port
**Raises**:
- None
---
#### `connect_to_device(port, baud)`
**Function Description**: Connects to a flight controller device on a specified serial port
**Arguments (Args)**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `port` | `str` | Yes | - | Serial port path where the flight controller device is connected |
| `baud` | `int` | Yes | - | Baud rate for serial communication |
**Returns**:
- `object`: Device object upon successful connection
**Raises**:
- None
---
#### `query_mav_sys_id(rflyShell, sys_id)`
**Function Description**: Queries MAVLink device information for a specified system ID
**Arguments (Args)**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `rflyShell` | `object` | Yes | - | Instance of `MavRflyShell` |
| `sys_id` | `int` | Yes | - | MAVLink system ID to query |
**Returns**:
- `dict`: Device information retrieved from the query
**Raises**:
- None
**Example**:
```python
from RflySimSDK.swarm import MavRflyShell
shell = MavRflyShell()
# Automatically configure the IP for flight controller ID 1
shell.auto_configure_ip(targetID=1)
# Configure flight controller ID and corresponding IP
shell.setSysIDIP("COM3", airplane_id=1, baud=921600)
Advanced Usage Examples¶
Demonstrates complex composite scenarios (e.g., multi-device collaboration, asynchronous control, batch operations)
```python import RflySimSDK.swarm as rfly_swarm import time from concurrent.futures import ThreadPoolExecutor
Advanced scenario: Batch parameter configuration + asynchronous reboot for multiple drones¶
1. Initialize serial ports and RflyShell instances, scanning all available serial ports¶
available_ports = rfly_swarm.MavRflyShell.getAvailableSerialPorts() mav_shell_list = [] for port in available_ports: if rfly_swarm.MavRflyShell.checkSerialAvailable(port): serial_port = rfly_swarm.MavlinkSerialPort(port, 57600) mav_shell = rfly_swarm.RflyShell(serial_port) mav_shell_list.append(mav_shell)
2. Asynchronously batch-modify PX4 parameters for collaborative multi-drone configuration¶
def config_single_drone(mav_shell, param_list): for param_name, param_val in param_list: mav_shell.SendChangeParam(param_name, param_val) time.sleep(0.1) mav_shell.SendCommitParam() return mav_shell.SendRebootPX4()
Assign distinct PID parameter configurations to each drone¶
param_configs = [ [("MC_PITCH_P", 0.18), ("MC_ROLL_P", 0.18)], [("MC_PITCH_P", 0.2), ("MC_ROLL_P", 0.2)], [("MC_PITCH_P", 0.15), ("MC_ROLL_P", 0.15)] ]
Asynchronously execute configuration tasks in parallel to improve multi-drone debugging efficiency¶
with ThreadPoolExecutor(max_workers=len(mav_shell_list)) as executor: results = executor.map(lambda args: config_single_drone(*args), zip(mav_shell_list, param_configs))
3. Verify configuration results¶
for res, mav_shell in zip(results, mav_shell_list): if res: print("Single drone parameter configuration and reboot succeeded") # Close connection and release resources mav_shell.SendClose() mav_shell._serial.close()
Notes and Pitfall Avoidance Guide¶
- Parameter Modification Submission Timeliness: After calling
SendChangeParamto batch-modify multiple parameters,SendCommitParammust be invoked to write the modifications into the PX4 flight control firmware; otherwise, uncommitted parameter changes will be lost upon flight control reboot. - Serial Port Resource Concurrency Limitation: A single serial port cannot be simultaneously opened by multiple
MavlinkSerialPortinstances. After batch-scanning available serial ports, theclosemethod must be promptly called to release resources of unavailable ports, preventing subsequent device connection detection failures. - IP Address Format Validation Requirement: Before calling
setSysIDIPto bind the flight control system ID with an IP address, the IP format must first be validated using thevalidate_ipmethod. An invalid IP will cause UDP communication link establishment to fail, without actively throwing an explicit error. - Command Sending Inter-Command Interval: When consecutively calling
SendCmdNshto send NSH commands, a minimum interval of 100 ms must be reserved between commands to allow the flight control to respond. Rapid consecutive sending will result in command packet loss, with the flight control executing only the last received command.
Changelog¶
2024-12-10: fix: Update API documentation page2024-12-10: fix: Update cluster control interface comments2024-09-06: fix: Add HIL firmware flashing support for new airframe types2024-09-04: fix: 1. Add UDP validation function; 2. Add error handling and retry mechanism; 3. Fix bug wheremav_idparameter cannot be found after flight control reboot; 4. Fix bug where configuration proceeds despite prior completion2024-09-03: fix: Add IP validation, serial port detection, and message delay2024-09-03: fix: Add IP validation, serial port detection, and message delay2024-09-03: fix: Add IP validation, serial port detection, and message delay2024-08-26: fix: Update苏晓MavRflyShell2024-08-16: fix: Upgrade shell library2024-08-16: fix: Add initial flight control parameter configuration interface