RflySimSDK v3.08
RflySimSDK说明文档
载入中...
搜索中...
未找到
ModelLoad类 参考

DLL文件外部加载接口类 更多...

+ 类 ModelLoad 继承关系图:

Public 成员函数

 __init__ (self, dll_name, CopterID=1, ClassID=-1, MapName='Grasslands', ip='127.0.0.1', LocX=0, LocY=0, Yaw=0, UdpMode=0, useGPS=False, GpsOrin=[0, 0, 0])
 这是类的构造函数,用于初始化 ModelLoad 类的实例。参数的详细含义参考 Bat脚本使用参考
 
 CreateVehicle (self, CopterID=1, ClassID=-1, MapName='Grasslands', ip='127.0.0.1', LocX=0, LocY=0, Yaw=0, UdpMode=0, useGPS=False, GpsOrin=[0, 0, 0])
 初始化并配置载具模型。参数的详细含义参考 Bat脚本使用参考
 
 Updata3Doutput (self)
 用于更新载具模型仿真输出,读取车辆当前的运动状态数据并更新到 out3Ddata 和 outHilData,并与地形数据进行交互。
 
 SendUpdate3DMap (self, isSetSpeed=False)
 用于向 RflySim3D发送命令,更新 3D 地图或设置RflySim3D仿真速度。
 
 get3DDataBuf (self)
 提取载具模型的 3D 仿真数据out3Dvect并将其打包,以便通过网络转发给RflySim3D
 
 Send3DData (self)
 将打包的 3D 数据通过 UDP 发送到端口 20010,用于与 RflySim3D 进行通信
 
 SendSimData (self)
 将与 Send3DData 同样的 3D 数据发送到端口 30100,用于仿真数据的传输
 
 SendHILData (self)
 发送硬件在环(HIL)仿真数据到指定的端口,通常用于与飞控系统交互
 
 SendOutCopter (self)
 发送仿真数据到30100端口,可用于日志记录
 
 fillList (self, data, inLen, fill=0)
 填充或裁剪一个列表
 
 StartAutUpdate (self, UpdateFreq=30, speed=-1)
 用于启动自动更新循环,以指定的频率更新仿真状态。
 
 StopAutUpdate (self)
 用于停止自动更新循环
 
 AutUpdateLoop (self)
 自动更新循环的核心逻辑,实现持续的仿真更新、数据发送等功能。
 
 StartExtCtrl (self)
 用于启动外部控制功能,创建两个用于接收外部控制数据的UDP套接字,并开启两个线程来监听数据。
 
 StopExtCtrl (self)
 停止外部控制,关闭UDP套接字并终止接收线程。
 
 Recv20100Loop (self)
 线程的主循环,用于接收20100端口的数据并根据控制模式执行相应的控制命令。
 
 Recv30100Loop (self)
 线程的主循环,用于接收30100端口的数据并根据不同的数据类型执行相应处理。
 
 DllDestroyModel (self)
 销毁当前加载的仿真模型
 
 DllReInitModel (self)
 重新初始化仿真模型。
 
 DllInputSILs (self, in_ints=[0] *8, in_floats=[0] *20)
 将综合模型系统仿真输入数据传递给 DLL,参见 sendSILIntFloat

 
 DllInputColls (self, in_floats_collision=[0] *20)
 将碰撞数据传递给 DLL,用于仿真中处理碰撞情况,参见 sendColl20d

 
 DllTerrainIn15d (self, terrain15d=[0] *15)
 输入三维场景的地形高度数据给DLL,用于仿真环境的地形建模,参见 sendTerrIn15d
 
 DllInitGpsPos (self, gps=[0] *3)
 初始化仿真的 GPS 坐标原点,用于地理位置相关的仿真,参见 sendReGPSOrin

 
 DllInitPosAngState (self, init_pos_offset=[0, 0, 0], init_ang_offset=[0, 0, 0])
 初始化位置和姿态状态,用于设置仿真对象的初始位置信息和朝向,参见 sendReSimXyzRPYaw
 
 DllInputDoubCtrls (self, in_doub_ctrls=[0] *28)
 综合模型外部控制指令输入接口,用于传递 28 维的双精度控制指令数据,参见 sendInDoubCtrls
 
 DllinSIL28d (self, in_doub_ctrls=[0] *28)
 综合模型外部控制指令输入接口,用于传递 28 维的双精度控制指令数据,参见 sendInDoubCtrls
 
 DllInCtrlExt (self, in_ctrl_ext=[0] *140)
 扩展控制数据,用于支持更高级的控制仿真功能,参见 sendInCtrlExtAll
 
 DllInFromUE (self, in_from_ue=[0] *32)
 从RflySim3D输入自定义数据到 DLL,用于与外部仿真环境的集成。
 
 DllInputColls (self, inCll=[0] *20)
 传递 20 维float数组的碰撞数据的接口,用于处理仿真对象之间的碰撞检测。
 
 DllGetStep0 (self)
 获取仿真的步长,用于确定仿真时间步的大小。如果 DLL 中没有对应的函数,默认返回 0.001
 
 Dllstep (self)
 执行一次仿真步骤。这是对 DLL 中仿真时间推进的基本调用。
 
 ModelUpdate (self, step_time)
 手动更新仿真状态的接口
 
 DlloutVehileInfo60d (self)
 从 DLL 获取 60 维的载具三维信息数据。包括各种飞行器或车辆的状态数据。
 
 DllOutCopterData (self)
 从 DLL 获取 32 维数据,包括飞行器的传感器读数、状态信息等
 
 SendPosNED (self, x=0, y=0, z=0, yaw=0)
 发送NED(北东地)地球参考系下的位置控制命令。
 
 SendPosLocal (self, x=0, y=0, z=0, yaw=0)
 
 SendVelNED (self, vx=0, vy=0, vz=0, yawRate=0)
 发送NED(北东地)地球参考系下的速度及偏航控制命令。
 
 SendVelFRD (self, vx=0, vy=0, vz=0, yawRate=0)
 发送FRD(前右下)机体参考系下的速度控制命令。
 
 SendVelNEDNoYaw (self, northvel=0, eastvel=0, downvel=0)
 发送NED(北东地)地球参考系下的速度及偏航控制命令。
 

Public 属性

 udp_socket
 
 isSendExtData
 
 out3Ddata
 
 out3Dvect
 
 outHilData
 
 outCopterVect
 
 simSpeed
 
 dll
 
 isBroadCast
 
 isAutoUpdate
 
 CopterID
 
 ClassID
 
 MapName
 
 LocX
 
 LocY
 
 Yaw
 
 UdpMode
 
 useGPS
 
 GpsOrin
 
 map
 
 ue
 
 geo
 
 ip
 
 port
 
 port2
 
 InitPos
 
 InitAng
 
 GpsOrinInit
 
 t1
 
 Interval
 
 nextTime
 
 lastTime
 
 udp_20100
 
 isRec20100
 
 t2
 
 udp_30100
 
 isRec30100
 
 t3
 

详细描述

DLL文件外部加载接口类

用于加载和初始化一个指定的 DLL 文件(动态链接库)

构造及析构函数说明

◆ __init__()

__init__ ( self,
dll_name,
CopterID = 1,
ClassID = -1,
MapName = 'Grasslands',
ip = '127.0.0.1',
LocX = 0,
LocY = 0,
Yaw = 0,
UdpMode = 0,
useGPS = False,
GpsOrin = [0,0,0] )

这是类的构造函数,用于初始化 ModelLoad 类的实例。参数的详细含义参考 Bat脚本使用参考

  • 参数
    dll_name要加载的 DLL 文件的名称。
    CopterID飞机ID
    ClassID载具三维样式
    MapName仿真三维地图名称
    ipip地址,默认为本机
    LocX载具初始X位置,单位m
    LocY载具初始Y位置,单位m
    Yaw载具初始yaw角度,设置地图中的初始航向角,单位是度数(degree)。航向角是指在水平面上,相对于北方的方向角。
    UdpMode选择不同的通信模式(默认为Full)
    useGPS是否启用GPS模式(默认模式选择直角坐标系)
    GpsOrinGPS原点坐标,三维数列依次为经度、纬度、海拔高度

MultiCopterDll 重载.

+ 函数调用图:

成员函数说明

◆ AutUpdateLoop()

AutUpdateLoop ( self)

自动更新循环的核心逻辑,实现持续的仿真更新、数据发送等功能。

+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ CreateVehicle()

CreateVehicle ( self,
CopterID = 1,
ClassID = -1,
MapName = 'Grasslands',
ip = '127.0.0.1',
LocX = 0,
LocY = 0,
Yaw = 0,
UdpMode = 0,
useGPS = False,
GpsOrin = [0,0,0] )

初始化并配置载具模型。参数的详细含义参考 Bat脚本使用参考

  • 参数
    dll_name要加载的 DLL 文件的名称。
    CopterID飞机ID
    ClassID载具三维样式
    MapName仿真三维地图名称
    ipip地址,默认为本机
    LocX载具初始X位置,单位m
    LocY载具初始Y位置,单位m
    Yaw载具初始yaw角度,设置地图中的初始航向角,单位是度数(degree)。航向角是指在水平面上,相对于北方的方向角。
    UdpMode选择不同的通信模式(默认为Full)
    useGPS是否启用GPS模式(默认模式选择直角坐标系)
    GpsOrinGPS原点坐标,三维数列依次为经度、纬度、海拔高度,启用GPS模式后起作用
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllDestroyModel()

DllDestroyModel ( self)

销毁当前加载的仿真模型

销毁模型
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllGetStep0()

DllGetStep0 ( self)

获取仿真的步长,用于确定仿真时间步的大小。如果 DLL 中没有对应的函数,默认返回 0.001

获取步长
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInCtrlExt()

DllInCtrlExt ( self,
in_ctrl_ext = [0]*140 )

扩展控制数据,用于支持更高级的控制仿真功能,参见 sendInCtrlExtAll

  • 参数
    in_ctrl_ext最高140 维浮点型的扩展控制数据
    输入故障注入数据
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInFromUE()

DllInFromUE ( self,
in_from_ue = [0]*32 )

从RflySim3D输入自定义数据到 DLL,用于与外部仿真环境的集成。

  • 参数
    in_from_ue最高32 维double型列表,来自RflySim3D的数据
    输入UE数据给DLL
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInitGpsPos()

DllInitGpsPos ( self,
gps = [0]*3 )

初始化仿真的 GPS 坐标原点,用于地理位置相关的仿真,参见 sendReGPSOrin

  • 参数
    gps三维浮点数列,依次为经度、纬度、海拔高度
    输入GPS坐标的原点值
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInitPosAngState()

DllInitPosAngState ( self,
init_pos_offset = [0,0,0],
init_ang_offset = [0,0,0] )

初始化位置和姿态状态,用于设置仿真对象的初始位置信息和朝向,参见 sendReSimXyzRPYaw

  • 参数
    init_pos_offset3维浮点列表,初始化位置状态
    init_ang_offset3维浮点列表,初始化角度状态
    初始化位置和角度状态
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInputColls() [1/2]

DllInputColls ( self,
in_floats_collision = [0]*20 )

将碰撞数据传递给 DLL,用于仿真中处理碰撞情况,参见 sendColl20d

  • 参数
    in_floats_collision最多20 维的浮点数组,传输碰撞数据

输入Collision数据
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInputColls() [2/2]

DllInputColls ( self,
inCll = [0]*20 )

传递 20 维float数组的碰撞数据的接口,用于处理仿真对象之间的碰撞检测。

  • 参数
    inCll最高20 维float数组的碰撞数据
    输入碰撞数据给DLL
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInputDoubCtrls()

DllInputDoubCtrls ( self,
in_doub_ctrls = [0]*28 )

综合模型外部控制指令输入接口,用于传递 28 维的双精度控制指令数据,参见 sendInDoubCtrls

  • 参数
    in_doub_ctrls最高28 维的double控制指令数据
    输入控制指令数据
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllInputSILs()

DllInputSILs ( self,
in_ints = [0]*8,
in_floats = [0]*20 )

将综合模型系统仿真输入数据传递给 DLL,参见 sendSILIntFloat

  • 参数
    in_ints最高8维整型数组,主要用于传递系统状态
    in_floats最高20维浮点型数组,主要用于传递系统状态
    输入SIL数据
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllinSIL28d()

DllinSIL28d ( self,
in_doub_ctrls = [0]*28 )

综合模型外部控制指令输入接口,用于传递 28 维的双精度控制指令数据,参见 sendInDoubCtrls

参数
in_doub_ctrls最高28 维的double控制指令数据
输入控制指令数据
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllOutCopterData()

DllOutCopterData ( self)

从 DLL 获取 32 维数据,包括飞行器的传感器读数、状态信息等

  • 返回
    返回的数据是一个 32 元素的 Python 列表
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DlloutVehileInfo60d()

DlloutVehileInfo60d ( self)

从 DLL 获取 60 维的载具三维信息数据。包括各种飞行器或车辆的状态数据。

  • 返回
    返回的数据是一个 60 维Python 列表。
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllReInitModel()

DllReInitModel ( self)

重新初始化仿真模型。

初始化模型
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ Dllstep()

Dllstep ( self)

执行一次仿真步骤。这是对 DLL 中仿真时间推进的基本调用。

执行仿真步骤
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ DllTerrainIn15d()

DllTerrainIn15d ( self,
terrain15d = [0]*15 )

输入三维场景的地形高度数据给DLL,用于仿真环境的地形建模,参见 sendTerrIn15d

  • 参数
    terrain15d最多15 维double型数据,地形高度数据
    输入地形高度数据
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ fillList()

fillList ( self,
data,
inLen,
fill = 0 )

填充或裁剪一个列表

  • 参数
    data数据
    inLen指定数据长度
    fill(默认值为0)填充值
    返回
    裁剪或者填充到长度为inLen的data
+ 这是这个函数的调用关系图:

◆ get3DDataBuf()

get3DDataBuf ( self)

提取载具模型的 3D 仿真数据out3Dvect并将其打包,以便通过网络转发给RflySim3D

+ 这是这个函数的调用关系图:

◆ ModelUpdate()

ModelUpdate ( self,
step_time )

手动更新仿真状态的接口

  • 参数
    step_time执行仿真步骤以推进仿真 step_time 秒
    首先获取仿真步长( DllGetStep0 ),然后根据给定的时间 step_time 和步长计算需要执行的步骤数 num_steps,并调用 Dllstep 完成这些步骤。最后,调用 Updata3Doutput 更新输出信息。
执行仿真步骤,仿真step_time秒
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ Recv20100Loop()

Recv20100Loop ( self)

线程的主循环,用于接收20100端口的数据并根据控制模式执行相应的控制命令。

+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ Recv30100Loop()

Recv30100Loop ( self)

线程的主循环,用于接收30100端口的数据并根据不同的数据类型执行相应处理。

+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ Send3DData()

Send3DData ( self)

将打包的 3D 数据通过 UDP 发送到端口 20010,用于与 RflySim3D 进行通信

+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendHILData()

SendHILData ( self)

发送硬件在环(HIL)仿真数据到指定的端口,通常用于与飞控系统交互

+ 这是这个函数的调用关系图:

◆ SendOutCopter()

SendOutCopter ( self)

发送仿真数据到30100端口,可用于日志记录

+ 这是这个函数的调用关系图:

◆ SendPosNED()

SendPosNED ( self,
x = 0,
y = 0,
z = 0,
yaw = 0 )

发送NED(北东地)地球参考系下的位置控制命令。

  • 参数
    xNED坐标系下的x坐标偏移值
    yNED坐标系下的y坐标偏移值
    zNED坐标系下的z坐标偏移值
    yaw偏航角度
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendSimData()

SendSimData ( self)

将与 Send3DData 同样的 3D 数据发送到端口 30100,用于仿真数据的传输

+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendUpdate3DMap()

SendUpdate3DMap ( self,
isSetSpeed = False )

用于向 RflySim3D发送命令,更新 3D 地图或设置RflySim3D仿真速度。

  • 参数
    isSetSpeed是否启用加速仿真。
+ 这是这个函数的调用关系图:

◆ SendVelFRD()

SendVelFRD ( self,
vx = 0,
vy = 0,
vz = 0,
yawRate = 0 )

发送FRD(前右下)机体参考系下的速度控制命令。

  • 参数
    vxFRD坐标系下的x方向速度
    vyFRD坐标系下的y方向速度
    vzFRD坐标系下的z方向速度
    yawRate偏航角速度
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelNED()

SendVelNED ( self,
vx = 0,
vy = 0,
vz = 0,
yawRate = 0 )

发送NED(北东地)地球参考系下的速度及偏航控制命令。

  • 参数
    vxNED坐标系下的x方向速度
    vyNED坐标系下的y方向速度
    vzNED坐标系下的z方向速度
    yawRate偏航角速度
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelNEDNoYaw()

SendVelNEDNoYaw ( self,
northvel = 0,
eastvel = 0,
downvel = 0 )

发送NED(北东地)地球参考系下的速度及偏航控制命令。

  • 参数
    northvelNED坐标系下的x方向速度
    eastvelNED坐标系下的y方向速度
    downvelNED坐标系下的z方向速度
+ 函数调用图:

◆ StartAutUpdate()

StartAutUpdate ( self,
UpdateFreq = 30,
speed = -1 )

用于启动自动更新循环,以指定的频率更新仿真状态。

  • 参数
    UpdateFreq更新频率,默认为30hz
    speed仿真速度倍数,默认为-1,使用默认仿真速度
+ 函数调用图:

◆ StartExtCtrl()

StartExtCtrl ( self)

用于启动外部控制功能,创建两个用于接收外部控制数据的UDP套接字,并开启两个线程来监听数据。

+ 函数调用图:

◆ StopAutUpdate()

StopAutUpdate ( self)

用于停止自动更新循环

◆ StopExtCtrl()

StopExtCtrl ( self)

停止外部控制,关闭UDP套接字并终止接收线程。

◆ Updata3Doutput()

Updata3Doutput ( self)

用于更新载具模型仿真输出,读取车辆当前的运动状态数据并更新到 out3Ddata 和 outHilData,并与地形数据进行交互。

+ 函数调用图:
+ 这是这个函数的调用关系图:

该类的文档由以下文件生成: