根据命令设置不同飞行状态以及目标
SET_POSITION_TARGET_LOCAL_NED 84
type_mask参数说明
coordinate_frame 为机体坐标系参数
目前设置为两个参数
MAV_FRAME_LOCAL_NED 大地坐标系(NED坐标)
MAV_FRAME_BODY_FRD 机体坐标系(遵循右手定则)
返回command = MAV_CMD_REQUEST_MESSAGE
返回值 param1 84 执行命令id
返回值 param2 0或1 是否执行成功
返回值 param3 失败代码
失败代码列表
0 无异常
1 无法初始化无人机飞行控制
2 获取无人机控制权失败
3 未知坐标系
4 销毁FRU坐标系移动线程失败
5 销毁NED坐标系移动线程失败
6 创建FRU坐标系移动线程失败
7 创建NED坐标系移动线程失败
python测试脚本
import time
from pymavlink import mavutil
timestamp = int(time.time() * 1000)
millis = int(time.time() * 1000)
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
master.wait_heartbeat()
boot_time = time.time()
def ready():
master.mav.command_long_send(
master.target_system,
master.target_component,
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
0,
0, 0, 0, 0, 0, 0, 0
)
def fly():
# test pos mod use ned frame
print('test pos mod use ned frame')
master.mav.set_position_target_local_ned_send(
int(1e3 * (time.time() - boot_time)), # ms since boot
master.target_system,
master.target_component,
coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_NED,
type_mask=(
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
),
x=10, y=10, z=-10,
vx=0, vy=0, vz=0,
afx=0, afy=0, afz=0,
yaw=0, yaw_rate=0
)
# test yaw rate mod
time.sleep(10)
print('test yaw rate mod')
master.mav.set_position_target_local_ned_send(
int(1e3 * (time.time() - boot_time)), # ms since boot
master.target_system,
master.target_component,
coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_NED,
type_mask=(
mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
),
x=0, y=0, z=0,
vx=0, vy=0, vz=0,
afx=0, afy=0, afz=0,
yaw=0, yaw_rate=90
)
# test velocity mod fru mod
time.sleep(10)
print('test velocity mod fru mod')
x = 0
while x < 200:
master.mav.set_position_target_local_ned_send(
int(1e3 * (time.time() - boot_time)), # ms since boot
master.target_system,
master.target_component,
coordinate_frame=mavutil.mavlink.MAV_FRAME_BODY_FRD,
type_mask=(
mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
),
x=0, y=0, z=0,
vx=5, vy=0, vz=-5,
afx=0, afy=0, afz=0,
yaw=0, yaw_rate=0)
x += 1
time.sleep(0.25)
print('----------------' + str(x))
# test yaw mod
time.sleep(10)
print('test yaw mod')
master.mav.set_position_target_local_ned_send(
int(1e3 * (time.time() - boot_time)), # ms since boot
master.target_system,
master.target_component,
coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_NED,
type_mask=(
mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
# mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
),
x=0, y=0, z=0,
vx=0, vy=0, vz=0,
afx=0, afy=0, afz=0,
yaw=-110, yaw_rate=0
)
def land():
master.mav.command_long_send(
master.target_system,
master.target_component,
mavutil.mavlink.MAV_CMD_NAV_LAND,
0,
0, 0, 0, 0, 0, 0, 0
)
ready()
time.sleep(10)
fly()
time.sleep(10)
land()
作者:bai 创建时间:2024-09-14 16:11
最后编辑:bai 更新时间:2024-12-03 09:16
最后编辑:bai 更新时间:2024-12-03 09:16