|
|
| __init__ (self, copter_id=1, ip='127.0.0.1', com='udp', port=0, simulink_dll=False) |
|
| init_loop (self, ct_mode=2, offboard=False) |
|
| is_full_send (self) |
| | takeoff (self, height=0, pos_x=0, pos_y=0) |
| | return_home (self, height=0) |
| | land (self, height=0) |
| | send_pos_ned (self, pos, yaw) |
| | send_pos_speed_fw (self, pos, speed) |
|
| send_pos_global (self, pos, yaw) |
|
| send_vel_ned (self, vel, yaw_rate) |
|
| send_vel_body (self, vel, yaw_rate) |
| | send_acc (self, acc) |
| | send_att_thrust (self, att, thrust) |
| | send_att (self, att) |
| | send_cruise_speed_fw (self, speed) |
| | send_cruise_radius_fw (self, radius) |
| | get_vehicle_id (self) |
|
| get_time_s (self) |
| | get_pos_ned (self) |
| | get_pos_ned_global (self) |
| | get_pos_global (self) |
| | get_home_pos (self) |
|
| get_vel_ned (self) |
| | get_acc (self) |
|
| get_euler (self) |
|
| get_angular_rate (self) |
| | get_quaternion (self) |
| | get_actuator_speed (self) |
| | get_max_vel_xy (self) |
| | get_max_vel_z (self) |
| | get_max_acc_xy (self) |
| | get_max_acc_z (self) |
|
| __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 系统
|
| | SendMavCmdLongNEW (self, command, param1=0, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0, target_system=None, target_component=1, confirmation=0, force_send=False) |
| | 发送 MAVLink COMMAND_LONG 到 PX4,并确保写入 vehicle_command(ulog->csv)
|
| | SendFaultEvent (self, int fault_id, params=None, int action=1, int seq=0, int vehicle_id=None, int sim_id=0, int command=MAV_CMD_USER_1) |
| | 向 PX4 写入一条(或多条分片)“故障事件”记录(COMMAND_LONG),确保出现在 vehicle_command_*.csv
|
| | ClearFault (self, int fault_id, int seq=0, int vehicle_id=None, int sim_id=0, int command=MAV_CMD_USER_1) |
| | 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) |
|
|
| rflysim_cmd = RflySimCP.CmdBase + RflySimCP.CmdArmed |
|
| simulinkDLL |
|
bool | isInPointMode = False |
|
bool | isCom = False |
|
| Com = Com |
|
int | baud = 115200 |
|
int | isRealFly = 0 |
|
| ip = ip |
|
bool | isRedis = False |
|
int | CopterID = ID |
|
int | port = 20100+self.CopterID*2-2 |
|
str | ComName = 'COM3' |
|
| redisCon = None |
|
| redisHost = ip |
|
int | redisPort = 6379 |
|
| redisPass = None |
|
| pubsub = None |
| dict | redisKey |
|
| f = fifo |
|
bool | stopFlag = False |
|
| mav0 = mavlink2.MAVLink(self.f) |
|
| udp_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
|
| udp_socketUDP = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
|
| udp_socketTrue = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
|
| udp_socketPX4 = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
|
| udp_socketUE4 = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
|
int | uavTimeStmp = 0 |
|
int | trueTimeStmp = 0 |
|
list | uavAngEular = [0, 0, 0] |
|
list | trueAngEular = [0, 0, 0] |
|
list | uavAngRate = [0, 0, 0] |
|
list | trueAngRate = [0, 0, 0] |
|
list | uavPosNED = [0, 0, 0] |
|
list | truePosNED = [0, 0, 0] |
|
list | uavVelNED = [0, 0, 0] |
|
list | trueVelNED = [0, 0, 0] |
|
bool | isVehicleCrash = False |
|
int | isVehicleCrashID = -10 |
|
list | uavPosGPS = [0, 0, 0,0, 0, 0,0,0,0] |
|
list | uavPosGPSHome = [0, 0, 0] |
|
list | uavGlobalPos = [0, 0, 0] |
|
list | trueAngQuatern = [0, 0, 0, 0] |
|
list | uavAngQuatern = [0, 0, 0, 0] |
|
list | trueMotorRPMS = [0, 0, 0, 0, 0, 0, 0, 0] |
|
list | uavMotorRPMS = [0, 0, 0, 0, 0, 0, 0, 0] |
|
list | trueAccB = [0, 0, 0] |
|
list | uavAccB = [0, 0, 0] |
|
list | uavGyro = [0, 0, 0] |
|
list | uavMag = [0, 0, 0] |
|
list | uavVibr = [0, 0, 0] |
|
| out3Ddata = Data3D() |
|
list | truePosGPS = [0, 0, 0] |
|
list | trueSimulinkData = [0]*32 |
|
bool | useCustGPSOri = False |
|
list | trueGpsUeCenter = [40.1540302,116.2593683,50] |
|
list | GpsOriOffset = [0,0,0] |
|
int | uavThrust = 0 |
|
int | zInt = 0 |
|
list | EnList = [0,1,0,0,0,1] |
|
| type_mask = self.TypeMask(self.EnList) |
|
int | coordinate_frame = mavlink2.MAV_FRAME_BODY_NED |
|
list | pos = [0,0,0] |
|
list | vel = [0,0,0] |
|
list | acc = [0, 0, 0] |
|
int | yaw = 0 |
|
int | yawrate = 0 |
|
bool | isInOffboard = False |
|
bool | isArmed = False |
|
bool | hasSendDisableRTLRC = False |
|
int | UDPMode = 2 |
|
| startTime = time.time() |
|
int | MaxSpeed = 5 |
|
bool | stopFlagTrueData = False |
|
bool | hasTrueDataRec = False |
|
bool | isPX4Ekf3DFixed = False |
|
int | isArmerror = 0 |
|
int | truegyro = 0 |
|
int | truemag = 0 |
|
list | RCPWMs = [0, 0, 0,0, 0, 0,0, 0] |
|
bool | isRCLoop = False |
|
float | tRCHz = 0.03 |
|
bool | isFailsafeEn = False |
|
| FailsafeInfo = None |
|
| px4ext = PX4ExtMsg() |
|
bool | px4extTrue = False |
|
int | offMode = 0 |
|
int | ctrlMode = 0 |
|
list | cmdVel = [0]*7 |
|
int | system_status = 0 |
|
bool | connected = False |
|
list | batInfo = [0]*2 |
|
int | nId = 0 |
|
int | isOffBoard = 0 |
|
dict | hasMsgDict = {} |
|
list | trigMsgVect = [] |
|
| hasMsgEvent = threading.Event() |
|
| trueMsgEvent = threading.Event() |
|
| geo = EarthModel.EarthModel() |
|
| netEvent = threading.Event() |
|
| uavEvent = threading.Event() |
|
int | uavMsg = 0 |
|
| t1 = None |
|
| intAlt = intAlt |
|
| intStateX = intState[0] |
|
| intStateY = intState[1] |
|
| intStateYaw = intState[2] |
|
| t3 = threading.Thread(target=self.PointMassModelLoop, args=()) |
|
float | startTime3 = time.time() |
|
| lastTime3 = self.startTime3 |
|
| trueAngRat = list(self.uavAngRate) |
|
| tTrue = threading.Thread(target=self.getTrueDataMsg, args=()) |
|
bool | stopFlagPX4Data = False |
|
| tPX4 = threading.Thread(target=self.getPX4DataMsg, args=()) |
|
| the_connection = mavutil.mavlink_connection(self.ComName,self.baud) |
|
int | lastTime = 0 |
|
| t2 = threading.Thread(target=self.OffboardSendMode, args=()) |
|
int | lastTime2 = 0 |
|
| startTime2 = time.time() |
|
| tRC = threading.Thread(target=self.RcSendLoop, args=()) |