From 6ae6ff91b4f407cb21ba740fd15e60278383c15d Mon Sep 17 00:00:00 2001 From: tk Date: Mon, 26 Aug 2024 12:03:15 +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=9Afix=20=E6=B8=85=E9=99=A4=20=E5=86=97=E4=BD=99=E5=87=BD?= =?UTF-8?q?=E6=95=B0=20=E3=80=90=E5=8E=9F=20=20=E5=9B=A0=E3=80=91=EF=BC=9A?= =?UTF-8?q?=20=E3=80=90=E8=BF=87=20=20=E7=A8=8B=E3=80=91=EF=BC=9A=20?= =?UTF-8?q?=E3=80=90=E5=BD=B1=20=20=E5=93=8D=E3=80=91=EF=BC=9A?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动 --- src/FoodDeliveryBase.cpp | 16 +--------------- src/FoodDeliveryBase.h | 17 ++++++++++------- 2 files changed, 11 insertions(+), 22 deletions(-) diff --git a/src/FoodDeliveryBase.cpp b/src/FoodDeliveryBase.cpp index 55d0a36..a332e9c 100644 --- a/src/FoodDeliveryBase.cpp +++ b/src/FoodDeliveryBase.cpp @@ -668,20 +668,6 @@ void FoodCube::mav_mission_item(int8_t seq, uint8_t frame, uint8_t command, uint SWrite(buf, len, mavlinkSerial); } -/** - * @description: 向飞控发送 设置模式指令 - */ -void FoodCube::mav_set_mode(uint8_t SysState) -{ - mavlink_message_t msg; // mavlink协议信息(msg) - uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存 - // 设置飞行模式的数据包 - mavlink_msg_set_mode_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, 1, 209, SysState); - int len = mavlink_msg_to_send_buffer(buf, &msg); - // 通过串口发送 - SWrite(buf, len, mavlinkSerial); -} - void FoodCube::mav_send_text(uint8_t severity, const char *text) { return; @@ -756,7 +742,7 @@ void FoodCube::mav_channels_override(uint16_t chan[]) SWrite(buf, len, mavlinkSerial); } -void FoodCube::mav_send_command(mavlink_command_long_t msg_cmd) +void FoodCube::mav_send_command(mavlink_command_long_t &msg_cmd) { mavlink_message_t msg; // mavlink协议信息(msg) uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存 diff --git a/src/FoodDeliveryBase.h b/src/FoodDeliveryBase.h index c1d1811..01c7f7f 100644 --- a/src/FoodDeliveryBase.h +++ b/src/FoodDeliveryBase.h @@ -11,12 +11,12 @@ /*json库*/ #include "ArduinoJson.h" /*异步库*/ -#include "Ticker.h" //调用Ticker.h库 +#include "Ticker.h" /*udp发送*/ #include "WiFiUdp.h" -#define MAVLINK_SYSTEM_ID 0xFF -#define MAVLINK_COMPONENT_ID 0xBE +#define MAVLINK_SYSTEM_ID 0xBE // 飞控系统 ID +#define MAVLINK_COMPONENT_ID 0xBE // 飞控组件 ID class FoodCube { @@ -54,8 +54,7 @@ public: void mqttLoop(String topicSub); void subscribeTopic(String topicString, int Qos); void pubMQTTmsg(String topicString, String messageString); - /*串口输出*/ - void SWrite(uint8_t buf[], int len, uint8_t swSerial); + /*声音模块控制*/ void playText(String str, bool flying = false); void SetplayvolMax(); @@ -69,11 +68,12 @@ public: void comm_receive(void (*pFun)(uint8_t)); void mav_mission_count(uint8_t taskcount); void mav_mission_item(int8_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, double param1, double param2, double param3, double param4, double x, double y, double z); - void mav_set_mode(uint8_t SysState); void mav_command(uint8_t controlType, uint16_t param[]); - void mav_send_command(mavlink_command_long_t msg_cmd); void mav_channels_override(uint16_t chan[]); void mav_send_text(uint8_t severity, const char *text); + + void mav_send_command(mavlink_command_long_t &msg_cmd); + /*云台相机控制*/ void udpSendToCamera(uint8_t *p_command, uint32_t len); void Camera_action_down(); @@ -136,6 +136,9 @@ private: 0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0xed1, 0x1ef0}; uint16_t CRC16_cal(uint8_t *ptr, uint32_t len, uint16_t crc_init); void crc_check_16bites(uint8_t *pbuf, uint32_t len, uint16_t *p_result); + + /*串口输出*/ + void SWrite(uint8_t buf[], int len, uint8_t swSerial); }; #endif \ No newline at end of file