【类 型】:fix 测试增加串口 的缓冲区 是否能收到 home点信息
【原 因】: 【过 程】: 【影 响】:测试收不到
This commit is contained in:
parent
805b83f143
commit
082442dfc6
@ -23,13 +23,19 @@ FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int
|
|||||||
switch (mavlinkSerial)
|
switch (mavlinkSerial)
|
||||||
{ // 初始化指定 串口号
|
{ // 初始化指定 串口号
|
||||||
case 0:
|
case 0:
|
||||||
Serial.begin(57600);
|
Serial.begin(57600, SERIAL_8N1);
|
||||||
|
// 设置接收缓冲区大小为1024字节
|
||||||
|
Serial.setRxBufferSize(1024);
|
||||||
break;
|
break;
|
||||||
case 1:
|
case 1:
|
||||||
Serial1.begin(57600);
|
Serial1.begin(57600, SERIAL_8N1);
|
||||||
|
// 设置接收缓冲区大小为1024字节
|
||||||
|
Serial1.setRxBufferSize(1024);
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
Serial2.begin(57600);
|
Serial2.begin(57600, SERIAL_8N1);
|
||||||
|
// 设置接收缓冲区大小为1024字节
|
||||||
|
Serial2.setRxBufferSize(1024);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// 初始化声音模块串口 波特率
|
// 初始化声音模块串口 波特率
|
||||||
@ -556,34 +562,6 @@ void FoodCube::mav_parameter_data(const char *param_id)
|
|||||||
SWrite(buf, len, mavlinkSerial);
|
SWrite(buf, len, mavlinkSerial);
|
||||||
}
|
}
|
||||||
|
|
||||||
// /**
|
|
||||||
// * @description: 向飞控请求返航点的位置数据
|
|
||||||
// */
|
|
||||||
// void FoodCube::mav_request_home_position()
|
|
||||||
// {
|
|
||||||
// mavlink_message_t msg;
|
|
||||||
// uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
|
||||||
|
|
||||||
// // 组装命令
|
|
||||||
// mavlink_command_long_t command = {0};
|
|
||||||
// command.command = MAV_CMD_GET_HOME_POSITION;
|
|
||||||
// command.confirmation = 0;
|
|
||||||
// command.param1 = 0; // 参数保留,不使用
|
|
||||||
// command.param2 = 0;
|
|
||||||
// command.param3 = 0;
|
|
||||||
// command.param4 = 0;
|
|
||||||
// command.param5 = 0;
|
|
||||||
// command.param6 = 0;
|
|
||||||
// command.param7 = 0;
|
|
||||||
|
|
||||||
// // 打包命令消息
|
|
||||||
// mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &command);
|
|
||||||
|
|
||||||
// // 将消息转换为字节流并发送
|
|
||||||
// int len = mavlink_msg_to_send_buffer(buf, &msg);
|
|
||||||
// SWrite(buf, len, mavlinkSerial);
|
|
||||||
// }
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 向飞控请求返航点的位置数据
|
* @description: 向飞控请求返航点的位置数据
|
||||||
*/
|
*/
|
||||||
@ -594,15 +572,15 @@ void FoodCube::mav_request_home_position()
|
|||||||
|
|
||||||
// 组装命令
|
// 组装命令
|
||||||
mavlink_command_long_t command = {0};
|
mavlink_command_long_t command = {0};
|
||||||
command.command = MAV_CMD_REQUEST_MESSAGE; // 使用 MAV_CMD_REQUEST_MESSAGE 请求消息
|
command.command = MAV_CMD_GET_HOME_POSITION;
|
||||||
command.confirmation = 0;
|
command.confirmation = 0;
|
||||||
command.param1 = 49; // 请求的消息 ID,242 代表 Home 点位置
|
command.param1 = 0; // 参数保留,不使用
|
||||||
command.param2 = 0; // 可选参数
|
command.param2 = 0;
|
||||||
command.param3 = 0; // 可选参数
|
command.param3 = 0;
|
||||||
command.param4 = 0; // 可选参数
|
command.param4 = 0;
|
||||||
command.param5 = 0; // 可选参数
|
command.param5 = 0;
|
||||||
command.param6 = 0; // 可选参数
|
command.param6 = 0;
|
||||||
command.param7 = 0; // 可选参数
|
command.param7 = 0;
|
||||||
|
|
||||||
// 打包命令消息
|
// 打包命令消息
|
||||||
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &command);
|
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &command);
|
||||||
@ -612,6 +590,34 @@ void FoodCube::mav_request_home_position()
|
|||||||
SWrite(buf, len, mavlinkSerial);
|
SWrite(buf, len, mavlinkSerial);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @description: 向飞控请求返航点的位置数据
|
||||||
|
*/
|
||||||
|
// void FoodCube::mav_request_home_position()
|
||||||
|
// {
|
||||||
|
// mavlink_message_t msg;
|
||||||
|
// uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||||
|
|
||||||
|
// // 组装命令
|
||||||
|
// mavlink_command_long_t command = {0};
|
||||||
|
// command.command = MAV_CMD_REQUEST_MESSAGE; // 使用 MAV_CMD_REQUEST_MESSAGE 请求消息
|
||||||
|
// command.confirmation = 0;
|
||||||
|
// command.param1 = 49; // 请求的消息 ID,242 代表 Home 点位置
|
||||||
|
// command.param2 = 0; // 可选参数
|
||||||
|
// command.param3 = 0; // 可选参数
|
||||||
|
// command.param4 = 0; // 可选参数
|
||||||
|
// command.param5 = 0; // 可选参数
|
||||||
|
// command.param6 = 0; // 可选参数
|
||||||
|
// command.param7 = 0; // 可选参数
|
||||||
|
|
||||||
|
// // 打包命令消息
|
||||||
|
// mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &command);
|
||||||
|
|
||||||
|
// // 将消息转换为字节流并发送
|
||||||
|
// int len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||||
|
// SWrite(buf, len, mavlinkSerial);
|
||||||
|
// }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 解析mavlink数据流
|
* @description: 解析mavlink数据流
|
||||||
* @param {pFun} pFun 拿到缓存数据之后 解析数据执行回调
|
* @param {pFun} pFun 拿到缓存数据之后 解析数据执行回调
|
||||||
|
@ -385,7 +385,7 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
{
|
{
|
||||||
topicPubMsg[17] = buf;
|
topicPubMsg[17] = buf;
|
||||||
}
|
}
|
||||||
fc.pubMQTTmsg("demo", buf);
|
fc.pubMQTTmsg("demo", "49");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
|
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
|
||||||
@ -767,7 +767,6 @@ void pubThread()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// fc.mav_request_home_position(); // 请求 飞控返航点
|
|
||||||
// 将JSON对象序列化为JSON字符串
|
// 将JSON对象序列化为JSON字符串
|
||||||
String jsonString;
|
String jsonString;
|
||||||
serializeJson(doc, jsonString);
|
serializeJson(doc, jsonString);
|
||||||
|
Loading…
Reference in New Issue
Block a user