【类 型】:fix 测试用512 指定请求id 请求242 home点

【原  因】:
【过  程】:
【影  响】:
This commit is contained in:
tk 2024-08-15 13:07:10 +08:00
parent 31ab4ec8b3
commit 37b8918e93
3 changed files with 48 additions and 17 deletions

View File

@ -289,6 +289,8 @@ extern "C"
MAV_CMD_ENUM_END = 401, /* | */
MAV_CMD_DO_START_MAG_CAL = 42424, /*磁罗盘校准*/
MAV_CMD_GET_HOME_POSITION = 410, // 请求返航点 410
MAV_CMD_SET_MESSAGE_INTERVAL = 511, // 定时请求 某个id的信息
MAV_CMD_REQUEST_MESSAGE = 512, // 获取指定id信息仅一次
};
#endif

View File

@ -556,6 +556,34 @@ void FoodCube::mav_parameter_data(const char *param_id)
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:
*/
@ -566,15 +594,15 @@ void FoodCube::mav_request_home_position()
// 组装命令
mavlink_command_long_t command = {0};
command.command = MAV_CMD_GET_HOME_POSITION;
command.command = MAV_CMD_REQUEST_MESSAGE; // 使用 MAV_CMD_REQUEST_MESSAGE 请求消息
command.confirmation = 0;
command.param1 = 0; // 参数保留,不使用
command.param2 = 0;
command.param3 = 0;
command.param4 = 0;
command.param5 = 0;
command.param6 = 0;
command.param7 = 0;
command.param1 = 49; // 请求的消息 ID242 代表 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);

View File

@ -35,7 +35,7 @@ FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlin
/* 发布 主题 ps:以下是登记发布json内容的组成元素 */
// 登记 json成员名字
// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:相对高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,海拔高度} 16:电池总容量 17:返航点 18:文本信息
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "battCapacity", "homePorsion", "statusText"};
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "battCapacity", "homePosition", "statusText"};
const int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); // 登记 json成员总数
String topicPubMsg[topicPubCount] = {""}; // 登记 json成员的值 对应topicPub
/*触发发送 主题*/
@ -361,11 +361,16 @@ void mavlink_receiveCallback(uint8_t c)
if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
{ // MAVLink解析是按照一个一个字符进行解析我们接收到一个字符就对其进行解析直到解析完根据返回标志判断一帧数据为止。
// 通过msgid来判断 数据流的类别
char buf[10];
char buf[50];
// printf("mav_id:%d\n",msg.msgid);
switch (msg.msgid)
{
case 242: // #242 返航点位置MAVLINK_MSG_ID_HOME_POSITION
{
fc.pubMQTTmsg("demo", "242");
}
break;
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: // #49 本应原点信息 改过飞控固件设置 现在放的是HOME点
{
mavlink_gps_global_origin_t gps_org; // 解构的数据放到这个对象
@ -380,10 +385,7 @@ void mavlink_receiveCallback(uint8_t c)
{
topicPubMsg[17] = buf;
}
}
break;
case 242: // #242 返航点位置MAVLINK_MSG_ID_HOME_POSITION
{
fc.pubMQTTmsg("demo", buf);
}
break;
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
@ -452,7 +454,7 @@ void mavlink_receiveCallback(uint8_t c)
break;
case 5:
{
topicPubMsg[12] = "悬停";
topicPubMsg[12] = "悬停"; // Loiter 定点
}
break;
case 6:
@ -467,7 +469,7 @@ void mavlink_receiveCallback(uint8_t c)
break;
case 16:
{
topicPubMsg[12] = "定点";
topicPubMsg[12] = "定点"; // PosHold
}
break;
default:
@ -775,7 +777,6 @@ void refreshRequest()
delay(100);
fc.mav_parameter_data("BATT_CAPACITY"); // 请求飞控 返回参数 电池容量 值
delay(100);
fc.pubMQTTmsg("demo", "init");
}
/**