mavlink id 76 COMMAND_LONG command = MAV_CMD_DO_SET_HOME (179)

设置返航点。将返航点设置为当前位置或指定位置。返航点是系统默认返回并降落的位置。起飞时系统会自动设置位置(也可以使用此命令进行设置)。

Param (:Label)
Description
Units
1: Use Current
是否设置当前位置为返航点。不等于 0 或 1 的数值无效。
bool
2:
保留

3:
保留

4:
保留

5: Latitude
纬度
角度
6: Longitude
经度
角度
7:
保留

返回消息:

返回消息:COMMAND_ACK
返回值 command 179 执行命令id
返回值 result 0或4 0:执行成功,4:执行失败

HOME_POSITION(242)
详见返航点信息页。

python测试脚本

import time
from pymavlink import mavutil


def get_current_millis():
    """获取当前时间(毫秒级)"""
    return int(time.time() * 1000)


# MAVLink 命令常量
MAV_CMD_DO_SET_HOME = 179
USE_CURRENT_GPS = 0
USE_SPECIFIED_GPS = 1
DEFAULT_TIMEOUT = 5.0


def send_set_home_command(master, latitude, longitude, use_current_gps=USE_SPECIFIED_GPS):
    """发送设置航点命令到无人机

    Args:
        master: MAVLink 连接对象
        latitude: 纬度 (单位: 度)
        longitude: 经度 (单位: 度)
        use_current_gps: 是否使用当前位置 (0=使用指定经纬度, 1=使用当前位置)
    """
    send_time = get_current_millis()
    print(f"[{send_time}] 发送设置航点命令")

    if use_current_gps:
        print("  使用当前位置作为航点")
    else:
        print(f"  设置航点经纬度: 纬度 = {latitude}, 经度 = {longitude}")

    master.mav.command_long_send(
        master.target_system,
        master.target_component,
        mavutil.mavlink.MAV_CMD_DO_SET_HOME,
        0,  # 确认标志
        use_current_gps,  # param1: 0=使用指定经纬度, 1=使用当前位置
        0,  # param2: 保留
        0,  # param3: 保留
        0,  # param4: 保留
        latitude,   # param5: 纬度 (单位: 度)
        longitude,   # param6: 经度 (单位: 度)
        0           # param7: 高度 (保留)
    )

    return send_time


def wait_for_ack(master, send_time, timeout=DEFAULT_TIMEOUT):
    """等待命令确认响应"""
    print("等待设置航点命令响应...")

    ack = master.recv_match(
        type='COMMAND_ACK',
        blocking=True,
        timeout=timeout
    )

    if ack:
        ack_time = get_current_millis()
        delay = ack_time - send_time
        print(f"[{ack_time}] 收到命令应答 (MAV_CMD_DO_SET_HOME)")
        print(f" 命令ID: {ack.command}, 结果: {ack.result}, 延迟: {delay}ms")
    else:
        print(f"[{get_current_millis()}] 超时:未收到设置航点命令应答")


def main():
    """主函数:连接无人机并发送设置航点命令"""
    # 连接无人机(UDP端口14550)
    master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
    print("等待无人机心跳...")
    master.wait_heartbeat()
    print("无人机已连接,开始发送设置航点命令")

    # 设置航点(示例坐标,请根据实际情况修改)
    latitude = 40.1234    # 示例纬度
    longitude = 110.1234  # 示例经度
    send_time = send_set_home_command(master, latitude, longitude)

    # 等待响应
    wait_for_ack(master, send_time)

    print("设置航点命令发送完成")


if __name__ == "__main__":
    main()

调用脚本

执行结果

作者:sfd  创建时间:2024-09-14 15:35
最后编辑:sfd  更新时间:2026-04-01 08:51