From dcbd67fb7f0a768f72e9519a53dd5f4710f548ea Mon Sep 17 00:00:00 2001 From: tk Date: Fri, 30 Aug 2024 18:53:24 +0800 Subject: [PATCH] =?UTF-8?q?=E3=80=90=E7=B1=BB=20=20=E5=9E=8B=E3=80=91?= =?UTF-8?q?=EF=BC=9Afeat=201=E6=A0=A1=E5=87=86=E5=8A=A0=E9=80=9F=E5=BA=A6?= =?UTF-8?q?=E8=AE=A1=E5=87=BD=E6=95=B0=202.style=20=E5=8F=91=E9=80=81?= =?UTF-8?q?=E5=91=BD=E4=BB=A4=E5=8C=85=E6=88=90=E5=91=98=E5=87=BD=E6=95=B0?= =?UTF-8?q?=E5=8A=A0=E4=B8=8A=E6=B3=A8=E9=87=8A=E8=AF=B4=E6=98=8E=20?= =?UTF-8?q?=E3=80=90=E5=8E=9F=20=20=E5=9B=A0=E3=80=91=EF=BC=9A=20=E3=80=90?= =?UTF-8?q?=E8=BF=87=20=20=E7=A8=8B=E3=80=91=EF=BC=9A=E6=8E=A5=E6=94=B6?= =?UTF-8?q?=E5=88=B0=E5=89=8D=E7=AB=AF=E6=A0=A1=E5=87=86=E5=91=BD=E4=BB=A4?= =?UTF-8?q?=20=E6=89=A7=E8=A1=8C=E6=A0=A1=E5=87=86=20=E5=92=8C=E4=B8=80?= =?UTF-8?q?=E6=AD=A5=20=E4=B8=80=E6=AD=A5=E6=89=A7=E8=A1=8C=EF=BC=88?= =?UTF-8?q?=E4=B8=A4=E4=B8=AA=E5=87=BD=E6=95=B0=E5=8F=91=E9=80=81=E5=91=BD?= =?UTF-8?q?=E4=BB=A4=E5=B8=A7=EF=BC=89=20=E3=80=90=E5=BD=B1=20=20=E5=93=8D?= =?UTF-8?q?=E3=80=91=EF=BC=9A?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/FoodDeliveryBase.cpp | 18 ++++++++++++++++++ src/commser.cpp | 4 ++-- 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/src/FoodDeliveryBase.cpp b/src/FoodDeliveryBase.cpp index 7d155f3..6b874b4 100644 --- a/src/FoodDeliveryBase.cpp +++ b/src/FoodDeliveryBase.cpp @@ -742,6 +742,12 @@ void FoodCube::mav_channels_override(uint16_t chan[]) SWrite(buf, len, mavlinkSerial); } +/** + * @brief 发送MAVLink命令 + * 该函数通过串口发送一个MAVLink `COMMAND_LONG` 命令。此命令可以用于向飞控发送各种控制命令, + * 包括但不限于模式切换、校准、任务启动等。 + * @param msg_cmd 参考传递的 `mavlink_command_long_t` 类型的 MAVLink 命令结构体。 + */ void FoodCube::mav_send_command(mavlink_command_long_t &msg_cmd) { mavlink_message_t msg; // mavlink协议信息(msg) @@ -752,6 +758,18 @@ void FoodCube::mav_send_command(mavlink_command_long_t &msg_cmd) SWrite(buf, len, mavlinkSerial); } +/** + * @brief 发送 COMMAND_ACK 消息 + * 该函数用于发送一个 `COMMAND_ACK` 消息,以响应飞控发送的命令确认请求。该消息通常用于通知飞控某个命令 + * 是否已被接收和处理,以及处理的结果状态。 + * @param command 表示要响应的命令 ID,通常与接收到的命令相对应。 + * @param result 表示命令的处理结果。常用值包括: + * - 0: MAV_RESULT_ACCEPTED (命令成功接受) + * - 1: MAV_RESULT_TEMPORARILY_REJECTED (命令被暂时拒绝) + * - 2: MAV_RESULT_DENIED (命令被拒绝) + * - 3: MAV_RESULT_UNSUPPORTED (命令不受支持) + * - 4: MAV_RESULT_FAILED (命令执行失败) + */ void FoodCube::sendCommandAck(uint16_t command, uint8_t result) { mavlink_message_t msg; // MAVLink 信息 diff --git a/src/commser.cpp b/src/commser.cpp index 81f60f2..4b9fc18 100644 --- a/src/commser.cpp +++ b/src/commser.cpp @@ -206,11 +206,11 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length) uint32_t todo = value.as(); // 转换值 if (todo == 1) { - initAcce(); + initAcce(); // 发起校准 } else { - fc.sendCommandAck(1, 1); + fc.sendCommandAck(1, 1); // 摆好校准 } } else if (key == "refreshRequest")