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

本类用于创建并控制飞行器对象(Vehicle)。包含对飞行器类型、位置、姿态、速度、飞行模式以及地图场景等的初始化和更新逻辑。 更多...

Public 成员函数

 __init__ (self, CopterID=1, Vehicletype=3, mapName='Grasslands', updatefreq=100, isBroadCast=False)
 构造函数,初始化飞行器的ID、类型、地图场景、更新频率以及其他控制参数。
 
 yawSat (self, yaw)
 对输入的偏航角进行角度约束,将偏航角限制在[-pi, pi]区间内。
 
 yawSat1 (self, yaw)
 对偏航角进行幅度限制,将偏航角限制在[-pi, pi]附近的范围内。
 
 RollSat (self, Roll)
 对滚转角进行幅度限制,将滚转角限制在[-pi/6, pi/6]范围内。
 
 sat (self, inPwm=0, thres=1)
 对输入的PWM值进行饱和限制,限制在[-thres, thres]范围内。
 
 initSimpleModel (self, intState=[0, 0, 0], targetIP='127.0.0.1', GPSOrigin=[40.1540302, 116.2593683, 50])
 初始化简化模型(质点模型)的运行环境,包括起始状态、目标IP地址和GPS原点设定。 启动模型更新循环与Mavlink数据监听线程。
 
 RecMavLoop (self)
 接收并处理来自Mavlink的控制数据循环线程。
 
 EndSimpleModel (self)
 停止质点模型的运行。
 
 enFixedWRWTO (self)
 固定翼滑跑(Runway TakeOff)相关预留函数(当前未实现)。

 
 TypeMask (self, EnList)
 根据EnList生成POSITION_TARGET_LOCAL_NED消息的type_mask位图。
 
 SimpleModelLoop (self)
 点质量模型的主循环函数,以固定频率更新模型状态、发送UAV状态和输出数据到RflySim3D。
 
 ModelStep (self, CurTime=-1)
 模型单步更新函数。
 
 SendUavState (self, CurTime)
 发送UAV的状态数据给Simulink,用于模拟PX4内部估计状态。
 
 ProssInput (self, dt)
 根据当前模式和控制指令对输入进行处理的函数。
 
 fixedPitchFromVel (self, vel)
 根据当前速度vel来确定飞行器的俯仰角。
 
 Step (self, dt)
 使用龙格-库塔法以及内部定义的动力学方程,进行状态更新(位置、速度、高度、航向等)。
 
 SendOutput (self, CurTime)
 将当前飞行器的真实状态(位置、姿态、速度)发送给RflySim3D以更新显示。
 
 SendPosNED (self, x=0, y=0, z=0, yaw=0)
 发送目标位置与偏航指令给PX4(NED坐标系)。 设置CurFlag=2表示进入某种自定义模式(例如Offboard位置控制),offMode=0表示SET_POSITION_TARGET_LOCAL_NED消息格式。 启用位置和偏航控制相关的使能位,禁用速度、加速度等其他通道。
 
 SendPosNEDNoYaw (self, x=0, y=0, z=0)
 发送目标位置指令给PX4(NED坐标系,不控制偏航)。 设置CurFlag=0表示Offboard模式,offMode=0表示SET_POSITION_TARGET_LOCAL_NED消息格式。 仅启用位置控制,使能位中不启用yaw控制通道。
 
 SendPosFRD (self, x=0, y=0, z=0, yaw=0)
 
 SendPosFRDNoYaw (self, x=0, y=0, z=0)
 
 SendVelNED (self, vx=0, vy=0, vz=0, yawrate=0)
 
 SendVelNEDNoYaw (self, vx, vy, vz)
 
 SendVelFRD (self, vx=0, vy=0, vz=0, yawrate=0)
 
 SendVelNoYaw (self, vx, vy, vz)
 
 sendBuf (self, buf, windowID=-1)
 
 sendUE4PosNew (self, copterID=1, vehicleType=3, PosE=[0, 0, 0], AngEuler=[0, 0, 0], VelE=[0, 0, 0], PWMs=[0] *8, runnedTime=-1, windowID=-1)
 
 SendCruiseSpeed (self, Speed=10)
 
 SendCopterSpeed (self, Speed=5)
 
 SendGroundSpeed (self, Speed=15)
 
 SendCruiseRadius (self, rad=20)
 
 SendMavArm (self, isArm=0)
 
 sendUE4Cmd (self, cmd, windowID=-1)
 
 SendVelYawAlt (self, vel=10, alt=-100, yaw=6.28)
 
 sendMavTakeOff (self, xM=0, yM=0, zM=0, YawRad=0, PitchRad=20/180.0 *math.pi)
 
 sendMavTakeOffGPS (self, lat, lon, alt, yawDeg=0, pitchDeg=15)
 

Public 属性

 udp_socket
 
 CopterID
 
 Vehicletype
 
 updatefreq
 
 isBroadCast
 
 map
 
 intStateX
 
 intStateY
 
 intAlt
 
 intStateYaw
 
 isInPointMode
 
 uavAngEular
 
 trueAngEular
 
 uavAngRate
 
 trueAngRate
 
 uavPosNED
 
 truePosNED
 
 uavVelNED
 
 trueVelNED
 
 uavPosGPS
 
 uavGlobalPos
 
 offMode
 
 EnList
 
 type_mask
 
 coordinate_frame
 
 pos
 
 vel
 
 acc
 
 yaw
 
 yawrate
 
 B
 
 velOff
 
 yawOff
 
 yawRateOff
 
 MotorRPMS
 
 velair
 
 MaxSpeed
 
 FwSpeedTrim
 
 FwLoiterRad
 
# 如果解锁了,才更新控制输入 isArmed
 
 CurFlag
 
 lastFlag
 
 TkOffYaw
 
 TkOffAccSpeed
 
 TkOffMaxSpeed
 
 TkOffNextFlag
 
 ClimbSlope
 
 ClimbStartSpeed
 
 ClimbAccSpeed
 
 ClimbMaxSpeed
 
# 达到起飞高度 ClimbMaxAlt
 
 ClimbNextFlag
 
 ForwardSpeed
 
 ForwardPosXYZ
 
 ForwardNextFlag
 
 CircleSpeed
 
 CircleRadius
 
 CirclePosXYZ
 
 CircleDir
 
 VehiclePitch
 
 VehicleYaw
 
 GPSOrigin
 
 geo
 
 lastTimeStep
 
 lastCtrl
 
 t3
 
 udpCtrlRec
 
 RecIPPort
 
 SendIpPort
 
# 如果t4Flag显示停止,则退出循环 t4Flag
 
 t4
 
 startTime3
 
 startTime
 
 lastTime3
 
 CircleStep
 
 uavVelAir
 
 yawf
 
 yawRatef
 
 velEf
 
 targetPosEf
 
 VelAirf
 
 trueAngRat
 
 uavTimeStmp
 
 trueTimeStmp
 
 GNDSpeed
 

详细描述

本类用于创建并控制飞行器对象(Vehicle)。包含对飞行器类型、位置、姿态、速度、飞行模式以及地图场景等的初始化和更新逻辑。

构造及析构函数说明

◆ __init__()

__init__ ( self,
CopterID = 1,
Vehicletype = 3,
mapName = 'Grasslands',
updatefreq = 100,
isBroadCast = False )

构造函数,初始化飞行器的ID、类型、地图场景、更新频率以及其他控制参数。

  • 参数
    CopterID(int)飞机ID,默认为1。
    Vehicletype(int)飞机类型编号,默认为3。
    mapName(str)地图名称,默认为'Grasslands'。
    updatefreq(int)往RflySim3D发送消息的频率,同时也是模型更新频率,默认为100。当updatefreq=0时,需外部调用step函数。
    isBroadCast(bool)是否将飞机三维数据广播到局域网其他电脑,默认为False。
+ 函数调用图:

成员函数说明

◆ EndSimpleModel()

EndSimpleModel ( self)

停止质点模型的运行。

  • 停止内部循环更新模型以及Mavlink数据监听循环,并回收线程资源。
 End the point mass model

◆ enFixedWRWTO()

enFixedWRWTO ( self)

固定翼滑跑(Runway TakeOff)相关预留函数(当前未实现)。

◆ fixedPitchFromVel()

fixedPitchFromVel ( self,
vel )

根据当前速度vel来确定飞行器的俯仰角。

  • 当vel > 20 m/s时,设定俯仰角为2度; 当5 < vel < 20 m/s时,俯仰角在2度到12度之间线性变化; 当vel <= 5 m/s时,设定俯仰角为12度。
    参数
    vel(float)当前飞行速度,单位:m/s
    返回
    pitch(float): 对应的俯仰角(弧度)
+ 这是这个函数的调用关系图:

◆ initSimpleModel()

initSimpleModel ( self,
intState = [0,0,0],
targetIP = '127.0.0.1',
GPSOrigin = [40.1540302,116.2593683,50] )

初始化简化模型(质点模型)的运行环境,包括起始状态、目标IP地址和GPS原点设定。 启动模型更新循环与Mavlink数据监听线程。

  • 参数
    intState(list)初始状态 [PosX(m), PosY(m), Yaw(deg)]
    targetIP(str)发送数据的目标IP地址
    GPSOrigin(list)GPS原点坐标 [lat, lon, alt]
     Init and start the point mass model for UAV control
    intAlt (unit m) is the init height of the vehicle on the UE4 map, which can be obtained from the CopterSim or UE4
    intState contains the PosX (m), PosY (m) and Yaw (degree) of the vehicle, which denotes the initial state of the vehicle
    it is the same as the value on CopterSim UI.
    targetIP: is the target IP address (Simulink rec PC) to send vehicle info
    
+ 函数调用图:

◆ ModelStep()

ModelStep ( self,
CurTime = -1 )

模型单步更新函数。

  • 根据当前时间与上一次更新的时间差dt对模型状态进行推进和计算。 包含对输入处理(ProssInput)、步进(Step)以及状态发送(SendUavState、SendOutput)。
    参数
    CurTime(float)当前时间戳,若为负数则自动获取当前时间。
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ ProssInput()

ProssInput ( self,
dt )

根据当前模式和控制指令对输入进行处理的函数。

  • 包括Offboard模式、起飞模式(滑跑和爬升阶段)以及平飞和盘旋模式。 不同的模式根据状态和目标点计算期望速度、偏航角和俯仰角,并存储在相应的成员变量中,为后续的模型更新提供参考值。
    参数
    dt(float)本次调用与上次调用之间的时间间隔,单位:秒
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ RecMavLoop()

RecMavLoop ( self)

接收并处理来自Mavlink的控制数据循环线程。

  • 当t4Flag被设为False时退出循环。 根据接收到的控制模式(ctrlMode)和数据(controls),执行相应的动作,如改变飞行模式、速度、高度、航向等。
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ RollSat()

RollSat ( self,
Roll )

对滚转角进行幅度限制,将滚转角限制在[-pi/6, pi/6]范围内。

  • 参数
    Roll(float)待处理的滚转角度(弧度值)
    返回
    返回处理后的滚转角度
     satuate the yaw angle from -pi to pi
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sat()

sat ( self,
inPwm = 0,
thres = 1 )

对输入的PWM值进行饱和限制,限制在[-thres, thres]范围内。

  • 参数
    inPwm(float)输入的PWM值
    thres(float)饱和限制阈值,默认值为1
    返回
    返回限制后的PWM值
    Saturation function for value inPwm with range thres
    if inPwm>thres, then inPwm=thres
    if inPwm<-thres,then inPwm=-thres
    
+ 这是这个函数的调用关系图:

◆ SendCopterSpeed()

SendCopterSpeed ( self,
Speed = 5 )
 send command to set the maximum speed of the multicopter

◆ SendCruiseRadius()

SendCruiseRadius ( self,
rad = 20 )
 Send command to change the Cruise Radius (m) of the aircraft
+ 这是这个函数的调用关系图:

◆ SendCruiseSpeed()

SendCruiseSpeed ( self,
Speed = 10 )
 Send command to change the Cruise speed (m/s) of the aircraft
+ 这是这个函数的调用关系图:

◆ SendGroundSpeed()

SendGroundSpeed ( self,
Speed = 15 )
 Send command to change the ground speed (m/s) of the aircraft

◆ sendMavTakeOff()

sendMavTakeOff ( self,
xM = 0,
yM = 0,
zM = 0,
YawRad = 0,
PitchRad = 20/180.0*math.pi )
 Send command to make aircraft takeoff to the desired local position (m)
+ 这是这个函数的调用关系图:

◆ sendMavTakeOffGPS()

sendMavTakeOffGPS ( self,
lat,
lon,
alt,
yawDeg = 0,
pitchDeg = 15 )
 Send command to make aircraft takeoff to the desired global position (degree)
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendOutput()

SendOutput ( self,
CurTime )

将当前飞行器的真实状态(位置、姿态、速度)发送给RflySim3D以更新显示。

  • 其中的truePosNED和trueAngEular等值均由当前状态(uavPosNED、uavAngEular等)和初始偏置(intStateX、intStateY、intAlt、intStateYaw)计算得出。 通过sendUE4PosNew函数将飞行器的最新状态发送给RflySim3D进行渲染。
    参数
    CurTime(float)当前时间戳,用于计算飞行时间并随同状态一起发送。
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendPosFRD()

SendPosFRD ( self,
x = 0,
y = 0,
z = 0,
yaw = 0 )
 Send vehicle targe position (m) to PX4 in the body forward-rightward-downward (FRD) frame with yaw control (rad)
when the vehicle fly above the ground, then z < 0
+ 函数调用图:

◆ SendPosFRDNoYaw()

SendPosFRDNoYaw ( self,
x = 0,
y = 0,
z = 0 )
 Send vehicle targe position (m) to PX4 in the body forward-rightward-downward (FRD) frame without yaw control (rad)
when the vehicle fly above the ground, then z < 0
+ 函数调用图:

◆ SendPosNED()

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

发送目标位置与偏航指令给PX4(NED坐标系)。 设置CurFlag=2表示进入某种自定义模式(例如Offboard位置控制),offMode=0表示SET_POSITION_TARGET_LOCAL_NED消息格式。 启用位置和偏航控制相关的使能位,禁用速度、加速度等其他通道。

参数
x(float)目标位置X方向(北向),单位:米
y(float)目标位置Y方向(东向),单位:米
z(float)目标位置Z方向(下为正),当飞行器高于地面时z<0
yaw(float)目标偏航角(弧度)
 Send vehicle targe position (m) to PX4 in the earth north-east-down (NED) frame with yaw control (rad)
when the vehicle fly above the ground, then z < 0
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendPosNEDNoYaw()

SendPosNEDNoYaw ( self,
x = 0,
y = 0,
z = 0 )

发送目标位置指令给PX4(NED坐标系,不控制偏航)。 设置CurFlag=0表示Offboard模式,offMode=0表示SET_POSITION_TARGET_LOCAL_NED消息格式。 仅启用位置控制,使能位中不启用yaw控制通道。

参数
x(float)目标位置X方向(北向),单位:米
y(float)目标位置Y方向(东向),单位:米
z(float)目标位置Z方向(下为正),当飞行器高于地面时z<0
 Send vehicle targe position (m) to PX4 in the earth north-east-down (NED) frame without yaw control (rad)
when the vehicle fly above the ground, then z < 0
+ 函数调用图:

◆ SendUavState()

SendUavState ( self,
CurTime )

发送UAV的状态数据给Simulink,用于模拟PX4内部估计状态。

  • 数据结构参考 outHILStateShort: int checksum; //校验位1234567890 int32_t gpsHome[3]; // Home GPS位置(lat,long以度*1e7,alt以m*1e3向上为正) float AngEular[3]; // 估计的欧拉角,单位:弧度 float localPos[3]; // 估计的本地位置,NED,单位:m float localVel[3]; // 估计的本地速度,NED,单位:m/s 打包后发送给设定的IP和端口(SendIpPort),用于与Simulink通信。
    参数
    CurTime(float)当前时间戳,用于标记发送数据的时间(本函数中未使用)。
+ 这是这个函数的调用关系图:

◆ sendUE4Cmd()

sendUE4Cmd ( self,
cmd,
windowID = -1 )
send command to control the display style of RflySim3D
    The available command are list as follows, the command string is as b'RflyShowTextTime txt time'
    RflyShowTextTime(String txt, float time)\\ let UE4 show txt with time second
    RflyShowText(String txt)\\  let UE4 show txt 5 second
    RflyChangeMapbyID(int id)\\ Change the map to ID (int number)
    RflyChangeMapbyName(String txt)\\ Change to map with name txt
    RflyChangeViewKeyCmd(String key, int num) \\ the same as press key + num on UE4
    RflyCameraPosAngAdd(float x, float y, float z,float roll,float pitch,float yaw) \\ move the camera with x-y-z(m) and roll-pitch-yaw(degree) related to current pos
    RflyCameraPosAng(float x, float y, float z, float roll, float pitch, float yaw) \\ set the camera with x-y-z(m) and roll-pitch-yaw(degree) related to UE origin
    RflyCameraFovDegrees(float degrees) \\ change the cameras fov (degree)
    RflyChange3DModel(int CopterID, int veTypes=0) \\ change the vehicle 3D model to ID
    RflyChangeVehicleSize(int CopterID, float size=0) \\change vhielce's size
    RflyMoveVehiclePosAng(int CopterID, int isFitGround, float x, float y, float z, float roll, float pitch, float yaw) \\ move the vehicle's  x-y-z(m) and roll-pitch-yaw(degree) related to current pos
    RflySetVehiclePosAng(int CopterID, int isFitGround, float x, float y, float z, float roll, float pitch, float yaw) \\ set the vehilce's x-y-z(m) and roll-pitch-yaw(degree) related to UE origin
    RflyScanTerrainH(float xLeftBottom(m), float yLeftBottom(m), float xRightTop(m), float yRightTop(m), float scanHeight(m), float scanInterval(m)) \\ send command to let UE4 scan the map to generate png and txt files
    RflyCesiumOriPos(double lat, double lon, double Alt) \\ change the lat, lon, Alt (degrees) of the Cesium map origin
    RflyClearCapture \\ clear the image capture unit
    struct Ue4CMD0{
        int checksum;
        char data[52];
    } i52s
    struct Ue4CMD{
        int checksum;
        char data[252];
    } i252s            
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendUE4PosNew()

sendUE4PosNew ( self,
copterID = 1,
vehicleType = 3,
PosE = [0,0,0],
AngEuler = [0,0,0],
VelE = [0,0,0],
PWMs = [0]*8,
runnedTime = -1,
windowID = -1 )
 send the position & angle information to RflySim3D to create a new 3D model or update the old model's states
    # //输出到模拟器的数据
    # struct SOut2SimulatorSimpleTime {
    #     int checkSum; //1234567890
    #     int copterID;  //Vehicle ID
    #     int vehicleType;  //Vehicle type
    #     float PWMs[8];
    #     float VelE[3];
    #     float AngEuler[3];  //Vehicle Euler angle roll pitch yaw (rad) in x y z
    #     double PosE[3];   //NED vehicle position in earth frame (m)
    #     double runnedTime; //Current Time stamp (s)
    # };
    #struct.pack 3i14f4d
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelFRD()

SendVelFRD ( self,
vx = 0,
vy = 0,
vz = 0,
yawrate = 0 )
 Send vehicle targe speed (m/s) to PX4 in the body forward-rightward-downward (FRD) frame with yawrate control (rad/s)
when the vehicle fly upward, the vz < 0
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelNED()

SendVelNED ( self,
vx = 0,
vy = 0,
vz = 0,
yawrate = 0 )
 Send targe vehicle speed (m/s) to PX4 in the earth north-east-down (NED) frame with yawrate (rad/s)
when the vehicle fly upward, the vz < 0
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelNEDNoYaw()

SendVelNEDNoYaw ( self,
vx,
vy,
vz )
 Send targe vehicle speed (m/s) to PX4 in the earth north-east-down (NED) frame without yaw control
when the vehicle fly upward, the vz < 0
+ 函数调用图:

◆ SendVelNoYaw()

SendVelNoYaw ( self,
vx,
vy,
vz )
 Send vehicle targe speed (m/s) to PX4 in the body forward-rightward-downward (FRD) frame without yawrate control (rad)
when the vehicle fly upward, the vz < 0
+ 函数调用图:

◆ SendVelYawAlt()

SendVelYawAlt ( self,
vel = 10,
alt = -100,
yaw = 6.28 )
 Send vehicle targe position (m) to PX4 in the earth north-east-down (NED) frame with yaw control (rad)
when the vehicle fly above the ground, then z < 0
+ 这是这个函数的调用关系图:

◆ SimpleModelLoop()

SimpleModelLoop ( self)

点质量模型的主循环函数,以固定频率更新模型状态、发送UAV状态和输出数据到RflySim3D。

  • 当isInPointMode为False时退出循环。 内部使用time.sleep维持固定更新频率,并调用ModelStep函数更新状态和输出。
 This is the dead loop for point mass model
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ Step()

Step ( self,
dt )

使用龙格-库塔法以及内部定义的动力学方程,进行状态更新(位置、速度、高度、航向等)。

  • 根据当前模式(CurFlag)和飞行器状态,求解飞行器在dt时间间隔内的状态演进。 包含高度控制、空速控制、航向控制以及水平面位置积分等过程。
    参数
    dt(float)时间步长,单位为秒。
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ TypeMask()

TypeMask ( self,
EnList )

根据EnList生成POSITION_TARGET_LOCAL_NED消息的type_mask位图。

  • 参见:https://mavlink.io/en/messages/common.html#POSITION_TARGET_TYPEMASK
    参数
    EnList(list)含有bool的列表,用于决定启用或禁用指定参数(Pos、Vel、Acc、Force、Yaw、Yawrate)。
    返回
    返回生成的type_mask整数值。
     Obtain the bitmap for offboard message
    https://mavlink.io/en/messages/common.html#POSITION_TARGET_TYPEMASK
    
+ 这是这个函数的调用关系图:

◆ yawSat()

yawSat ( self,
yaw )

对输入的偏航角进行角度约束,将偏航角限制在[-pi, pi]区间内。

  • 参数
    yaw(float)待约束的偏航角度(单位:弧度)
    返回
    返回约束后的偏航角度,范围在[-pi, pi]之间
     satuate the yaw angle from -pi to pi
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ yawSat1()

yawSat1 ( self,
yaw )

对偏航角进行幅度限制,将偏航角限制在[-pi, pi]附近的范围内。

  • 参数
    yaw(float)待处理的偏航角度(弧度值)
    返回
    返回处理后的偏航角度
     satuate the yaw angle from -pi to pi
    
+ 函数调用图:

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