RflyRosCtrlApi结构体类。提供了与无人机进行通信和控制的完整接口,支持多种通信模式,并集成了ROS系统 更多...
Public 成员函数 | |
__init__ (self, CopterID=1, ip='127.0.0.1', Com='udp', port=0) | |
RflyRosCtrlApi的构造函数 | |
convert_to_payload64 (self, payload_bytes) | |
将payload字节转换为Mavlink的payload64格式 | |
convert_to_rosmsg (self, mavmsg, header) | |
将pymavlink消息转换为ROS的Mavlink消息 | |
arm_px4 (self, isArm) | |
解锁或锁定PX4无人机 | |
fillList (self, data, inLen, fill=0) | |
填充或截断列表,使其长度达到指定值 | |
InitMavLoop (self) | |
初始化Mavlink连接,并启动Mavros | |
SendMavArm (self, isArm) | |
发送解锁或锁定命令到无人机 | |
initOffboard (self) | |
初始化Offboard模式并发送初始命令 | |
OffboardLoop (self) | |
持续发送Offboard命令以维持Offboard模式 | |
endOffboard (self) | |
结束Offboard模式,停止相关线程,并关闭ROS2节点 | |
stopRun (self) | |
停止运行,杀死子进程并提醒用户关闭所有终端窗口 | |
calcTypeMask (self, EnList) | |
根据输入的启用列表计算Type Mask | |
SendVelNED (self, vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan) | |
发送NED(北、东、下)坐标系下的速度命令 | |
SendVelFRD (self, vx=math.nan, vy=math.nan, vz=math.nan, yawrate=math.nan) | |
发送FRD(前、右、下)坐标系下的速度命令 | |
SendPosNED (self, x=math.nan, y=math.nan, z=math.nan, yaw=math.nan) | |
发送NED坐标系下的位置命令 | |
SendPosVelNED (self, PosE=[math.nan] *3, VelE=[math.nan] *3, yaw=math.nan, yawrate=math.nan) | |
发送NED坐标系下的位置和速度命令 | |
local_pose_callback (self, msg) | |
处理本地位姿消息 | |
local_vel_callback (self, msg) | |
处理本地速度消息 | |
mavros_state_callback (self, msg) | |
处理Mavros状态消息 | |
imu_callback (self, msg) | |
处理IMU消息 | |
gps_callback (self, msg) | |
处理GPS消息 | |
q2yaw (self, q) | |
从四元数计算偏航角 | |
q2Euler (self, q) | |
从四元数计算欧拉角 | |
SendMavArm (self, isArm=0) | |
发送解锁或锁定命令到无人机 | |
arm (self) | |
解锁无人机 | |
disarm (self) | |
锁定无人机 | |
offboard (self) | |
切换飞行模式到Offboard模式 | |
yawSat (self, yaw) | |
对偏航角进行限制,使其保持在[-π/2, π/2]范围内 | |
sendMavSetParam (self, param_id_str, param_value, param_type) | |
设置MAVLink参数 | |
SendMavCmdLong (self, command, param1=0, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0) | |
发送长命令到飞行控制器 | |
SendHILCtrlMsg (self, ctrls=[0] *16, idx=0) | |
发送HIL(硬件在环)控制消息到Pixhawk,这些消息会转化为uORB消息rfly_ctrl | |
Public 属性 | |
isCom | |
用于标识当前通信模式是否为串口模式 | |
Com | |
存储传入的通信模式参数 | |
baud | |
波特率,默认设置为115200 | |
ip | |
存储数据发送的IP地址 | |
CopterID | |
无人机的ID号,用于区分不同的无人机 | |
port | |
端口号,默认根据CopterID计算而得 | |
rosName | |
ComName | |
imu | |
存储无人机的IMU数据 | |
gps | |
存储无人机的GPS数据 | |
local_pose | |
存储无人机的本地位姿数据 | |
mavros_state | |
存储无人机的当前状态信息 | |
current_heading | |
存储无人机当前的航向角信息 | |
local_vel | |
存储无人机的本地速度数据 | |
arm_state | |
表示无人机的解锁/上锁状态 | |
offboard_state | |
表示无人机是否处于Offboard模式 | |
received_imu | |
表示是否接收到IMU数据 | |
frame | |
定义数据坐标系的参考框架 | |
state | |
存储自定义状态信息 | |
command | |
存储速度控制命令 | |
offCmd | |
存储位置控制命令 | |
isInOffboard | |
表示是否处于Offboard模式中 | |
uavAngEular | |
存储无人机的欧拉角信息 | |
uavAngRate | |
存储无人机的角速度信息 | |
uavPosNED | |
存储无人机的本地NED坐标系位置信息 | |
uavVelNED | |
存储无人机的本地NED坐标系速度信息 | |
uavAngQuatern | |
存储无人机的四元数姿态信息 | |
count | |
计数器,初始化为0 | |
countHil | |
HIL(硬件在环)模式的计数器,初始化为0 | |
local_pose_sub | |
local_vel_sub | |
mavros_sub | |
gps_sub | |
imu_sub | |
vel_pub | |
vel_raw_pub | |
mav_raw_pub | |
armService | |
flightModeService | |
setparamService | |
sendCmdLongService | |
ros_node | |
executor | |
t1 | |
f | |
mav0 | |
tgtSys | |
child | |
t2 | |
RflyRosCtrlApi结构体类。提供了与无人机进行通信和控制的完整接口,支持多种通信模式,并集成了ROS系统
创建一个通信实例 ID: 表示飞机的CopterID号。按平台规则,port=20100+CopterID*2-2。 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 port: UDP模式下默认情况下设为0,会自动根据IP填充,按平台规则,port=20100+CopterID*2-2。如果这里赋值大于0,则会强制使用port定义的端口。 COM模式下,Port默认表示波特率self.baud=port。如果port=0,则会设置self.baud=57600 接口示例: UDP模式 PX4MavCtrler(1) # 默认IP PX4MavCtrler(1,'192.168.31.24') # 指定IP,用于远程控制 串口模式 PX4MavCtrler(1,'127.0.0.1','com1',57600) # 指定串口,并设置波特率
__init__ | ( | self, | |
CopterID = 1, | |||
ip = '127.0.0.1', | |||
Com = 'udp', | |||
port = 0 ) |
RflyRosCtrlApi的构造函数
初始化传输模式,波特率,ip等等参数 |
分为ros1和ros2两种,定义一些ROS系统中的服务、订阅和发布
convert_to_payload64 | ( | self, | |
payload_bytes ) |
convert_to_rosmsg | ( | self, | |
mavmsg, | |||
header ) |
fillList | ( | self, | |
data, | |||
inLen, | |||
fill = 0 ) |
SendHILCtrlMsg | ( | self, | |
ctrls = [0]*16, | |||
idx = 0 ) |
发送HIL(硬件在环)控制消息到Pixhawk,这些消息会转化为uORB消息rfly_ctrl
ctrls | 16个控制量 |
idx(默认值为 | 0) 0-3,用于选择不同的uORB消息rfly_ctrl,rfly_ctrl1,rfly_ctrl2,rfly_ctrl
|
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
SendMavCmdLong | ( | self, | |
command, | |||
param1 = 0, | |||
param2 = 0, | |||
param3 = 0, | |||
param4 = 0, | |||
param5 = 0, | |||
param6 = 0, | |||
param7 = 0 ) |
sendMavSetParam | ( | self, | |
param_id_str, | |||
param_value, | |||
param_type ) |
SendPosNED | ( | self, | |
x = math.nan, | |||
y = math.nan, | |||
z = math.nan, | |||
yaw = math.nan ) |
SendPosVelNED | ( | self, | |
PosE = [math.nan]*3, | |||
VelE = [math.nan]*3, | |||
yaw = math.nan, | |||
yawrate = math.nan ) |
SendVelFRD | ( | self, | |
vx = math.nan, | |||
vy = math.nan, | |||
vz = math.nan, | |||
yawrate = math.nan ) |
SendVelNED | ( | self, | |
vx = math.nan, | |||
vy = math.nan, | |||
vz = math.nan, | |||
yawrate = math.nan ) |
arm_state |
表示无人机的解锁/上锁状态
baud |
波特率,默认设置为115200
Com |
存储传入的通信模式参数
command |
存储速度控制命令
CopterID |
无人机的ID号,用于区分不同的无人机
count |
计数器,初始化为0
countHil |
HIL(硬件在环)模式的计数器,初始化为0
current_heading |
存储无人机当前的航向角信息
frame |
定义数据坐标系的参考框架
gps |
存储无人机的GPS数据
imu |
存储无人机的IMU数据
ip |
存储数据发送的IP地址
isCom |
用于标识当前通信模式是否为串口模式
isInOffboard |
表示是否处于Offboard模式中
local_pose |
存储无人机的本地位姿数据
local_vel |
存储无人机的本地速度数据
mavros_state |
存储无人机的当前状态信息
offboard_state |
表示无人机是否处于Offboard模式
offCmd |
存储位置控制命令
port |
端口号,默认根据CopterID计算而得
received_imu |
表示是否接收到IMU数据
state |
存储自定义状态信息
uavAngEular |
存储无人机的欧拉角信息
uavAngQuatern |
存储无人机的四元数姿态信息
uavAngRate |
存储无人机的角速度信息
uavPosNED |
存储无人机的本地NED坐标系位置信息
uavVelNED |
存储无人机的本地NED坐标系速度信息