DllSimCtrlAPIROS Interface Documentation¶
Introduction¶
Overview: Provides a ROS bridge communication class based on UDP, enabling bidirectional data exchange of drone control information between the RflySim simulation platform and the ROS system.
In drone simulation development based on RflySim, many developers integrate ROS-based tools to implement upper-layer algorithms such as path planning, visual perception, and autonomous decision-making. This module establishes the data communication channel between the RflySim simulation kernel and the ROS environment. The UdpRosBridge class achieves low-latency data transmission across processes or even devices via the UDP protocol, supporting bidirectional forwarding of simulation data—including drone states and control commands—between the RflySim simulation core and ROS nodes. It is suitable for scenarios involving ROS-based drone simulation algorithm development and co-simulation testing.
Quick Start¶
Minimal runnable example; copy and modify minimal configuration to run.
import rospy
from RflySimSDK.ctrl import UdpRosBridge
if __name__ == "__main__":
# Initialize ROS node
rospy.init_node("rflysim_udp_bridge_node")
# Initialize UdpRosBridge with default configuration: Copter ID 1, local UDP address, ROS node using the currently initialized node.
# Automatically assigns listening port as 30100 + 1*2 - 1 = 30101, and sending port as 30100 + (1-1)*2 = 30100.
udp_bridge = UdpRosBridge(copter_id=1, target_ip="127.0.0.1", ros_node=rospy)
# Start UDP listening thread and ROS communication
udp_bridge.start()
# Keep node running until ROS shutdown signal is received
try:
rospy.spin()
except KeyboardInterrupt:
print("Shutdown signal received, preparing to exit.")
finally:
# Stop threads and clean up resources
udp_bridge.stop()
Environment and Dependencies¶
- Python Environment:
>= 3.8.10 - Dependencies:
DllSimCtrlAPI,ctrl.IpManager,errno,logging,math,socket,struct,sys,threading,time - Prerequisites: Before calling this interface, ensure the RflySimSDK environment is correctly configured and the corresponding dynamic-link library can be invoked successfully.
Core Interface Description¶
The module DllSimCtrlAPIROS.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¶
| Variable Name | Type | Value | Description |
|---|---|---|---|
ROS1 |
bool |
False |
- |
ROS2 |
bool |
False |
- |
Global / Standalone Functions¶
None
UdpRosBridge Class¶
UDP communication bridge between RflySim simulation and ROS, enabling bidirectional forwarding of drone simulation data and ROS commands. Automatically assigns communication ports based on drone ID; upon initialization, it creates ROS communication objects (publishers, subscribers, services) and prepares UDP port listening.
__init__(copter_id=1, target_ip=127.0.0.1, ros_node=None)¶
Function Description: Initializes UDP communication ports, creates ROS-related publishers, subscribers, and services, and starts the UDP data listening thread. The local listening port and remote sending port are automatically calculated based on the provided drone ID. Parameters (Args):
| Parameter Name | Type | Required | Default | Description |
|---|---|---|---|---|
copter_id |
int |
No | 1 |
Drone ID used to automatically compute UDP communication ports: listening port = 30100 + id*2 - 1, sending port = 30100 + (id-1)*2 |
target_ip |
str |
No | 127.0.0.1 |
Target IP address for UDP data transmission; defaults to localhost |
ros_node |
rospy.NodeHandle |
No | None |
ROS node handle; if provided, communication objects are created using this node; otherwise, the default ROS node is used |
Return Value (Returns):
- Instance of
UdpRosBridge
Exceptions (Raises):
- None
start()¶
Function Description: Starts the UDP bridge communication thread, beginning reception of simulation data and forwarding it to ROS, while simultaneously receiving ROS commands and forwarding them to the simulation. Parameters (Args): - None Return Value (Returns):
- None
Exceptions (Raises):
- None
Example:
from RflySimSDK.ctrl import UdpRosBridge
# Create UDP communication bridge for copter ID 1
bridge = UdpRosBridge(copter_id=1)
# Start communication
bridge.start()
stop()¶
Function Description: Stops all UDP listening and data forwarding threads, and cleans up occupied communication resources. Parameters (Args): - None Return Value (Returns):
- None
Exceptions (Raises):
- None
Example:
from RflySimSDK.ctrl import UdpRosBridge
bridge = UdpRosBridge()
bridge.start()
# Stop and clean up resources when ending communication
bridge.stop()
---
## Advanced Usage Examples
> Demonstrates complex composite scenarios (e.g., multi-unit collaboration, asynchronous control, batch operations)
```python
import asyncio
from RflySimSDK.ctrl import UdpRosBridge
# Multi-link asynchronous collaboration scenario: Simultaneously start multiple UAV simulation communication bridges to enable heterogeneous task collaboration
async def start_multi_bridge(bridge_configs):
bridge_list = []
# Batch initialize and start multiple UDP communication bridge instances
for config in bridge_configs:
bridge = UdpRosBridge(config['local_port'], config['remote_ip'], config['remote_port'])
bridge.start()
bridge_list.append(bridge)
print(f"UAV {config['drone_id']} communication bridge started, local port: {config['local_port']}")
# Asynchronously wait for collaborative tasks to complete
await run_cooperative_task(bridge_list)
# Batch stop bridges to prevent resource leaks
for bridge in bridge_list:
bridge.stop()
print("All heterogeneous UAV collaborative tasks completed; all communication bridges have been shut down")
async def run_cooperative_task(bridge_list):
# Asynchronously dispatch distinct task commands to achieve multi-UAV collaborative reconnaissance
for idx, bridge in enumerate(bridge_list):
asyncio.create_task(send_task_command(bridge, idx))
await asyncio.sleep(30) # Wait for task execution
async def send_task_command(bridge, task_id):
# Asynchronously send task commands periodically without blocking communication on other bridges
for _ in range(10):
# Business logic for sending task commands—custom ROS topics can be forwarded via the bridge channel
await asyncio.sleep(3)
if __name__ == "__main__":
# Configure communication parameters for 3 heterogeneous UAVs
configs = [
{"drone_id": 1, "local_port": 5001, "remote_ip": "127.0.0.1", "remote_port": 6001},
{"drone_id": 2, "local_port": 5002, "remote_ip": "127.0.0.1", "remote_port": 6002},
{"drone_id": 3, "local_port": 5003, "remote_ip": "127.0.0.1", "remote_port": 6003},
]
asyncio.run(start_multi_bridge(configs))
Notes and Pitfall Avoidance Guide¶
- Port Occupancy Issue: Only one
UdpRosBridgeinstance can bind to a given local port. When starting multiple bridges in batch, distinct local ports must be assigned; otherwise, startup will fail, and the occupied port resources will not be automatically released. - Resource Release Requirement: The
stopmethod must be manually invoked after task completion to shut down the bridge; otherwise, the UDP listening thread will continue occupying system network resources after the process exits, requiring manual termination of the process to release the port. - Asynchronous Invocation Limitation: The
startandstopmethods are synchronous interfaces. In asynchronous multi-bridge scenarios, avoid directly invokingstart/stopwithin asynchronous callbacks without proper synchronization, to prevent communication chaos caused by concurrent port access across threads. - Network Compatibility Note:
UdpRosBridgesupports ROS communication forwarding only within the same local area network (LAN). For cross-subnet scenarios, routing rules must be pre-configured; otherwise, topic data from the simulation side cannot be received properly.
Changelog¶
2026-03-03: feat: SDK adds IP handling mechanism to support local-on-cloud deployment2026-01-04: fix