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

PX4MavCtrler结构体类 更多...

+ 类 PX4MavCtrler 继承关系图:

Public 成员函数

 __init__ (self, ID=1, ip='127.0.0.1', Com='udp', port=0)
 
 fillList (self, data, inLen, fill=0)
 填充或裁剪一个列表
 
 sendStartMsg (self, copterID=-1)
 向无人机发送启动信号
 
 waitForStartMsg (self)
 等待来自 sendStartMsg 函数发送的启动信号
 
 initPointMassModel (self, intAlt=0, intState=[0, 0, 0])
 初始化并启动用于无人机控制
 
 EndPointMassModel (self)
 终止模型
 
 yawSat (self, yaw)
 调整偏航角在-π到π之间
 
 PointMassModelLoop (self)
 控制无人机在点质量模型下循环运行
 
 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)
 发送无人机位姿和状态到Rflysim3D
 
 InitTrueDataLoop (self)
 初始化真实数据接收机制
 
 EndTrueDataLoop (self)
 结束真实数据接收的循环
 
 SendOffAll (self, type_mask=PosTypeMask(), coordinate_frame=1, pos=[0, 0, 0], vel=[0, 0, 0], acc=[0, 0, 0], yaw=0, yawrate=0)
 设置和准备发送无人机的位置信息和控制参数
 
 SendAttAll (self, type_mask=AttTypeMask(), q=[1, 0, 0, 0], body_rate=[0, 0, 0], thrust=0)
 结束真实数据接收的循环
 
 InitMavLoop (self, UDPMode=2)
 初始化 MAVLink 通信循环,并与coptersim进行通信
 
 endMavLoop (self)
 结束通信
 
 SendVisionPosition (self, x, y, z, yaw)
 发送视觉定位数据给 MAVLink 连接
 
 SendHILGps (self, lat=40.1540302, lon=116.2593683, alt=50, vel=0, vn=0, ve=0, vd=0, cog=0, time_usec=-1, eph=0.3, epv=0.4, fix_type=3, satellites_visible=15)
 发送GPS仿真数据给 MAVLink 连接
 
 SendRedisData (self, key, buf)
 发送数据到redis
 
 SendBuf (self, buf)
 发送数据
 
 SendBufTrue (self, buf, port=None)
 发送数据
 
 sat (self, inPwm=0, thres=1)
 饱和操作的函数,确保输入值在正负阈值内
 
 SendMavCmdLong (self, command, param1=0, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0)
 将 MAVLink 的长指令消息发送到 Pixhawk 系统
 
 SendQgcCmdLong (self, command, param1=0, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0)
 将 MAVLink 的长指令消息发送到 QGC
 
 sendMavOffboardCmd (self, type_mask, coordinate_frame, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)
 发送Offboard命令到PX4
 
 TypeMask (self, EnList)
 获取offboard消息的位图
 
 sendMavOffboardAPI (self, type_mask=0, coordinate_frame=0, pos=[0, 0, 0], vel=[0, 0, 0], acc=[0, 0, 0], yaw=0, yawrate=0)
 发送Offboard命令到PX4
 
 sendUDPSimpData (self, ctrlMode, ctrls)
 发送UDP简单数据
 
 sendPX4UorbRflyCtrl (self, data=[0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], modes=1, flags=1)
 发送UDP简单数据
 
 SendVelNED (self, vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan)
 北东地坐标系下操控飞机
 
 SendVelNEDNoYaw (self, vx, vy, vz)
 北东地坐标系下操控飞机
 
 SendVelFRD (self, vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan)
 前右下坐标系下操控飞机
 
 SendAttPX4 (self, att=[0, 0, 0, 0], thrust=0.5, CtrlFlag=0, AltFlg=0)
 前右下坐标系以目标姿态控制飞机
 
 EulerToQuat (self, Euler)
 将欧拉角转化为四元数
 
 SendAccPX4 (self, afx=math.nan, afy=math.nan, afz=math.nan, yawValue=math.nan, yawType=0, frameType=0)
 发送目标加速度给PX4
 
 SendVelNoYaw (self, vx=math.nan, vy=math.nan, vz=math.nan)
 机体前右下坐标系下控制飞机
 
 SendPosNED (self, x=math.nan, y=math.nan, z=math.nan, yaw=math.nan)
 地球北东地坐标系下控制飞机到指定位置
 
 SendVelYawAlt (self, vel=10, yaw=6.28, alt=-100)
 地球北东地坐标系下控制飞机
 
 SendPosGlobal (self, lat=0, lon=0, alt=0, yawValue=0, yawType=0)
 地球北东地坐标系下控制飞机到目标全球位置
 
 SendPosNEDNoYaw (self, x=math.nan, y=math.nan, z=math.nan)
 地球北东地坐标系下控制飞机到目标位置
 
 SendPosFRD (self, x=math.nan, y=math.nan, z=math.nan, yaw=math.nan)
 机体前右下坐标系下控制飞机到目标位置
 
 SendPosFRDNoYaw (self, x=math.nan, y=math.nan, z=math.nan)
 机体前右下坐标系下控制飞机到目标位置
 
 SendPosNEDExt (self, x=math.nan, y=math.nan, z=math.nan, mode=3, isNED=True)
 机体前右下坐标系下控制飞机到目标位置
 
 enFixedWRWTO (self)
 发送指令使飞机起飞
 
 SendCruiseSpeed (self, Speed=0)
 发送指定改变飞机的巡航速度
 
 SendCopterSpeed (self, Speed=0)
 发送设定多旋翼飞行器的最大速度
 
 SendGroundSpeed (self, Speed=0)
 发送指定改变飞机的地面速度
 
 SendCruiseRadius (self, rad=0)
 发送指定改变飞机的巡航半径
 
 sendTakeoffMode (self, alt=0)
 发送指定使飞机起飞
 
 initOffboard (self)
 发送命令进入offboard模式,消息发送频率为30HZ
 
 initOffboardAcc (self)
 发送命令进入offboard模式,消息发送频率为30HZ
 
 initOffboardAtt (self)
 发送命令进入offboard模式,消息发送频率为30HZ
 
 initOffboard2 (self)
 发送命令进入offboard模式,消息发送频率为30HZ
 
 sendMavTakeOff (self, xM=0, yM=0, zM=0, YawRad=0, PitchRad=0)
 发送命令让飞行器起飞到指定位置
 
 sendMavTakeOffLocal (self, xM=0, yM=0, zM=0, YawRad=0, PitchRad=0, AscendRate=2)
 发送指令使飞机从指定的本地位置起飞,并允许设置俯仰角、偏航角和上升速率
 
 sendMavTakeOffGPS (self, lat, lon, alt, yawDeg=0, pitchDeg=15)
 发送指令使飞机从指定的本地位置起飞,并允许设置俯仰角、偏航角和上升速率
 
 sendMavLand (self, xM, yM, zM)
 发送指令使飞机降落到指定位置
 
 sendMavLandGPS (self, lat, lon, alt)
 发送指令使飞机降落到指定全球位置
 
 endOffboard (self)
 退出offboard模式,停止消息发送
 
 sendMavSetParam (self, param_id, param_value, param_type)
 向 Pixhawk 发送命令更改其参数
 
 SendHILCtrlMsg (self, ctrls=[0] *16, idx=0, flags=1)
 发送 hil_actuator_controls 消息发送到 Pixhawk
 
 SendHILCtrlMsg1 (self)
 发送 debug_vect 消息发送到 Pixhawk
 
 SendMavArm (self, isArm=1)
 发送指令到 Pixhawk 使其上锁/解锁
 
 initRCSendLoop (self, Hz=30)
 初始化遥控器发送循环
 
 endRCSendLoop (self)
 结束遥控器发送循环
 
 RcSendLoop (self)
 循环发送遥控器信号
 
 SendRCPwms (self, Pwms)
 更新遥控器 PWM 信号
 
 SendRcOverride (self, ch1=1500, ch2=1500, ch3=1100, ch4=1500, ch5=1100, ch6=1100, ch7=1500, ch8=1500)
 通过 MAVLink 协议向 PX4 发送遥控信号覆盖命令
 
 sendMavManualCtrl (self, x=0, y=0, z=0, r=0)
 通过 MAVLink 协议向 PX4 发送手动控制信号
 
 SendSetMode (self, mainmode, cusmode=0)
 发送 MAVLink 命令到 PX4 以更改飞行模式
 
 stopRun (self)
 停止 MAVLink 的监听循环
 
 getTrueDataMsg (self)
 从30100串口监听真是数据,更新Pixhawk状态
 
 getPX4DataMsg (self)
 从40100串口监听真是数据,更新Pixhawk状态
 
 setMsgDict (self, stName)
 设置消息字典的状态
 
 netForwardData (self)
 用于网络通信的事件信号
 
 GetUDPRedisBuf (self, sock)
 从套接字或 Redis 订阅中获取数据
 
 getMavMsg (self)
 开始循环监听来自20100系列端口或COM端口的MAVLink数据,更新Pixhawk状态
 
 OffboardSendMode (self)
 循环发送MAVLink的offboard模式控制命令
 
 sendRebootPix (self, copterID, delay=-1)
 发送消息重启飞机仿真
 
 sendCustomData (self, CopterID, data=[0] *16, checksum=123456, port=50000, IP='127.0.0.1')
 发送一个16维double型数据到指定端口,本接口可用于与Simulink通信
 
 setGPSOriLLA (self, LonLatAlt)
 设置GPS的原点位置,并根据提供的GPS坐标计算位置偏差
 
 sendSILIntFloat (self, inSILInts=[0] *8, inSILFLoats=[0] *20, copterID=-1)
 

Public 属性

 isInPointMode
 
 isCom
 
 Com
 
 baud
 
 isRealFly
 
 ip
 
 isRedis
 
 CopterID
 
 port
 
 ComName
 
 redisCon
 
 redisHost
 
 redisPort
 
 redisPass
 
 pubsub
 
 redisKey
 
 f
 
 stopFlag
 
 mav0
 
 udp_socket
 
 udp_socketUDP
 
 udp_socketTrue
 
 udp_socketPX4
 
 udp_socketUE4
 
 uavTimeStmp
 
 trueTimeStmp
 
 uavAngEular
 
 trueAngEular
 
 uavAngRate
 
 trueAngRate
 
 uavPosNED
 
 truePosNED
 
 uavVelNED
 
 trueVelNED
 
 isVehicleCrash
 
 isVehicleCrashID
 
 uavPosGPS
 
 uavPosGPSHome
 
 uavGlobalPos
 
 trueAngQuatern
 
 uavAngQuatern
 
 trueMotorRPMS
 
 uavMotorRPMS
 
 trueAccB
 
 uavAccB
 
 uavGyro
 
 uavMag
 
 uavVibr
 
 out3Ddata
 
 truePosGPS
 
 trueSimulinkData
 
 useCustGPSOri
 
 trueGpsUeCenter
 
 GpsOriOffset
 
 uavThrust
 
 zInt
 
 EnList
 
 type_mask
 
 coordinate_frame
 
 pos
 
 vel
 
 acc
 
 yaw
 
 yawrate
 
 isInOffboard
 
 isArmed
 
 hasSendDisableRTLRC
 
 UDPMode
 
 startTime
 
 MaxSpeed
 
 stopFlagTrueData
 
 hasTrueDataRec
 
 isPX4Ekf3DFixed
 
 isArmerror
 
 truegyro
 
 truemag
 
 RCPWMs
 
 isRCLoop
 
 tRCHz
 
 isFailsafeEn
 
 FailsafeInfo
 
 px4ext
 
 px4extTrue
 
 offMode
 
 ctrlMode
 
 cmdVel
 
 system_status
 
 connected
 
 batInfo
 
 nId
 
 isOffBoard
 
 hasMsgDict
 
 trigMsgVect
 
 hasMsgEvent
 
 trueMsgEvent
 
 geo
 
 netEvent
 
 uavEvent
 
 uavMsg
 
 t1
 
 intAlt
 
 intStateX
 
 intStateY
 
 intStateYaw
 
 t3
 
 startTime3
 
 lastTime3
 
 trueAngRat
 
 tTrue
 
 stopFlagPX4Data
 
 tPX4
 
 the_connection
 
 lastTime
 
 t2
 
 lastTime2
 
 startTime2
 
 tRC
 

Protected 属性

 _active
 

详细描述

PX4MavCtrler结构体类

创建一个通信实例
ID: 如果ID<=10000则表示飞机的CopterID号。如果ID>10000,例如20100这种,则表示通信端口号port。按平台规则,port=20100+CopterID*2-2(为了兼容旧接口的过渡定义,将来ID只表示CopterID)。
ip: 数据向外发送的IP地址。默认是发往本机的127.0.0.1的IP;在分布式仿真时,也可以指定192.168打头的局域网电脑IP;也可以使用255.255.255.255的广播地址(会干扰网络其他电脑)
Com: 与Pixhawk的连接模式。
    Com='udp',表示使用默认的udp模式接收数据,这种模式下,是接收CopterSim转发的PX4的MAVLink消息(或UDP_full,simple)消息包
             使用port+1端口收和port端口发(例如,1号飞机是20101端口收,20100端口发,与CopterSim对应)。
    Com='COM3'(Widnows下)或 Com='/dev/ttyUSB0'(Linux系统,也可能是ttyS0、ttyAMA0等),表示通过USB线(或者数传)连接飞控,使用默认57600的波特率。注意:波特率使用port口设置,默认port=0,会重映射为57600
    Com='Direct',表示UDP直连模式(对应旧版接口的真机模式),这种模式下使用使用同一端口收发(端口号有port设置),例如Com='Direct',port=15551,表示通过15551这一个端口来收发数据
    注意:COM模式和Direct模式下,ID只表示飞机的ID号,而不表示端口号
    Com='redis':使用Redis模式通信,服务器地址为ip,服务器端口为port
port: UDP模式下默认情况下设为0,会自动根据IP填充,按平台规则,port=20100+CopterID*2-2。如果这里赋值大于0,则会强制使用port定义的端口。
      COM模式下,Port默认表示波特率self.baud=port。如果port=0,则会设置self.baud=57600
      Direct模式下,Port默认表示收发端口号(使用相同端口)
      redis模式下,Port对应服务器端口号self.redisPort = port。如果port=0,则self.redisPort=6379为平台默认值。

接口示例:
UDP模式
PX4MavCtrler(1) # 默认IP
PX4MavCtrler(1,'192.168.31.24') # 指定IP,用于远程控制

串口模式
PX4MavCtrler(1,'127.0.0.1','com1',57600) # 指定串口,并设置波特率

PX4MavCtrler(1,'192.168.31.105','Direct',15552) # 真机直连Direct方式,远端IP为'192.168.31.105',端口15552
注意:下面这里是旧版接口,便于用户参考旧规则进行接口升级
For hardware connection PX4MavCtrler('COM:baud','IP:CopterID') format
Windows use format PX4MavCtrler('COM3') or PX4MavCtrler('COM3:115200') for Pixhawk USB port connection
Windows use format 'COM4:57600' for Pixhawk serial port connection
Linux use format PX4MavCtrler('/dev/ttyUSB0') or PX4MavCtrler('/dev/ttyUSB0:115200') for USB, or '/dev/ttyAMA0:57600' for Serial port (RaspberryPi example)
PX4MavCtrler('COM3:115200:2'): the second input is the CopterID, in this case CopterID = 2

For real flight
PX4MavCtrler(port,'IP:CopterID:Flag'), Flag set to 1 to enable real flight com mode
for example PX4MavCtrler(15551,'192.168.1.123:1:1') to set IP=192.168.1.123, port=15551,CopterID=1,Flag=1

PX4 MAVLink listen and control API and RflySim3D control API

成员函数说明

◆ endMavLoop()

endMavLoop ( self)

结束通信

  • 参数
    返回
     The same as stopRun(), stop message listenning from 20100 or serial port
    
+ 函数调用图:

◆ endOffboard()

endOffboard ( self)

退出offboard模式,停止消息发送

  • 返回
    无 stop Offboard mode
     Send command to px4 to out offboard mode, and stop the message sending loop
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ EndPointMassModel()

EndPointMassModel ( self)

终止模型

  • 参数
    返回
     End the point mass model
    

◆ endRCSendLoop()

endRCSendLoop ( self)

结束遥控器发送循环

  • 参数
    返回

◆ EndTrueDataLoop()

EndTrueDataLoop ( self)

结束真实数据接收的循环

  • 参数
    返回
     End the true data mode
    

◆ enFixedWRWTO()

enFixedWRWTO ( self)

发送指令使飞机起飞

  • 参数
    返回

     Send command to enable takeoff on Runway of the aircraft
    
+ 函数调用图:

◆ EulerToQuat()

EulerToQuat ( self,
Euler )

将欧拉角转化为四元数

  • 参数
    Euler欧拉角
    返回
    四元数

◆ fillList()

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

填充或裁剪一个列表

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

◆ getMavMsg()

getMavMsg ( self)

开始循环监听来自20100系列端口或COM端口的MAVLink数据,更新Pixhawk状态

  • 参数
    返回
     Start loop to listen mavlink data from 20100 series port or COM port
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ getPX4DataMsg()

getPX4DataMsg ( self)

从40100串口监听真是数据,更新Pixhawk状态

  • 参数
    返回
     Start loop to listen True data from 40100 serial data
    
+ 这是这个函数的调用关系图:

◆ getTrueDataMsg()

getTrueDataMsg ( self)

从30100串口监听真是数据,更新Pixhawk状态

  • 参数
    返回
     Start loop to listen True data from 30100 serial data
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ GetUDPRedisBuf()

GetUDPRedisBuf ( self,
sock )

从套接字或 Redis 订阅中获取数据

  • 参数
    sock套接字
    返回
    buf 接收到的数据
+ 这是这个函数的调用关系图:

◆ InitMavLoop()

InitMavLoop ( self,
UDPMode = 2 )

初始化 MAVLink 通信循环,并与coptersim进行通信

  • 参数
    UDPMode(默认值为2)UDP连接模式
    • 0表示UDP_Full Mode
    • 1表示UDP_Simple Mode
    • 2表示MAVLink_Full Mode
    • 3表示MAVLink_Simple Mode
    • 4表示MAVLink_NoSend Mode
    • 5表示MAVLink_NoGPS Mode
    • 6表示MAVLink_NoVision Mode
    返回
     Initialize MAVLink listen loop from CopterSim
        0 and 1 for UDP_Full and UDP_Simple Modes, 2 and 3 for MAVLink_Full and MAVLink_Simple modes, 4 for MAVLink_NoSend, 5 for MAVLink_NoGPS, 6 for MAVLink_NoVision
        The default mode is 2 i.e., MAVLink_Full
    
+ 函数调用图:

◆ initOffboard()

initOffboard ( self)

发送命令进入offboard模式,消息发送频率为30HZ

  • 参数
    返回
     Send command to make px4 enter offboard mode, and start to send offboard message 30Hz
    
+ 函数调用图:

◆ initOffboard2()

initOffboard2 ( self)

发送命令进入offboard模式,消息发送频率为30HZ

  • 参数
    返回
     Send command to make px4 enter offboard mode, and start to send offboard message 30Hz
    
+ 函数调用图:

◆ initOffboardAcc()

initOffboardAcc ( self)

发送命令进入offboard模式,消息发送频率为30HZ

  • 参数
    返回
     Send command to make px4 enter offboard mode, and start to send offboard message 30Hz
    
+ 函数调用图:

◆ initOffboardAtt()

initOffboardAtt ( self)

发送命令进入offboard模式,消息发送频率为30HZ

  • 参数
    返回
     Send command to make px4 enter offboard mode, and start to send offboard message 30Hz
    
+ 函数调用图:

◆ initPointMassModel()

initPointMassModel ( self,
intAlt = 0,
intState = [0,0,0] )

初始化并启动用于无人机控制

  • 参数
    intAlt(默认值为0)无人机的初始高度
    intState(默认值为[0,0,0])无人机的X坐标、Y坐标和偏航角
    返回
     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.
    
+ 函数调用图:

◆ initRCSendLoop()

initRCSendLoop ( self,
Hz = 30 )

初始化遥控器发送循环

  • 参数
    Hz(默认值为30)发送频率
    返回
+ 函数调用图:

◆ InitTrueDataLoop()

InitTrueDataLoop ( self)

初始化真实数据接收机制

  • 参数
    返回
     Initialize UDP True data listen loop from CopterSim through 30100 series ports
    
+ 函数调用图:

◆ netForwardData()

netForwardData ( self)

用于网络通信的事件信号

  • 参数
    返回
+ 这是这个函数的调用关系图:

◆ OffboardSendMode()

OffboardSendMode ( self)

循环发送MAVLink的offboard模式控制命令

  • 参数
    返回
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ PointMassModelLoop()

PointMassModelLoop ( self)

控制无人机在点质量模型下循环运行

  • 参数
    返回
     This is the dead loop for point mass model
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ RcSendLoop()

RcSendLoop ( self)

循环发送遥控器信号

  • 参数
    返回
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sat()

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

饱和操作的函数,确保输入值在正负阈值内

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

◆ SendAccPX4()

SendAccPX4 ( self,
afx = math.nan,
afy = math.nan,
afz = math.nan,
yawValue = math.nan,
yawType = 0,
frameType = 0 )

发送目标加速度给PX4

  • 参数
    afx(默认值为NaN,表示不控制本通道)x方向的加速度
    afy(默认值为NaN,表示不控制本通道)y方向的加速度
    afz(默认值为NaN,表示不控制本通道)z方向的加速度
    yawValue(默认值为0) 偏航角速度
    yawType(默认值为0) 姿态控制模式
    • 0表示没有无偏航和偏航速率
    • 1表示偏航角控制
    • 2表示偏航速率控制
    frameType(默认值为0) 偏航角速率
    • 0表示地球 NED(北东地)坐标系
    • 1表示机体 FRD(前右下)坐标系
    返回
     Send a targe acceleration (m/s^2) to PX4
    
+ 函数调用图:

◆ SendAttAll()

SendAttAll ( self,
type_mask = AttTypeMask(),
q = [1, 0, 0, 0],
body_rate = [0,0,0],
thrust = 0 )

结束真实数据接收的循环

  • 参数
    type_mask类型掩码
    q(默认值为[0,0,0])四元数
    body_rate(默认值为[0,0,0])机体速率列表,表示机体各个轴向的旋转速率
    thrust(默认值为0)推力
    返回
+ 函数调用图:

◆ SendAttPX4()

SendAttPX4 ( self,
att = [0,0,0,0],
thrust = 0.5,
CtrlFlag = 0,
AltFlg = 0 )

前右下坐标系以目标姿态控制飞机

  • 参数
    att(默认值为[0,0,0,0]) 飞行器姿态
    thrust(默认值为0.5) 推力值
    CtrlFlag(默认值为0) 姿态控制模式
    • 0表示 att 是一个三维向量,表示欧拉角,滚转、俯仰、偏航,单位为度
    • 1表示 att 是一个三维向量,表示欧拉角,滚转、俯仰、偏航,单位为弧度
    • 2表示 att 是一个四维向量,表示四元数
    • 3表示 att 是一个三维向量,表示旋转速率,滚转、俯仰、偏航,单位为弧度/秒
    • 4表示 att 是一个三维向量,表示旋转速率,滚转、俯仰、偏航,单位为度/秒
    AltFlg(默认值为0) 偏航角速率
    • 0表示 thrust 被定义为 "集体推力,归一化到 0 .. 1(对于能够反向推力的飞行器则为 -1 .. 1)"
    • 1表示 thrust 为期望的高度
    返回
     Send vehicle targe attitude to PX4 in the body forward-rightward-downward (FRD) frame
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendBuf()

SendBuf ( self,
buf )

发送数据

  • 参数
    buf发送的数据
    返回
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendBufTrue()

SendBufTrue ( self,
buf,
port = None )

发送数据

  • 参数
    buf发送的数据
    port(默认值为None)端口号
    返回
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendCopterSpeed()

SendCopterSpeed ( self,
Speed = 0 )

发送设定多旋翼飞行器的最大速度

  • 参数
    Speed(默认值为0) 速度
    返回

     send command to set the maximum speed of the multicopter
    
+ 函数调用图:

◆ SendCruiseRadius()

SendCruiseRadius ( self,
rad = 0 )

发送指定改变飞机的巡航半径

  • 参数
    rad(默认值为0) 半径
    返回

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

◆ SendCruiseSpeed()

SendCruiseSpeed ( self,
Speed = 0 )

发送指定改变飞机的巡航速度

  • 参数
    Speed(默认值为0) 速度
    返回

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

◆ sendCustomData()

sendCustomData ( self,
CopterID,
data = [0]*16,
checksum = 123456,
port = 50000,
IP = '127.0.0.1' )

发送一个16维double型数据到指定端口,本接口可用于与Simulink通信

  • 参数
    CopterID飞机编号
    data(默认值为16维0向量)要发送的数据
    checksum(默认值123456)用于数据校验
    port(默认值50000)数据发送的端口
    IP(默认值127.0.0.1)数据发送的IP地址
    返回
     Send 16d message to desired IP and port
    

◆ SendGroundSpeed()

SendGroundSpeed ( self,
Speed = 0 )

发送指定改变飞机的地面速度

  • 参数
    Speed(默认值为0) 速度
    返回

     Send command to change the ground speed (m/s) of the aircraft
    
+ 函数调用图:

◆ SendHILCtrlMsg()

SendHILCtrlMsg ( self,
ctrls = [0]*16,
idx = 0,
flags = 1 )

发送 hil_actuator_controls 消息发送到 Pixhawk

  • 参数
    ctrls(默认值为[0]*16)执行器控制值的列表
    idx(默认值为0)消息的索引
    flags(默认值为1)一个flags标志位,给Simulink控制器用于模式切换
    返回
     Send hil_actuator_controls command to PX4, which will be transferred to uORB message rfly_ctrl
    https://mavlink.io/en/messages/common.html#HIL_ACTUATOR_CONTROLS
    
+ 函数调用图:

◆ SendHILCtrlMsg1()

SendHILCtrlMsg1 ( self)

发送 debug_vect 消息发送到 Pixhawk

  • 参数
    返回
      Send debug_vect command to PX4, which will be transferred to uORB message rfly_ctrl
    https://mavlink.io/en/messages/common.html#DEBUG_VECT
    
+ 函数调用图:

◆ SendHILGps()

SendHILGps ( self,
lat = 40.1540302,
lon = 116.2593683,
alt = 50,
vel = 0,
vn = 0,
ve = 0,
vd = 0,
cog = 0,
time_usec = -1,
eph = 0.3,
epv = 0.4,
fix_type = 3,
satellites_visible = 15 )

发送GPS仿真数据给 MAVLink 连接

  • 参数
    lat飞机GPS坐标纬度值,单位度
    lon飞机GPS坐标经度值,单位度
    alt飞机GPS坐标高度值,单位米
    vel飞机速度大小,单位m/s
    vn飞机朝北飞速度大小,单位m/s
    ve飞机朝东飞速度大小,单位m/s
    vd飞机朝下飞速度大小,单位m/s
    yaw飞机当前机头偏航角朝向,单位度
    cog飞行速度航向角,单位度 @time_usec 当前的时间戳,UNIX时间
    eph飞机水平定位精度指标,范围0~1,无单位
    epv飞机垂直定位精度指,范围0~1,无单位
    fix_typeGPS当前状态,0-1: no fix, 2: 2D fix, 3: 3D fix.
    satellites_visible当前卫星数量
    返回

◆ SendMavArm()

SendMavArm ( self,
isArm = 1 )

发送指令到 Pixhawk 使其上锁/解锁

  • 参数
    isArm(默认值为1)是否上锁
    • 0表示上锁
    • 1表示解锁
    返回
     Send command to PX4 to arm or disarm the drone
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendMavCmdLong()

SendMavCmdLong ( self,
command,
param1 = 0,
param2 = 0,
param3 = 0,
param4 = 0,
param5 = 0,
param6 = 0,
param7 = 0 )

将 MAVLink 的长指令消息发送到 Pixhawk 系统

  • 参数
    command消息
    param1~param7(默认值均为0)参数1~参数7
    返回
     Send command long message to PX4, the mavlink command definitions can be found at
    https://mavlink.io/en/messages/common.html#COMMAND_LONG
    https://mavlink.io/en/messages/common.html#MAV_CMD
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavLand()

sendMavLand ( self,
xM,
yM,
zM )

发送指令使飞机降落到指定位置

  • 参数
    xMx轴位置
    yMy轴位置
    zMz轴位置
    返回
     Send command to make aircraft land to the desired local position (m)
    
+ 函数调用图:

◆ sendMavLandGPS()

sendMavLandGPS ( self,
lat,
lon,
alt )

发送指令使飞机降落到指定全球位置

  • 参数
    lat目标位置的经度
    lon目标位置的维度
    alt目标位置的高度
    返回
     Send command to make aircraft land to the desired global position (degree)
    
+ 函数调用图:

◆ sendMavManualCtrl()

sendMavManualCtrl ( self,
x = 0,
y = 0,
z = 0,
r = 0 )

通过 MAVLink 协议向 PX4 发送手动控制信号

  • 参数
    x(默认值为0) 手动控制的横向信号
    y(默认值为0) 手动控制的纵向信号
    z(默认值为0) 手动控制的垂直控制信号
    r(默认值为0) 手动控制的旋转信号
    返回
     Send MAVLink command to PX4 to override the manual control signal
    x,y,z,r range from -1000 to 1000
    https://mavlink.io/en/messages/common.html#MANUAL_CONTROL
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavOffboardAPI()

sendMavOffboardAPI ( self,
type_mask = 0,
coordinate_frame = 0,
pos = [0,0,0],
vel = [0,0,0],
acc = [0,0,0],
yaw = 0,
yawrate = 0 )

发送Offboard命令到PX4

  • 参数
    type_mask(默认值为0)掩码类型
    coordinate_frame(默认值为0)坐标轴类型
    pos(默认值为[0,0,0])位置
    vel(默认值为[0,0,0])速度
    acc(默认值为[0,0,0])加速度
    yaw(默认值为0)偏航角
    yaw_rate(默认值为0)偏航角速率
    返回
    send offboard command to PX4, the definition of the mavlink message can be found at
    https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavOffboardCmd()

sendMavOffboardCmd ( self,
type_mask,
coordinate_frame,
x,
y,
z,
vx,
vy,
vz,
afx,
afy,
afz,
yaw,
yaw_rate )

发送Offboard命令到PX4

  • 参数
    type_mask掩码类型
    coordinate_frame坐标轴类型
    xx坐标
    yy坐标
    zz坐标
    vxx方向的速度
    vyy方向的速度
    vzz方向的速度
    afxx方向的加速度
    afyy方向的加速度
    afzz方向的加速度
    yaw偏航角
    yaw_rate偏航角速率
    返回
     send offboard command to PX4, the definition of the mavlink message can be found at
    https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED
    
+ 函数调用图:

◆ sendMavSetParam()

sendMavSetParam ( self,
param_id,
param_value,
param_type )

向 Pixhawk 发送命令更改其参数

  • 参数
    param_id修改的参数ID
    param_value新的参数值
    param_type参数的数据类型
    返回
     Send command to px4 to change desired parameter
    the following mavlink message is adopted
    https://mavlink.io/en/messages/common.html#PARAM_SET
    the parameter list can be found in QGC
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavTakeOff()

sendMavTakeOff ( self,
xM = 0,
yM = 0,
zM = 0,
YawRad = 0,
PitchRad = 0 )

发送命令让飞行器起飞到指定位置

  • 参数
    xM(默认值为0)x方向的位置
    yM(默认值为0)y方向的位置
    zM(默认值为0)z方向的位置
    YawRad(默认值为0)起飞时的偏航角
    PitchRad(默认值为0)起飞时的俯仰角
    返回
     Send command to make aircraft takeoff to the desired local position (m)
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavTakeOffGPS()

sendMavTakeOffGPS ( self,
lat,
lon,
alt,
yawDeg = 0,
pitchDeg = 15 )

发送指令使飞机从指定的本地位置起飞,并允许设置俯仰角、偏航角和上升速率

  • 参数
    lat目标位置的经度
    lon目标位置的维度
    alt目标位置的高度
    YawRad(默认值为0)起飞时的偏航角
    pitchDeg(默认值为15)起飞时的俯仰角
    返回
     Send command to make aircraft takeoff to the desired global position (degree)
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendMavTakeOffLocal()

sendMavTakeOffLocal ( self,
xM = 0,
yM = 0,
zM = 0,
YawRad = 0,
PitchRad = 0,
AscendRate = 2 )

发送指令使飞机从指定的本地位置起飞,并允许设置俯仰角、偏航角和上升速率

  • 参数
    xM(默认值为0)x方向的位置
    yM(默认值为0)y方向的位置
    zM(默认值为0)z方向的位置
    YawRad(默认值为0)起飞时的偏航角
    PitchRad(默认值为0)起飞时的俯仰角
    AscendRate(默认值为2)起飞时的上升速率
    返回
     Send command to make aircraft takeoff to the desired local position (m)
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendOffAll()

SendOffAll ( self,
type_mask = PosTypeMask(),
coordinate_frame = 1,
pos = [0, 0, 0],
vel = [0, 0, 0],
acc = [0, 0, 0],
yaw = 0,
yawrate = 0 )

设置和准备发送无人机的位置信息和控制参数

  • 参数
    type_mask类型掩码
    coordinate_frame(默认值为1)坐标系
    pos(默认值为[0,0,0])位置
    vel(默认值为[0,0,0])速度
    acc(默认值为[0,0,0])加速度
    yaw(默认值为0)偏航角
    yawrate(默认值为0)偏航率
    返回
+ 函数调用图:

◆ SendPosFRD()

SendPosFRD ( self,
x = math.nan,
y = math.nan,
z = math.nan,
yaw = math.nan )

机体前右下坐标系下控制飞机到目标位置

  • 参数
    x(默认值为NaN,表示不控制本通道)x方向的位置
    y(默认值为NaN,表示不控制本通道)y方向的位置
    z(默认值为NaN,表示不控制本通道)z方向的位置
    yaw(默认值为NaN,表示不控制本通道)偏航角
    返回
     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 = math.nan,
y = math.nan,
z = math.nan )

机体前右下坐标系下控制飞机到目标位置

  • 参数
    x(默认值为NaN,表示不控制本通道)x方向的位置
    y(默认值为NaN,表示不控制本通道)y方向的位置
    z(默认值为NaN,表示不控制本通道)z方向的位置
    返回

     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
    
+ 函数调用图:

◆ SendPosGlobal()

SendPosGlobal ( self,
lat = 0,
lon = 0,
alt = 0,
yawValue = 0,
yawType = 0 )

地球北东地坐标系下控制飞机到目标全球位置

  • 参数
    lat(默认值为0) 目标维度
    lon(默认值为0) 目标经度
    alt(默认值为0) 目标高度
    yawValue(默认值为0) 目标偏航角或偏航速率
    yawType(默认值为0) 控制类型
    • 0表示不控制偏航角和偏航速率
    • 1表示偏航角控制
    • 2表示偏航速率控制
    返回
     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
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendPosNED()

SendPosNED ( self,
x = math.nan,
y = math.nan,
z = math.nan,
yaw = math.nan )

地球北东地坐标系下控制飞机到指定位置

  • 参数
    x(默认值为NaN,表示不控制本通道)x方向的位置
    y(默认值为NaN,表示不控制本通道)y方向的位置
    z(默认值为NaN,表示不控制本通道)z方向的位置
    返回
     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
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendPosNEDExt()

SendPosNEDExt ( self,
x = math.nan,
y = math.nan,
z = math.nan,
mode = 3,
isNED = True )

机体前右下坐标系下控制飞机到目标位置

  • 参数
    x(默认值为NaN,表示不控制本通道)x方向的位置
    y(默认值为NaN,表示不控制本通道)y方向的位置
    z(默认值为NaN,表示不控制本通道)z方向的位置
    mode(默认值为3) 控制模式
    • 0表示滑行设定点,仅用于固定翼
    • 1表示起飞设定点,仅用于固定翼
    • 2表示降落设定点,仅用于固定翼
    • 3表示盘旋设定点,对于 ROVER: 盘旋设定点(飞机接近设定点时停止);对于固定翼: 盘旋设定点(围绕设定点飞行一个圆圈)。
    • 4表示空闲设定点,仅用于固定翼
    isNED(默认值为True) 是否为地球北东地模式
    • True表示地球北东地模式
    • False表示机体前右下模式
    返回

     Send vehicle targe position (m) to PX4
    when the vehicle fly above the ground, then z < 0
    
+ 函数调用图:

◆ SendPosNEDNoYaw()

SendPosNEDNoYaw ( self,
x = math.nan,
y = math.nan,
z = math.nan )

地球北东地坐标系下控制飞机到目标位置

  • 参数
    x(默认值为NaN,表示不控制本通道)x方向的位置
    y(默认值为NaN,表示不控制本通道)y方向的位置
    z(默认值为NaN,表示不控制本通道)z方向的位置
    返回
     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
    
+ 函数调用图:

◆ sendPX4UorbRflyCtrl()

sendPX4UorbRflyCtrl ( self,
data = [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0],
modes = 1,
flags = 1 )

发送UDP简单数据

  • 参数
    data(默认值为[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0])数据
    modes(默认值为1)模式
    flags(默认值为1)控制信号
    返回
+ 函数调用图:

◆ SendQgcCmdLong()

SendQgcCmdLong ( self,
command,
param1 = 0,
param2 = 0,
param3 = 0,
param4 = 0,
param5 = 0,
param6 = 0,
param7 = 0 )

将 MAVLink 的长指令消息发送到 QGC

  • 参数
    command消息
    param1~param7(默认值均为0)命令相关参数
    返回
+ 这是这个函数的调用关系图:

◆ SendRcOverride()

SendRcOverride ( self,
ch1 = 1500,
ch2 = 1500,
ch3 = 1100,
ch4 = 1500,
ch5 = 1100,
ch6 = 1100,
ch7 = 1500,
ch8 = 1500 )

通过 MAVLink 协议向 PX4 发送遥控信号覆盖命令

  • 参数
    ch1(默认值为1500) 通道1的信号值
    ch2(默认值为1500) 通道2的信号值
    ch3(默认值为1100) 通道3的信号值
    ch4(默认值为1500) 通道4的信号值
    ch5(默认值为1100) 通道5的信号值
    ch6(默认值为1100) 通道6的信号值
    ch7(默认值为1500) 通道7的信号值
    ch8(默认值为1500) 通道8的信号值
    返回

     Send MAVLink command to PX4 to override the RC signal
    ch1~ch8 range from 1000 to 2000
    https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendRCPwms()

SendRCPwms ( self,
Pwms )

更新遥控器 PWM 信号

  • 参数
    Pwms新的 PWM 信号值
    返回

◆ sendRebootPix()

sendRebootPix ( self,
copterID,
delay = -1 )

发送消息重启飞机仿真

  • 参数
    copterID飞机编号
    delay(默认值为-1)重启前的延迟时间
    返回
     Send message to restart simulation to CopterID
    

◆ SendRedisData()

SendRedisData ( self,
key,
buf )

发送数据到redis

  • 参数
    keyredis的密钥
    buf发送的数据
    返回
+ 这是这个函数的调用关系图:

◆ SendSetMode()

SendSetMode ( self,
mainmode,
cusmode = 0 )

发送 MAVLink 命令到 PX4 以更改飞行模式

  • 参数
    mainmode主模式
    cusmode(默认值为0) 可选参数,用户自定义模式
    返回
     Send MAVLink command to PX4 to change flight mode
    https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MODE
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ sendStartMsg()

sendStartMsg ( self,
copterID = -1 )

向无人机发送启动信号

  • 参数
    copterID(默认值为-1)无人机ID
    • -1表示所有飞机
    返回
     send start signals to the network for copters calling waitForStartMsg()
    if copterID=-1, then all copters will start to run
    if copterID>0, then only the copter with specified copterID will start to run
    

◆ sendTakeoffMode()

sendTakeoffMode ( self,
alt = 0 )

发送指定使飞机起飞

  • 参数
    alt(默认值为0) 高度
    返回

     Send command to make the aircraft takeoff
    
+ 函数调用图:

◆ sendUDPSimpData()

sendUDPSimpData ( self,
ctrlMode,
ctrls )

发送UDP简单数据

  • 参数
    ctrlMode控制模式
    ctrls控制信号
    返回
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ 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 )

发送无人机位姿和状态到Rflysim3D

  • 参数
    copterID(默认值为1)无人机ID
    vehicleType(默认值为3)无人机类型
    PosE(默认值为[0,0,0])无人机坐标
    AngEuler(默认值为[0,0,0])欧拉角
    VelE(默认值为[0,0,0])XYZ方向的速度
    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; //1234567891
    #     int copterID;  //Vehicle ID
    #     int vehicleType;  //Vehicle type
    #     int PosGpsInt[3];   //lat*10^7,lon*10^7,alt*10^3,int型发放节省空间
    #     float MotorRPMS[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)
    # }6i14f4d
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ SendVelFRD()

SendVelFRD ( self,
vx = math.nan,
vy = math.nan,
vz = math.nan,
yawrate = math.nan )

前右下坐标系下操控飞机

  • 参数
    vx(默认值为NaN,表示不控制本通道)x方向的速度
    vy(默认值为NaN,表示不控制本通道)y方向的速度
    vz(默认值为NaN,表示不控制本通道)z方向的速度
    yawrate(默认值为NaN,表示不控制本通道)偏航角速率
    返回
     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 = math.nan,
vy = math.nan,
vz = math.nan,
yawrate = math.nan )

北东地坐标系下操控飞机

  • 参数
    vx(默认值为0)x方向的速度
    vy(默认值为0)y方向的速度
    vz(默认值为0)z方向的速度
    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 )

北东地坐标系下操控飞机

  • 参数
    vxx方向的速度
    vyy方向的速度
    vzz方向的速度
    返回
     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 = math.nan,
vy = math.nan,
vz = math.nan )

机体前右下坐标系下控制飞机

  • 参数
    vx(默认值为NaN,表示不控制本通道)x方向的速度
    vy(默认值为NaN,表示不控制本通道)y方向的速度
    vz(默认值为NaN,表示不控制本通道)z方向的速度
    返回
     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,
yaw = 6.28,
alt = -100 )

地球北东地坐标系下控制飞机

  • 参数
    vel(默认值为10) 目标速度
    yaw(默认值为6.28) 偏航角
    alt(默认值为-100) 目标高度
    返回
     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
    
+ 这是这个函数的调用关系图:

◆ SendVisionPosition()

SendVisionPosition ( self,
x,
y,
z,
yaw )

发送视觉定位数据给 MAVLink 连接

  • 参数
    x飞机位置 x 坐标
    y飞机位置 y 坐标
    z飞机位置 z 坐标
    yaw偏航角
    返回
    x,y,z 是动捕或视觉测量的飞机位置,yaw是动捕或视觉测量的偏航角
    

◆ setGPSOriLLA()

setGPSOriLLA ( self,
LonLatAlt )

设置GPS的原点位置,并根据提供的GPS坐标计算位置偏差

  • 参数
    LonLatAlt经度、纬度和高度
    返回
+ 函数调用图:

◆ setMsgDict()

setMsgDict ( self,
stName )

设置消息字典的状态

  • 参数
    stName状态名称
    返回
+ 这是这个函数的调用关系图:

◆ stopRun()

stopRun ( self)

停止 MAVLink 的监听循环

  • 参数
    返回
     stop mavlink listening loop for InitMavLoop(), the same as endMavLoop()
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ TypeMask()

TypeMask ( self,
EnList )

获取offboard消息的位图

  • 参数
    EnList包含位姿,速度,加速度,推力,偏航角,偏航速率的列表
    返回
    位图转化后的int值
     Obtain the bitmap for offboard message
    https://mavlink.io/en/messages/common.html#POSITION_TARGET_TYPEMASK
    
+ 这是这个函数的调用关系图:

◆ waitForStartMsg()

waitForStartMsg ( self)

等待来自 sendStartMsg 函数发送的启动信号

  • 参数
    返回
     Program will block until the start signal from sendStartMsg() is received
    

◆ yawSat()

yawSat ( self,
yaw )

调整偏航角在-π到π之间

  • 参数
    yaw偏航角
    返回
    调整后的偏航角
     satuate the yaw angle from -pi to pi
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

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