VehicleApi Interface Documentation¶
Introduction¶
Overview: This file provides fundamental API classes for the RflySim platform’s swarm simulation scenarios, specifically for drone vehicles and the UE map’s Earth model. It supports management and interaction with individual drone states in a swarm and the Earth model of the simulation map.
As the core foundational module for RflySim’s swarm drone simulation development, this module offers low-level interface support for multi-drone cooperative mission simulation. The Vehicle class enables independent management of each simulated drone’s state and control commands; the UEMapServe class interfaces with the simulation map service rendered by Unreal Engine; and the EarthModel class provides support for geodetic coordinate system models. These components are applicable to various swarm drone simulation development scenarios, including multi-drone cooperative reconnaissance, formation control, and swarm mission planning, helping developers quickly build customized swarm drone simulation missions.
Quick Start¶
Minimal runnable example; copy and modify only minimal configuration to run.
from RflySimSDK.swarm.VehicleApi import Vehicle
# 1. Initialize a quadcopter object; modify CopterID to match your drone's ID
uav = Vehicle(
CopterID=1, # Drone ID
Vehicletype=3, # vehicle type 3 represents a quadcopter drone
mapName="Grasslands", # map name used for simulation
updatefreq=100, # data update frequency
isBroadCast=False # whether broadcast mode is enabled
)
# 2. Retrieve the raw yaw angle and normalize it to the [-π, π] interval using yawSat
raw_yaw = 4.5 # raw angle, in radians
normalized_yaw = uav.yawSat(raw_yaw)
print(f"Raw yaw angle {raw_yaw:.2f}, normalized: {normalized_yaw:.2f} radians")
# 3. Alternatively, use yawSat1 for the same normalization
normalized_yaw2 = uav.yawSat1(raw_yaw)
print(f"Raw yaw angle {raw_yaw:.2f}, normalized (yawSat1): {normalized_yaw2:.2f} radians")
# 4. Normalize the roll angle to the [-π, π] interval
raw_roll = -5.0
normalized_roll = uav.RollSat(raw_roll)
print(f"Raw roll angle {raw_roll:.2f}, normalized: {normalized_roll:.2f} radians")
Environment & Dependencies¶
- Python Environment:
>= 3.8.10 - Dependencies:
copy,cv2,math,numpy,os,pymavlink,pymavlink.dialects.v20,socket,struct,sys,threading,time - Prerequisites: Before calling this interface, RflySimSDK initialization must be completed, and the
swarmmodule must be correctly imported.
Core Interface Description¶
The module VehicleApi.py contains configuration variables, helper functions, and core business classes.
Global Constants and Enumerations¶
This section lists all globally accessible constants and enumeration definitions directly referenced within the module.
Standalone Constants¶
None
Global/Standalone Functions¶
None
Vehicle Class¶
The API interface class for a single UAV, used to control and retrieve state information for a single UAV within the RflySim simulation environment.
__init__(CopterID=1, Vehicletype=3, mapName="Grasslands", updatefreq=100, isBroadCast=False)¶
Function Description: Initializes the simulation connection and API configuration for a single UAV, and creates the control object for the corresponding UAV. Parameters (Args):
| Parameter Name | Type | Default Value | Description |
|---|---|---|---|
| CopterID | int | 1 | UAV ID number, corresponding to the UAV’s ID in the simulation environment |
| Vehicletype | int | 3 | UAV type: 1 for fixed-wing, 3 for multi-rotor |
| mapName | str | "Grasslands" | Name of the map used in the simulation environment |
| updatefreq | int | 100 | Update frequency of UAV state data, in Hz |
| isBroadCast | bool | False | Whether to enable state broadcasting; if enabled, UAV state data will be broadcast over the network |
Returns: None
Raises: None
yawSat(yaw)¶
Function Description: Limits the yaw angle to the range [-π, π] Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| yaw | None | Yes | None | Input yaw angle to be saturated |
Returns: Yaw angle saturated to the range [-π, π]
Raises: None
yawSat1(yaw)¶
Function Description: Limits the yaw angle to the range [-π, π] Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| yaw | None | Yes | None | Input yaw angle to be saturated |
Returns: Yaw angle saturated to the range [-π, π]
Raises: None
RollSat(Roll)¶
Function Description: Limits the roll angle to the range [-π, π] Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| Roll | None | Yes | None | Input roll angle to be saturated |
Returns: Roll angle saturated to the range [-π, π]
Raises: None
sat(inPwm, thres=1)¶
Function Description: Saturates the input value: if the input exceeds the threshold, it is set to the threshold; if it is less than the negative threshold, it is set to the negative threshold; otherwise, it remains unchanged. Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| inPwm | None | Yes | 0 | Input value to be saturated |
| thres | None | No | 1 | Saturation threshold; the valid range is [-thres, thres] |
Returns: Saturated result value
Raises: None
initSimpleModel(intState=[0, 0, 0], targetIP="127.0.0.1", GPSOrigin=[40.1540302, 116.2593683, 50])¶
Function Description: Initializes and starts the UAV point-mass model for control. The initial position and yaw angle match those shown on the CopterSim interface; the initial altitude can be obtained from CopterSim or UE4. Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| intState | None | No | [0, 0, 0] |
Initial UAV state: initial X coordinate (m, in NED coordinate system), initial Y coordinate (m, in NED coordinate system), and initial yaw angle (degrees) |
| targetIP | None | No | 127.0.0.1 |
Target IP address to receive UAV state information, typically the IP of the computer running Simulink |
| GPSOrigin | None | No | [40.1540302, 116.2593683, 50] |
GPS origin coordinates: latitude, longitude, and altitude, used for coordinate transformation |
Returns: None
Raises: None
RecMavLoop()¶
Function Description: None
Parameters (Args): No parameters
Returns: None
Raises: None
EndSimpleModel()¶
Function Description: Terminates the point-mass model execution
Parameters (Args): No parameters
Returns: None
Raises: None
enFixedWRWTO()¶
Function Description: None
Parameters (Args): No parameters
Returns: None
Raises: None
TypeMask(EnList)¶
Function Description: Retrieves the type mask for offline control messages based on the enable list; mask definitions refer to the MAVLink official POSITION_TARGET_TYPEMASK documentation.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| EnList | None | Yes | None | Control enable list, indicating which control variables are active in offline control |
Returns: Mask of the generated offline position target message type
Raises: None
SimpleModelLoop()¶
Description: Infinite loop function for the point-mass model, maintaining continuous model updates
Args: No arguments
Returns: None
Raises: None
ModelStep(CurTime=-1)¶
Description: None
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| CurTime | None | No | -1 | Current simulation time |
Returns: None
Raises: None
SendUavState(CurTime)¶
Description: None
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| CurTime | None | Yes | None | Current simulation time |
Returns: None
Raises: None
ProssInput(dt)¶
Description: None
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| dt | None | Yes | None | Time step size |
Returns: None
Raises: None
fixedPitchFromVel(vel)¶
Description: None
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vel | None | Yes | None | Velocity input |
Returns: None
Raises: None
Step(dt)¶
Description: None
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| dt | None | Yes | None | Time step size |
Returns: None
Raises: None
SendOutput(CurTime)¶
Description: Sends output control commands
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| CurTime | Any | Yes | None | Current timestamp |
Returns: None
Raises: None
SendPosNED(x=0, y=0, z=0, yaw=0)¶
Description: Sends the UAV’s target position in the North-East-Down (NED) geographic coordinate frame to PX4, while controlling the yaw angle. Position units are meters; yaw angle units are radians. When the UAV is flying above ground, the z value is negative.
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| x | Any | No | 0 | Target position in NED frame x-direction (north), unit: m |
| y | Any | No | 0 | Target position in NED frame y-direction (east), unit: m |
| z | Any | No | 0 | Target position in NED frame z-direction (down), unit: m |
| yaw | Any | No | 0 | Target yaw angle, unit: rad |
Returns: None
Raises: None
SendPosNEDNoYaw(x=0, y=0, z=0)¶
Description: Sends the UAV’s target position in the North-East-Down (NED) geographic coordinate frame to PX4, without controlling the yaw angle. Position units are meters. When the UAV is flying above ground, the z value is negative.
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| x | Any | No | 0 | Target position in NED frame x-direction (north), unit: m |
| y | Any | No | 0 | Target position in NED frame y-direction (east), unit: m |
| z | Any | No | 0 | Target position in NED frame z-direction (down), unit: m |
Returns: None
Raises: None
SendPosFRD(x=0, y=0, z=0, yaw=0)¶
Description: Sends the UAV’s target position in the Front-Right-Down (FRD) body-fixed coordinate frame to PX4, while controlling the yaw angle. Position units are meters; yaw angle units are radians. When the UAV is flying above ground, the z value is negative.
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| x | Any | No | 0 | Target position in FRD frame x-direction (forward), unit: m |
| y | Any | No | 0 | Target position in FRD frame y-direction (right), unit: m |
| z | Any | No | 0 | Target position in FRD frame z-direction (down), unit: m |
| yaw | Any | No | 0 | Target yaw angle, unit: rad |
Returns: None
Raises: None
SendPosFRDNoYaw(x=0, y=0, z=0)¶
Description: Sends the UAV’s target position in the Front-Right-Down (FRD) body-fixed coordinate frame to PX4, without controlling the yaw angle. Position units are meters. When the UAV is flying above ground, the z value is negative.
Args:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| x | Any | No | 0 | Target position in x-direction (forward) under FRD coordinate system, unit: m |
| y | Any | No | 0 | Target position in y-direction (rightward) under FRD coordinate system, unit: m |
| z | Any | No | 0 | Target position in z-direction (downward) under FRD coordinate system, unit: m |
Returns: None
Raises: None
SendVelNED(vx=0, vy=0, vz=0, yawrate=0)¶
Function Description: Sends the drone’s target velocity in the geographic North-East-Down (NED) coordinate system to PX4, while controlling the yaw rate. Velocity unit: m/s; yaw rate unit: rad/s. When the drone ascends, vz is negative.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vx | Any | No | 0 | Target velocity in x-direction (northward) under NED coordinate system, unit: m/s |
| vy | Any | No | 0 | Target velocity in y-direction (eastward) under NED coordinate system, unit: m/s |
| vz | Any | No | 0 | Target velocity in z-direction (downward) under NED coordinate system, unit: m/s |
| yawrate | Any | No | 0 | Target yaw rate, unit: rad/s |
Returns: None
Raises: None
SendVelNEDNoYaw(vx, vy, vz)¶
Function Description: Sends the drone’s target velocity in the geographic North-East-Down (NED) coordinate system to PX4, without controlling yaw. Velocity unit: m/s. When the drone ascends, vz is negative.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vx | Any | Yes | None | Target velocity in x-direction (northward) under NED coordinate system, unit: m/s |
| vy | Any | Yes | None | Target velocity in y-direction (eastward) under NED coordinate system, unit: m/s |
| vz | Any | Yes | None | Target velocity in z-direction (downward) under NED coordinate system, unit: m/s |
Returns: None
Raises: None
SendVelFRD(vx=0, vy=0, vz=0, yawrate=0)¶
Function Description: Sends the drone’s target velocity in the body-fixed Front-Right-Down (FRD) coordinate system to PX4, while controlling the yaw rate. Velocity unit: m/s; yaw rate unit: rad/s. When the drone ascends, vz is negative.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vx | Any | No | 0 | Target velocity in x-direction (forward) under FRD coordinate system, unit: m/s |
| vy | Any | No | 0 | Target velocity in y-direction (rightward) under FRD coordinate system, unit: m/s |
| vz | Any | No | 0 | Target velocity in z-direction (downward) under FRD coordinate system, unit: m/s |
| yawrate | Any | No | 0 | Target yaw rate, unit: rad/s |
Returns: None
Raises: None
SendVelNoYaw(vx, vy, vz)¶
Function Description: Sends the drone’s target velocity in the body-fixed Front-Right-Down (FRD) coordinate system to PX4, without controlling yaw rate. Velocity unit: m/s. When the drone ascends, vz is negative.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vx | Any | Yes | None | Target velocity in x-direction (forward) under FRD coordinate system, unit: m/s |
| vy | Any | Yes | None | Target velocity in y-direction (rightward) under FRD coordinate system, unit: m/s |
| vz | Any | Yes | None | Target velocity in z-direction (downward) under FRD coordinate system, unit: m/s |
Returns: None
Raises: None
sendBuf(buf, windowID=-1)¶
Function Description: Sends custom buffer data.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| buf | Any | Yes | None | Buffer data to be sent |
| windowID | Any | No | -1 | Target window ID; -1 indicates the default window |
Returns: None
Raises: None
sendUE4PosNew(copterID=1, vehicleType=3, PosE=[0, 0, 0], AngEuler=[0, 0, 0], VelE=[0, 0, 0], PWMs=[0] * 8, runnedTime=-1, windowID=-1)¶
Function Description: Sends position and attitude information to RflySim3D for creating new 3D models or updating existing ones. The transmitted data includes checksum, drone ID, vehicle type, PWM outputs, velocity, Euler angles, position, and timestamp.
Arguments:
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| copterID | Any | No | 1 | Drone ID |
| vehicleType | Any | No | 3 | Drone type |
| PosE | Any | No | [0, 0, 0] | Position in geographic NED coordinate system, unit: m |
| AngEuler | Any | No | [0, 0, 0] | Euler angles (roll, pitch, yaw), unit: rad |
| VelE | Any | No | [0, 0, 0] | Velocity in geographic coordinate system, unit: m/s |
| PWMs | Any | No | [0] * 8 | Eight PWM output values |
| runnedTime | Any | No | -1 | Current timestamp in seconds; -1 indicates using internal timing |
| windowID | Any | No | -1 | Target RflySim3D window ID; -1 indicates the default window |
Returns: None
Raises: None
SendCruiseSpeed(Speed=10)¶
Function Description: Sends a command to modify the aircraft's cruise speed, in units of m/s.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| Speed | Any | No | 10 | Target cruise speed, in m/s |
Return Value (Returns): None
Exceptions (Raises): None
SendCopterSpeed(Speed=5)¶
Function Description: Sends a command to set the maximum speed of a multi-rotor aircraft, in units of m/s.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| Speed | Any | No | 5 | Target maximum speed for the multi-rotor, in m/s |
Return Value (Returns): None
Exceptions (Raises): None
SendGroundSpeed(Speed=15)¶
Function Description: Sends a command to modify the aircraft's ground speed, in units of m/s.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| Speed | Any | No | 15 | Target ground speed, in m/s |
Return Value (Returns): None
Exceptions (Raises): None
SendCruiseRadius(rad=20)¶
Function Description: Sends a command to modify the aircraft's cruise turning radius, in meters.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| rad | Any | No | 20 | Target cruise turning radius, in meters |
Return Value (Returns): None
Exceptions (Raises): None
SendMavArm(isArm=0)¶
Function Description: Sends a MAVLink arm/disarm command to control the aircraft’s power state.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| isArm | Any | No | 0 | 0 means disarm (stop motors); non-zero means arm (start motors) |
Return Value (Returns): None
Exceptions (Raises): None
sendUE4Cmd(cmd, windowID=-1)¶
Function Description: Sends control commands to RflySim3D (UE4 engine) to modify scene display, camera parameters, vehicle states, etc. Supported command formats are as follows:
b'RflyShowTextTime txt time': Display specified text in UE4 fortimesecondsb'RflyShowText txt': Display specified text in UE4 for 5 secondsRflyChangeMapbyID id: Switch scene map by IDRflyChangeMapbyName txt: Switch scene map by nameRflyChangeViewKeyCmd key num: Equivalent to pressing the shortcut key combinationkey + numin UE4RflyCameraPosAngAdd x y z roll pitch yaw: Incrementally offset camera position (x-y-z, in meters) and orientation (roll-pitch-yaw, in degrees) relative to current camera poseRflyCameraPosAng x y z roll pitch yaw: Directly set camera position (x-y-z, in meters) and orientation (roll-pitch-yaw, in degrees) relative to UE originRflyCameraFovDegrees degrees: Modify camera field of view (in degrees)RflyChange3DModel CopterID veTypes=0: Modify the 3D model ID of the vehicle with specified IDRflyChangeVehicleSize CopterID size=0: Modify the size of the vehicle with specified IDRflyMoveVehiclePosAng CopterID isFitGround x y z roll pitch yaw: Incrementally move vehicle to specified position (x-y-z, in meters) and orientation (roll-pitch-yaw, in degrees) relative to current pose;isFitGroundindicates whether to conform to terrain heightRflySetVehiclePosAng CopterID isFitGround x y z roll pitch yaw: Directly set vehicle position (x-y-z, in meters) and orientation (roll-pitch-yaw, in degrees) relative to UE origin;isFitGroundindicates whether to conform to terrain heightRflyScanTerrainH xLeftBottom yLeftBottom xRightTop yRightTop scanHeight scanInterval: Scan terrain in specified rectangular region to generate height map (PNG) and elevation data (TXT); all parameters are in metersRflyCesiumOriPos lat lon Alt: Modify the latitude, longitude, and altitude (in degrees and meters) of the Cesium map originRflyClearCapture: Clear image capture buffer
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| cmd | bytes | Yes | None | Byte stream of the control command to send |
| windowID | int | No | -1 | RflySim3D window ID; default -1 indicates sending to the main window |
Return Value (Returns): None
Exceptions (Raises): None
SendVelYawAlt(vel=10, alt=-100, yaw=6.28)¶
Function Description: Sends desired velocity, altitude, and yaw angle commands to PX4. Coordinate system is Earth-centered North-East-Down (NED); in NED, altitude above ground corresponds to negative z-values.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| vel | array[float] | No | 10 | Desired north-east velocity, format: [v_north, v_east], in m/s |
| alt | float | No | -100 | Desired altitude, in meters (NED) |
| yaw | float | No | 6.28 | Desired yaw angle, in radians |
Return Value (Returns): None
Exceptions (Raises): None
sendMavTakeOff(xM=0, yM=0, zM=0, YawRad=0, PitchRad=20 / 180.0 * math.pi)¶
Function Description: Sends a takeoff command to instruct the aircraft to take off to a specified target position in the local coordinate system.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| xM | float | No | 0 | Target x-coordinate, unit: m |
| yM | float | No | 0 | Target y-coordinate, unit: m |
| zM | float | No | 0 | Target z-coordinate (altitude), unit: m |
| YawRad | float | No | 0 | Target yaw angle, unit: rad |
| PitchRad | float | No | 20 / 180.0 * math.pi | Takeoff pitch angle, unit: rad |
Returns: None
Raises: None
sendMavTakeOffGPS(lat, lon, alt, yawDeg=0, pitchDeg=15)¶
Function Description: Sends a takeoff command to instruct the aircraft to take off to a specified target position defined in the GPS global coordinate system.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
| lat | float | Yes | None | Target latitude, unit: degrees |
| lon | float | Yes | None | Target longitude, unit: degrees |
| alt | float | Yes | None | Target altitude, unit: m |
| yawDeg | float | No | 0 | Target yaw angle, unit: degrees |
| pitchDeg | float | No | 15 | Takeoff pitch angle, unit: degrees |
Returns: None
Raises: None
UEMapServe Class¶
Manages Unreal Engine (UE) map elevation data within the RflySim simulation environment, providing map loading and terrain height query functionality. Commonly used in simulation scenarios such as drone trajectory planning and terrain obstacle avoidance, where terrain height information is required.
__init__(name="")¶
Function Description: Initializes an instance of the UEMapServe class and creates a map service object.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
name |
str |
No | "" |
Name of the map file to be loaded |
Returns:
UEMapServeinstance object
Raises:
- None
LoadPngData(name)¶
Function Description: Loads a PNG-format terrain elevation data file, parses and stores the terrain height information.
Parameters (Args):
| Parameter Name | Type | Required | Default Value | Description |
|---|---|---|---|---|
name |
str |
Yes | - | Path or filename of the PNG elevation data file |
Returns:
- None
Raises:
- None
Example:
from RflySimSDK.swarm import UEMapServe
map_serve = UEMapServe()
# Load terrain elevation PNG file
map_serve.LoadPngData("terrain_map.png")
---
#### `getTerrainAltData(xin, yin)`
**Function Description**: Queries the terrain altitude data at the specified coordinates.
**Arguments**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `xin` | `float`/`np.ndarray` | Yes | - | Eastward coordinate(s) of the query point(s); supports either a single coordinate or an array of coordinates. |
| `yin` | `float`/`np.ndarray` | Yes | - | Northward coordinate(s) of the query point(s); must match the dimensionality of `xin`. |
**Returns**:
- `float`/`np.ndarray`: Terrain altitude value(s) corresponding to the input coordinates; returns an array of the same shape as the input when arrays are provided.
**Raises**:
- None
**Example**:
```python
from RflySimSDK.swarm import UEMapServe
import numpy as np
map_serve = UEMapServe()
map_serve.LoadPngData("terrain_map.png")
# Query terrain altitude for a single point
alt = map_serve.getTerrainAltData(100.5, 200.3)
# Batch query terrain altitudes for multiple points
x_coords = np.array([100, 101, 102])
y_coords = np.array([200, 201, 202])
alts = map_serve.getTerrainAltData(x_coords, y_coords)
---
### `EarthModel` Class
Provides conversions among multiple coordinate systems under the WGS84 Earth model, enabling mutual transformation between geographic coordinates and local navigation coordinates in drone simulation.
---
#### `__init__()`
**Function Description**: Initializes an instance of the `EarthModel` class.
**Parameters (Args)**:
None
**Returns**:
- `EarthModel` instance object
**Raises**:
- None
---
#### `lla2ecef(lat, lon, h)`
**Function Description**: Converts latitude, longitude, and altitude (LLA geographic coordinates) to Earth-Centered, Earth-Fixed (ECEF) Cartesian coordinates.
**Parameters (Args)**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `lat` | `float` | Yes | - | Latitude, in degrees |
| `lon` | `float` | Yes | - | Longitude, in degrees |
| `h` | `float` | Yes | - | Altitude (height above ellipsoid), in meters |
**Returns**:
- `tuple[float, float, float]`: (x, y, z) coordinates in the ECEF system, in meters
**Raises**:
- None
---
#### `ecef2enu(x, y, z, lat0, lon0, h0)`
**Function Description**: Converts Earth-Centered, Earth-Fixed (ECEF) coordinates to East-North-Up (ENU) local coordinates with origin at a reference point.
**Parameters (Args)**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `x` | `float` | Yes | - | X coordinate in ECEF system, in meters |
| `y` | `float` | Yes | - | Y coordinate in ECEF system, in meters |
| `z` | `float` | Yes | - | Z coordinate in ECEF system, in meters |
| `lat0` | `float` | Yes | - | Reference point latitude, in degrees |
| `lon0` | `float` | Yes | - | Reference point longitude, in degrees |
| `h0` | `float` | Yes | - | Reference point altitude (height above ellipsoid), in meters |
**Returns**:
- `tuple[float, float, float]`: (xEast, yNorth, zUp) coordinates in the ENU system, in meters
**Raises**:
- None
---
#### `enu2ecef(xEast, yNorth, zUp, lat0, lon0, h0)`
**Function Description**: Converts East-North-Up (ENU) local coordinates (with origin at a reference point) to Earth-Centered, Earth-Fixed (ECEF) coordinates.
**Parameters (Args)**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `xEast` | `float` | Yes | - | Eastward coordinate in ENU system, in meters |
| `yNorth` | `float` | Yes | - | Northward coordinate in ENU system, in meters |
| `zUp` | `float` | Yes | - | Upward (vertical) coordinate in ENU system, in meters |
| `lat0` | `float` | Yes | - | Reference point latitude, in degrees |
| `lon0` | `float` | Yes | - | Reference point longitude, in degrees |
| `h0` | `float` | Yes | - | Reference point altitude (height above ellipsoid), in meters |
**Returns**:
- `tuple[float, float, float]`: (x, y, z) coordinates in the ECEF system, in meters
**Raises**:
- None
---
#### `ecef2lla(x, y, z)`
**Function Description**: Converts Earth-Centered, Earth-Fixed (ECEF) Cartesian coordinates to latitude, longitude, and altitude (LLA geographic coordinates).
**Parameters (Args)**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `x` | `float` | Yes | - | X coordinate in ECEF system, in meters |
| `y` | `float` | Yes | - | Y coordinate in ECEF system, in meters |
| `z` | `float` | Yes | - | Z coordinate in ECEF system, in meters |
**Returns**:
- `tuple[float, float, float]`: (lat, lon, h) coordinates in the LLA system; latitude and longitude in degrees, altitude in meters
**Raises**:
- None
---
#### `lla2enu(lat, lon, h, lat_ref, lon_ref, h_ref)`
**Function Description**: Directly converts latitude, longitude, and altitude (LLA) coordinates to East-North-Up (ENU) local coordinates relative to a reference point.
**Parameters (Args)**:
| Parameter | Type | Required | Default | Description |
| :--- | :--- | :---: | :--- | :--- |
| `lat` | `float` | Yes | - | Target point latitude, in degrees |
| `lon` | `float` | Yes | - | Target point longitude, in degrees |
| `h` | `float` | Yes | - | Target point altitude (height above ellipsoid), in meters |
| `lat_ref` | `float` | Yes | - | Reference point latitude, in degrees |
| `lon_ref` | `float` | Yes | - | Reference point longitude, in degrees |
| `h_ref` | `float` | Yes | - | Reference point altitude (height above ellipsoid), in meters |
**Returns**:
- `tuple[float, float, float]`: (xEast, yNorth, zUp) coordinates in the ENU system, in meters
**Raises**:
- None
---
#### `enu2lla(xEast, yNorth, zUp, lat_ref, lon_ref, h_ref)`
**Function Description**: Directly converts East-North-Up (ENU) local coordinates (relative to a reference point) to latitude, longitude, and altitude (LLA geographic coordinates).
**Parameters (Args)**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `xEast` | `float` | Yes | - | East coordinate in ENU frame, unit: meters |
| `yNorth` | `float` | Yes | - | North coordinate in ENU frame, unit: meters |
| `zUp` | `float` | Yes | - | Up (vertical) coordinate in ENU frame, unit: meters |
| `lat_ref` | `float` | Yes | - | Reference latitude, unit: degrees |
| `lon_ref` | `float` | Yes | - | Reference longitude, unit: degrees |
| `h_ref` | `float` | Yes | - | Reference altitude (height above ellipsoid), unit: meters |
**Returns**:
- `tuple[float, float, float]`: Coordinates in LLA frame (lat, lon, h), with latitude and longitude in degrees, and height in meters
**Raises**:
- None
---
#### `lla2ned(lla, lla0)`
**Description**: Converts latitude-longitude-altitude (LLA) coordinates to a local North-East-Down (NED) frame with origin at the reference point.
**Arguments**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `lla` | `tuple[float, float, float]` | Yes | - | Target point’s LLA coordinates, format: (lat, lon, h), with latitude and longitude in degrees, and height in meters |
| `lla0` | `tuple[float, float, float]` | Yes | - | Reference point’s LLA coordinates, format: (lat0, lon0, h0), with latitude and longitude in degrees, and height in meters |
**Returns**:
- `tuple[float, float, float]`: Coordinates in NED frame (north, east, down), unit: meters
**Raises**:
- None
---
#### `ned2lla(ned, lla0)`
**Description**: Converts a local North-East-Down (NED) frame (with origin at the reference point) to latitude-longitude-altitude (LLA) coordinates.
**Arguments**:
| Parameter Name | Type | Required | Default Value | Description |
| :--- | :--- | :---: | :--- | :--- |
| `ned` | `tuple[float, float, float]` | Yes | - | Coordinates in NED frame, format: (north, east, down), unit: meters |
| `lla0` | `tuple[float, float, float]` | Yes | - | Reference point’s LLA coordinates, format: (lat0, lon0, h0), with latitude and longitude in degrees, and height in meters |
**Returns**:
- `tuple[float, float, float]`: Coordinates in LLA frame (lat, lon, h), with latitude and longitude in degrees, and height in meters
**Raises**:
- None
**Example**:
```python
from RflySimSDK.swarm import EarthModel
# Initialize Earth model for coordinate transformation
em = EarthModel()
# Convert LLA to ENU: using start point (30.5°, 114.2°, 10 m) as reference
lat, lon, h = 30.501, 114.201, 15
lat_ref, lon_ref, h_ref = 30.5, 114.2, 10
xEast, yNorth, zUp = em.lla2enu(lat, lon, h, lat_ref, lon_ref, h_ref)
print(f"ENU coordinates: East {xEast:.2f} m, North {yNorth:.2f} m, Up {zUp:.2f} m")
# Convert back to LLA for verification
new_lat, new_lon, new_h = em.enu2lla(xEast, yNorth, zUp, lat_ref, lon_ref, h_ref)
print(f"Back to LLA: Latitude {new_lat:.4f}°, Longitude {new_lon:.4f}°, Height {new_h:.2f} m")
---
## Advanced Usage Examples
> Demonstrates complex composite scenarios (e.g., multi-class collaboration, asynchronous control, batch operations).
This example implements a composite scenario involving terrain-adaptive position calculation for a multi-drone swarm formation and asynchronous attitude saturation control. It integrates three functional modules:
- `swarm` module’s Vehicle swarm control
- UEMapServe terrain data reading
- EarthModel coordinate transformation
It enables batch adjustment of drone target positions based on actual terrain and asynchronous issuance of attitude commands to each drone, ensuring compliance with actuator saturation limits:
```python
import RflySimSDK.swarm as rs
import numpy as np
# Initialize multi-drone swarm control objects
drone_swarm = [rs.Vehicle() for i in range(5)]
# Start the simple simulation model loop
for drone in drone_swarm:
drone.initSimpleModel()
drone.RecMavLoop()
drone.SimpleModelLoop()
# Load UE terrain elevation data and obtain terrain height in the target waypoint region
map_serve = rs.UEMapServe()
map_serve.LoadPngData()
coord_trans = rs.EarthModel()
# Batch compute ENU target coordinates adapted to terrain
target_lonlat = [(116.397, 39.908) for _ in range(5)]
target_lla = []
for lon, lat in target_lonlat:
alt = map_serve.getTerrainAltData(lon, lat)
# Drones fly 100 m above terrain
target_lla.append([lon, lat, alt + 100])
# Asynchronously perform coordinate transformation + attitude saturation control for each drone
for idx, drone in enumerate(drone_swarm):
lla = target_lla[idx]
# Convert to ENU coordinates relative to origin
origin_lla = [116.397, 39.908, 100]
enu_pos = coord_trans.lla2enu(lla, origin_lla)
# Apply yaw saturation limit and output control commands compliant with physical constraints
limited_yaw = drone.yawSat(enu_pos[0] * 0.1)
# Apply type mask and send control command
masked_yaw = drone.TypeMask(limited_yaw, mask=0x04)
# Release resources upon simulation termination
drone.EndSimpleModel()
Notes and Pitfall Avoidance Guide¶
-
Consistency of Input Order for Coordinate Transformation:
Methods in theEarthModelclass for latitude/longitude/altitude conversion all use the input order (longitude, latitude, altitude). Reversing the order of longitude and latitude will result in百-meter-level coordinate deviations. Verify input parameter order before use. -
Simulation Model Lifecycle Management:
After callinginitSimpleModelon aVehicleobject to start the simple model, you must callEndSimpleModelupon task completion to release resources. Re-initializing a model without releasing it first can cause port conflicts and simulation process crashes. -
Terrain Data Loading Prerequisite:
Before callingUEMapServe.getTerrainAltDatato retrieve terrain elevation, you must first callLoadPngDatato load the elevation map data. If data is not loaded, the returned altitude defaults to 0, leading to incorrect flight altitude calculations. -
Matching Saturation Control Methods to Scenarios:
TheVehicleclass provides multiple channel-specific saturation limitation methods, such asyawSat,yawSat1, andRollSat. Select the appropriate method corresponding to the control channel being used; mismatched usage may cause attitude control outputs to exceed the drone’s actuator travel limits.
Changelog¶
2024-12-10: fix: Update swarm control interface documentation comments2024-07-18: fix: Update API homepage index2023-11-10: MoveVehicleApi.pyto a new location