RflyRosCtrlApi Interface Documentation¶
Introduction¶
Overview: This file provides API interfaces for communication between the RflySim simulation environment and drone ROS control nodes. It supports configuring communication parameters based on aircraft ID, enabling controlled data exchange with the corresponding drone.
In RflySim drone simulation development scenarios, many developers implement custom control algorithms—such as autonomous navigation and visual perception—based on the ROS framework. These algorithms require the transmission of generated control commands to the PX4 simulation flight controller. This module is part of the RflySimSDK’s visual toolchain’s communication interfaces, designed for multi-drone simulation scenarios. Developers can automatically configure the corresponding communication ports based on aircraft ID, quickly establishing data transmission channels between custom ROS control nodes and the simulated flight controller. It is suitable for development scenarios requiring third-party ROS control node integration with the simulation platform, such as multi-robot coordination and visual navigation control.
Quick Start¶
A minimal runnable example; copy and modify only the necessary configurations to run.
from RflySimSDK.vision.RflyRosCtrlApi import RflyRosCtrlApi
# 1. Initialize the ROS control API; by default, connects to the local simulation environment with aircraft ID 1
ros_ctrl = RflyRosCtrlApi(CopterID=1, ip="127.0.0.1", Com="udp")
# 2. Arm the drone
ros_ctrl.arm_px4(isArm=True)
print("Drone armed")
# Example usage: Add subsequent control code here, such as takeoff or waypoint following
# 3. To disarm the drone, call the following code:
# ros_ctrl.arm_px4(isArm=False)
# print("Drone disarmed")
Environment and Dependencies¶
- Python Environment:
>= 3.8.10 - Dependencies:
ctrl.IpManager,geometry_msgs.msg,math,mavros_msgs.msg,mavros_msgs.srv,numpy,os,platform,pymavlink,pymavlink.dialects.v20,sensor_msgs.msg,socket,std_msgs.msg,struct,subprocess,sys,threading,time - Prerequisites: Before calling this interface, ensure the ROS runtime environment is properly configured and RflySimSDK is correctly installed.
Core Interface Description¶
The module RflyRosCtrlApi.py includes configuration variables, helper functions, and the core business class.
Global Constants and Enumerations¶
This section lists all globally accessible constants and enumerations defined in the module.
Standalone Constants¶
None
Global/Standalone Functions¶
None
fifo Class¶
A First-In-First-Out (FIFO) queue used to buffer and transfer data in the RflySim simulation environment, commonly used in asynchronous data transmission and reception scenarios within the vision module.
__init__()¶
Function Description: Initializes an empty FIFO queue
Parameters (Args):
None
Returns:
fifoinstance object
Exceptions (Raises):
None
write(data)¶
Function Description: Writes data to the end of the FIFO queue
Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
data |
Any |
Yes | - | Data to be written into the queue |
Returns:
- None
Exceptions (Raises):
None
read()¶
Function Description: Reads and removes the earliest-written data from the head of the FIFO queue
Parameters (Args):
None
Returns:
Any: Data at the head of the queue
Exceptions (Raises):
None
Example:
```python from RflySimSDK.vision import fifo
Initialize FIFO queue¶
f = fifo()
Write data¶
f.write("simulation image data")
Read data¶
data = f.read()
RflyRosCtrlApi Class¶
A communication API for PX4 flight controller control in ROS environments, enabling the creation of communication connections with the flight controller. It supports two connection modes: UDP network communication and direct serial port connection.
__init__(self, CopterID=1, ip="127.0.0.1", Com="udp", port=0)¶
Function Description: Initializes an RflyRosCtrlApi communication instance and establishes a connection to the PX4 flight controller based on provided parameters. Automatically handles port and baudrate mapping rules.
Parameters (Args):
| Parameter Name | Type | Default Value | Description |
|---|---|---|---|
| CopterID | int | 1 | Aircraft ID number; the default port is automatically calculated based on this ID according to platform rules. |
| ip | str | "127.0.0.1" | Target IP address for UDP data transmission. By default, data is sent to localhost (127.0.0.1); for distributed simulation, specify a LAN IP or use the broadcast address 255.255.255.255. |
| Com | str | "udp" | Connection mode to the Pixhawk flight controller: udp indicates UDP network mode, receiving MAVLink messages forwarded by CopterSim; on Windows, specify COMx (e.g., COM3); on Linux, specify /dev/ttyXXX (e.g., /dev/ttyUSB0) for serial port connection mode. |
| port | int | 0 | In UDP mode, if set to a value greater than 0, this port is forced; if 0, the port is automatically calculated using the rule: port = 20100 + CopterID * 2 - 2. In serial port mode, this specifies the baudrate; if 0, the default baudrate of 57600 is used. |
Returns: None
Raises: None
convert_to_payload64(payload_bytes)¶
Function Description: Converts the input payload byte array into Mavlink.payload64 format.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| payload_bytes | Any | Yes | N/A | Raw payload byte data to be converted. |
Returns: Mavlink.payload64 formatted data after conversion.
Raises: None
convert_to_rosmsg(mavmsg, header)¶
Function Description: Converts a pymavlink message into Mavlink.msg ROS message format. Currently supports only MAVLink v1.0.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| mavmsg | Any | Yes | N/A | Input pymavlink-formatted message. |
| header | Any | Yes | N/A | ROS message header information used to populate the output ROS message. |
Returns: Mavlink.msg formatted ROS message after conversion.
Raises: None
arm_px4(isArm)¶
Function Description: Arms or disarms the PX4 drone.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| isArm | bool | Yes | N/A | True to arm, False to disarm. |
Returns: None
Raises: None
fillList(data, inLen, fill=0)¶
Function Description: Pads the input list to a specified length using a given fill value.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| data | list | Yes | N/A | Original list to be padded. |
| inLen | int | Yes | N/A | Desired length of the output list. |
| fill | Any | No | 0 | Value used to fill empty positions. |
Returns: A list of length inLen after padding.
Raises: None
InitMavLoop()¶
Function Description: Initializes the MAVLink message processing loop thread for continuous MAVLink communication handling.
Parameters (Args): None
Returns: None
Raises: None
SendMavArm(isArm)¶
Function Description: Sends a MAVLink arm/disarm command to the flight controller.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| isArm | bool | Yes | N/A | True to send an arm command, False to send a disarm command. |
Returns: None
Raises: None
initOffboard()¶
Function Description: Initializes Offboard mode, preparing to send offboard control commands.
Parameters (Args): None
Returns: None
Raises: None
OffboardLoop()¶
Function Description: Starts the offboard control loop to continuously send offboard control commands and maintain the mode.
Parameters (Args): None
Returns: None
Raises: None
endOffboard()¶
Function Description: Ends Offboard mode and stops the offboard control loop.
Parameters (Args): None
Returns: None
Raises: None
stopRun()¶
Function Description: Stops all background running threads and terminates control loops.
Parameters (Args): None
Returns: None
Raises: None
calcTypeMask(EnList)¶
Function Description: Calculates the type mask for a MAVLink message based on the enabled fields list.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| EnList | list[bool] | Yes | N/A | List indicating the enable status of each control field; True means the corresponding field is valid. |
Returns: The computed 16-bit type mask integer
Raises: None
SendVelNED(vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan)¶
Description: Sends a velocity control command in the NED coordinate frame
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| vx | float | No | math.nan | Velocity in the North direction of the NED frame, in m/s; nan indicates this axis is not controlled |
| vy | float | No | math.nan | Velocity in the East direction of the NED frame, in m/s; nan indicates this axis is not controlled |
| vz | float | No | math.nan | Velocity in the Down direction of the NED frame, in m/s; nan indicates this axis is not controlled |
| yawrate | float | No | math.nan | Yaw angular velocity, in rad/s; nan indicates it is not controlled |
Returns: None
Raises: None
SendVelFRD(vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan)¶
Description: Sends a velocity control command in the body-fixed FRD coordinate frame
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| vx | float | No | math.nan | Velocity in the Forward direction of the FRD frame, in m/s; nan indicates this axis is not controlled |
| vy | float | No | math.nan | Velocity in the Right direction of the FRD frame, in m/s; nan indicates this axis is not controlled |
| vz | float | No | math.nan | Velocity in the Down direction of the FRD frame, in m/s; nan indicates this axis is not controlled |
| yawrate | float | No | math.nan | Yaw angular velocity, in rad/s; nan indicates it is not controlled |
Returns: None
Raises: None
SendPosNED(x=math.nan, y=math.nan, z=math.nan, yaw=math.nan)¶
Description: Sends a position control command in the NED coordinate frame
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| x | float | No | math.nan | Position in the North direction of the NED frame, in meters; nan indicates this axis is not controlled |
| y | float | No | math.nan | Position in the East direction of the NED frame, in meters; nan indicates this axis is not controlled |
| z | float | No | math.nan | Position in the Down direction of the NED frame, in meters; nan indicates this axis is not controlled |
| yaw | float | No | math.nan | Yaw angle, in radians; nan indicates it is not controlled |
Returns: None
Raises: None
SendPosVelNED(PosE=[math.nan] * 3, VelE=[math.nan] * 3, yaw=math.nan, yawrate=math.nan)¶
Description: Sends a combined position-velocity control command in the NED coordinate frame
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| PosE | list[float] | No | [math.nan] * 3 | Array of positions in the North, East, and Down directions of the NED frame, in meters; nan elements indicate the corresponding axes are not controlled |
| VelE | list[float] | No | [math.nan] * 3 | Array of velocities in the North, East, and Down directions of the NED frame, in m/s; nan elements indicate the corresponding axes are not controlled |
| yaw | float | No | math.nan | Yaw angle, in radians; nan indicates it is not controlled |
| yawrate | float | No | math.nan | Yaw angular velocity, in rad/s; nan indicates it is not controlled |
Returns: None
Raises: None
local_pose_callback(msg)¶
Description: ROS callback function for the local position topic; receives and stores the drone’s local pose information
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| msg | Any | Yes | None | ROS message object from the local position topic, containing the drone’s pose information |
Returns: None
Raises: None
local_vel_callback(msg)¶
Description: ROS callback function for the local velocity topic; receives and stores the drone’s local velocity information
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| msg | Any | Yes | None | ROS message object from the local velocity topic, containing the drone’s linear velocity information |
Returns: None
Raises: None
mavros_state_callback(msg)¶
Description: ROS callback function for the mavros state topic; receives and stores the connection and flight mode status of the PX4 flight controller
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| msg | Any | Yes | None | ROS message object from the mavros state topic, containing the flight controller’s status information |
Returns: None
Raises: None
imu_callback(msg)¶
Description: ROS callback function for the IMU topic; receives and stores IMU sensor data including attitude, angular velocity, and linear acceleration
Arguments (Args):
| Parameter | Type | Required | Default | Description |
|---|---|---|---|---|
| msg | Any | Yes | None | ROS message object from the IMU topic, containing IMU measurement data |
Returns: None
Raises: None
gps_callback(msg)¶
Description: ROS GPS topic callback function, used to receive and store GPS positioning information.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| msg | Any | Yes | None | ROS GPS topic message object, containing GPS positioning measurement data |
Returns: None
Raises: None
q2yaw(q)¶
Description: Converts a quaternion to yaw angle.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| q | Any | Yes | None | Input quaternion, containing attitude rotation information |
Returns: float, the converted yaw angle (in radians)
Raises: None
q2Euler(q)¶
Description: Converts a quaternion to roll, pitch, and yaw Euler angles.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| q | Any | Yes | None | Input quaternion, containing attitude rotation information |
Returns: tuple(float, float, float), the converted roll, pitch, and yaw Euler angles (in radians)
Raises: None
SendMavArm(isArm=0)¶
Description: Sends PX4 arm/disarm command to the flight controller.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| isArm | Any | No | 0 | 1 indicates arming the drone; 0 indicates disarming the drone |
Returns: None
Raises: None
arm()¶
Description: Convenience interface to send a drone arming command.
Args: None
Returns: None
Raises: None
disarm()¶
Description: Convenience interface to send a drone disarming command.
Args: None
Returns: None
Raises: None
offboard()¶
Description: Switches the PX4 flight controller to offboard control mode.
Args: None
Returns: None
Raises: None
yawSat(yaw)¶
Description: Limits the yaw angle to the range [-π, π] (in radians).
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| yaw | float | Yes | None | Input yaw angle to be saturated (in radians) |
Returns: float, the yaw angle constrained to the [-π, π] range
Raises: None
sendMavSetParam(param_id_str, param_value, param_type)¶
Description: Sends a parameter setting command to modify a parameter value on the PX4 flight controller.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| param_id_str | str | Yes | None | Name string of the PX4 flight controller parameter |
| param_value | float | Yes | None | Target value to set for the parameter |
| param_type | Any | Yes | None | Type of the flight controller parameter |
Returns: None
Raises: None
SendMavCmdLong(command, param1=0, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0)¶
Description: Sends a MAVLink long command to the PX4 flight controller.
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| command | int | Yes | None | MAVLink command ID, corresponding to a specific control command |
| param1 | float | No | 0 | MAVLink command parameter 1 |
| param2 | float | No | 0 | MAVLink command parameter 2 |
| param3 | float | No | 0 | MAVLink command parameter 3 |
| param4 | float | No | 0 | MAVLink command parameter 4 |
| param5 | float | No | 0 | MAVLink command parameter 5 |
| param6 | float | No | 0 | MAVLink command parameter 6 |
| param7 | float | No | 0 | MAVLink command parameter 7 |
Returns: None
Raises: None
SendHILCtrlMsg(ctrls=[0] * 16, idx=0)¶
Description: Sends HIL actuator control commands to PX4. This command is converted into the PX4 uORB message rfly_ctrl for external control input injection. Refer to the MAVLink documentation: https://mavlink.io/en/messages/common.html#HIL_ACTUATOR_CONTROLS
Args:
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
| ctrls | list | No | [0] * 16 | 16-dimensional control vector array, corresponding to actuator output control values |
| idx | int | No | 0 | Control group index, identifying the current control group number being sent |
Returns: None
Raises: None
Advanced Usage Examples¶
Demonstrates complex composite scenarios (e.g., multi-vehicle collaboration, asynchronous control, batch operations)
```python import RflySimSDK.vision as rv from threading import Thread import time
Batch offline waypoint preloading + asynchronous offboard control: advanced multi-vehicle collaboration example¶
def uav_offboard_task(uav_id, waypoints, frame_buffer): # Initialize PX4 offboard control loop ros_api = rv.RflyRosCtrlApi() ros_api.InitMavLoop(uav_id) ros_api.initOffboard(uav_id) # Batch-fill waypoints ros_api.fillList(uav_id, waypoints) # Arm the UAV ros_api.arm_px4(uav_id) ros_api.SendMavArm(uav_id, True) # Asynchronously read visual frames for obstacle avoidance adjustments while True: if not frame_buffer.read(): continue obstacle_info = frame_buffer.read() if obstacle_info is None: break # Adjust waypoints based on obstacle_info and re-enter offboard loop ros_api.OffboardLoop(uav_id, 1) time.sleep(0.1) # Exit offboard mode ros_api.endOffboard(uav_id) ros_api.stopRun(uav_id)
Initialize shared vision frame buffer (FIFO) for multi-task coordination¶
vision_frame_buf = rv.fifo()
Define initial waypoints for three UAVs in batch¶
uav_waypoints = [ [(0,0,1), (0,1,1), (1,1,1)], [(0,0,2), (1,0,2), (1,1,2)], [(0,0,1.5), (-1,0,1.5), (-1,-1,1.5)] ]
Launch multi-vehicle collaborative tasks asynchronously via multi-threading¶
threads = [] for idx, wps in enumerate(uav_waypoints): t = Thread(target=uav_offboard_task, args=(idx+1, wps, vision_frame_buf)) t.start() threads.append(t)
Notes and Pitfall Avoidance Guide¶
- Mav Loop Initialization Order:
InitMavLoopmust be called first to initialize the flight controller communication link before invoking other methods such as arming or offboard control; otherwise, commands may become unresponsive. - FIFO Thread Safety Limitation: The
fifoclass only provides basic read/write buffering functionality. Manual mutex locking is required during concurrent multi-threaded read/write operations to prevent data corruption or cache inconsistencies. - Offboard Mode Exit Requirement: After completing offboard tasks,
endOffboardmust be explicitly called; otherwise, the flight controller will remain in offboard mode indefinitely and fail to respond to subsequent manual or autonomous control commands. - Batch Waypoint Filling Parameter Requirements: When calling
fillListto batch-write waypoints, ensure the input waypoint list format matches the method’s requirements. The number of waypoints per drone per call must not exceed the flight controller’s buffer capacity; otherwise, waypoints may be lost.
Changelog¶
2026-03-03: feat: SDK adds IP handling mechanism for compatibility with cloud-deployed versions derived from local deployments.2025-03-31: fix: Resolves issue where offboard mode fails to initiate takeoff in versions after 1.13.2024-08-05: fix: Adds HTML-formatted API documentation.2024-07-17: fix: UpdatesVisionCaptureApiinterface.2024-06-05: fix: Updates ROS interface.2024-06-04: fix: Updates library files.2024-05-27: fix: Adds multi-vehicle control framework compatible with both ROS1 and ROS2.2024-05-26: fix: Adds compatibility for ROS1/ROS2 multi-node setups.2024-05-26: fix: Addresses several known issues.2024-05-25: fix: Adds ROS2 multi-vehicle compatibility.2024-05-25: fix: Adds comments.2024-05-25: Adds ROS2 compatibility and introduces interfaces for communication with the underlying flight controller.2024-05-22: fix: Adds an interface for MAVROS-based control.