【类 型】:feat 飞控取WPNAV_SPEED 返航速度参数
【原 因】:前端用来计算 返航电量 【过 程】: 【影 响】:
This commit is contained in:
parent
d86e4cb811
commit
d713db3c1d
@ -34,8 +34,8 @@ uint32_t udpServerPort = 37260; // 云台相机端口
|
|||||||
FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象
|
FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象
|
||||||
/* 发布 主题 ps:以下是登记发布json内容的组成元素 */
|
/* 发布 主题 ps:以下是登记发布json内容的组成元素 */
|
||||||
// 登记 json成员名字
|
// 登记 json成员名字
|
||||||
// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:海拔高度 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,相对高度} 16:电池总容量 17:返航点 18:文本信息
|
// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:海拔高度 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,相对高度} 16:电池总容量 17:返航点 18:文本信息 19:返航速度
|
||||||
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "battCapacity", "homePosition", "statusText"};
|
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "battCapacity", "homePosition", "statusText", "wpnavSpeed"};
|
||||||
const int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); // 登记 json成员总数
|
const int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); // 登记 json成员总数
|
||||||
String topicPubMsg[topicPubCount] = {""}; // 登记 json成员的值 对应topicPub
|
String topicPubMsg[topicPubCount] = {""}; // 登记 json成员的值 对应topicPub
|
||||||
/*触发发送 主题*/
|
/*触发发送 主题*/
|
||||||
@ -709,7 +709,7 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
mavlink_param_value_t param_value;
|
mavlink_param_value_t param_value;
|
||||||
mavlink_msg_param_value_decode(&msg, ¶m_value);
|
mavlink_msg_param_value_decode(&msg, ¶m_value);
|
||||||
|
|
||||||
// 只处理 "BATT_CAPACITY" 参数
|
// "BATT_CAPACITY" 参数 电池总容量
|
||||||
if (strcmp(param_value.param_id, "BATT_CAPACITY") == 0)
|
if (strcmp(param_value.param_id, "BATT_CAPACITY") == 0)
|
||||||
{
|
{
|
||||||
// 将参数值转换为字符串
|
// 将参数值转换为字符串
|
||||||
@ -719,6 +719,16 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
topicPubMsg[16] = buf;
|
topicPubMsg[16] = buf;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
// "WPNAV_SPEED" 参数 返航速度
|
||||||
|
if (strcmp(param_value.param_id, "WPNAV_SPEED") == 0)
|
||||||
|
{
|
||||||
|
// 将参数值转换为字符串
|
||||||
|
dtostrf(param_value.param_value / 1000, 0, 2, buf); // 使用 dtostrf 将浮点数转换为字符串
|
||||||
|
if (String(buf) != topicPubMsg[19])
|
||||||
|
{
|
||||||
|
topicPubMsg[19] = buf;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -772,11 +782,13 @@ void pubThread()
|
|||||||
void refreshRequest()
|
void refreshRequest()
|
||||||
{
|
{
|
||||||
fc.mav_request_home_position();
|
fc.mav_request_home_position();
|
||||||
delay(100);
|
delay(50);
|
||||||
fc.mav_request_data(); // 请求 设定飞控输出数据流内容
|
fc.mav_request_data(); // 请求 设定飞控输出数据流内容
|
||||||
delay(100);
|
delay(50);
|
||||||
fc.mav_parameter_data("BATT_CAPACITY"); // 请求飞控 返回参数 电池容量 值
|
fc.mav_parameter_data("BATT_CAPACITY"); // 请求飞控 返回参数 电池容量 值
|
||||||
delay(100);
|
delay(50);
|
||||||
|
fc.mav_parameter_data("WPNAV_SPEED"); // 请求飞控 返回参数 返航速度
|
||||||
|
delay(50);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
Loading…
Reference in New Issue
Block a user