【类 型】:feat 增加获取飞控参数功能
【原 因】:前端获取电池总容量 ,用来算当前的电池容量 【过 程】:1.发布主题添加parameter 字段2.订阅到getBattCapacity主题信息是向飞控请求返回电池容量3.mavlink返回参数信息数据 写到发布主题的parameter字段中4.fc对象中添加一个mav_parameter_data方法 让飞控返回对应的参数数据 【影 响】:
This commit is contained in:
parent
08df7981cf
commit
3516ad02c8
@ -484,7 +484,7 @@ void FoodCube::udpSendToCamera(uint8_t *p_command, uint32_t len)
|
||||
/* //发送日志
|
||||
printf("SendToCamera:");
|
||||
for (int i=0;i<len+2;i++)
|
||||
printf("0x%02X,", bytes[i]);
|
||||
printf("0x%02X,", bytes[i]);
|
||||
printf("\n");
|
||||
*/
|
||||
// udp发送命令帧
|
||||
@ -549,6 +549,20 @@ void FoodCube::mav_request_data()
|
||||
// printf("send_mav\n");
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: 向飞控请求指定的参数值
|
||||
* @param {char*} param_id 要请求的参数的名称
|
||||
*/
|
||||
void FoodCube::mav_parameter_data(const char* param_id) {
|
||||
mavlink_message_t msg;
|
||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||
|
||||
// 构造PARAM_REQUEST_READ消息
|
||||
mavlink_msg_param_request_read_pack(1, 200, &msg, 1, 1, param_id, -1);
|
||||
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
SWrite(buf, len, mavlinkSerial);
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: 解析mavlink数据流
|
||||
* @param {pFun} pFun 拿到缓存数据之后 解析数据执行回调
|
||||
|
@ -64,6 +64,7 @@ public:
|
||||
/*mavlink*/
|
||||
String setNBit(String str, uint8_t n, uint8_t i);
|
||||
void mav_request_data();
|
||||
void mav_parameter_data(const char* param_id);
|
||||
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);
|
||||
|
@ -14,12 +14,12 @@ extern void Hook_recovery();
|
||||
static const char *MOUDLENAME = "COMMSER";
|
||||
|
||||
/*项目对象*/
|
||||
// char* ssid = "szdot"; //wifi帐号
|
||||
// char* password = "Ttaj@#*.com"; //wifi密码
|
||||
char* ssid = "szdot"; //wifi帐号
|
||||
char* password = "63587839ab"; //wifi密码
|
||||
// char *ssid = "flicube"; // wifi帐号
|
||||
// char *password = "fxmf0622"; // wifi密码
|
||||
char *ssid = "fxmf_sc01"; // 4g wifi帐号
|
||||
char *password = "12345678"; // 4g wifi密码
|
||||
// char *ssid = "fxmf_sc01"; // 4g wifi帐号
|
||||
// char *password = "12345678"; // 4g wifi密码
|
||||
char *mqttServer = "szdot.top"; // mqtt地址
|
||||
int mqttPort = 1883; // mqtt端口
|
||||
char *mqttName = "admin"; // mqtt帐号
|
||||
@ -32,11 +32,11 @@ uint32_t udpServerPort = 37260; // 云台相机端口
|
||||
FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象
|
||||
/* 发布 主题 ps:以下是登记发布json内容的组成元素 */
|
||||
// 登记 json成员名字
|
||||
// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:相对高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,海拔高度}
|
||||
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position"};
|
||||
// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:相对高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,海拔高度} 16:飞控参数{键:值}
|
||||
const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position","parameter"};
|
||||
const int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); // 登记 json成员总数
|
||||
String topicPubMsg[topicPubCount]; // 登记 json成员的值 对应topicPub
|
||||
String oldMsg[topicPubCount]; // 记录旧的值 用来对比有没有更新
|
||||
String topicPubMsg[topicPubCount] ={""}; // 登记 json成员的值 对应topicPub
|
||||
String oldMsg[topicPubCount]={""}; // 记录旧的值 用来对比有没有更新
|
||||
/*触发发送 主题*/
|
||||
// 0:对频信息
|
||||
String topicHandle[] = {"crosFrequency"};
|
||||
@ -160,6 +160,10 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
|
||||
String todo = value; // 转换值
|
||||
topicPubMsg[10] = todo; // 恢复初始状态
|
||||
}
|
||||
else if (key == "getBattCapacity")//请求 飞控返回 电池容量
|
||||
{
|
||||
fc.mav_parameter_data("BATT_CAPACITY");// 请求飞控 返回参数 电池容量 值
|
||||
}
|
||||
else if (key == "chan1")
|
||||
{
|
||||
uint16_t todo = value; // 转换值
|
||||
@ -487,13 +491,6 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_VALUE: // #22: PARAM_VALUE
|
||||
{
|
||||
mavlink_param_value_t param_value;
|
||||
mavlink_msg_param_value_decode(&msg, ¶m_value);
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_RAW_IMU: // #27: RAW_IMU
|
||||
{
|
||||
mavlink_raw_imu_t raw_imu;
|
||||
@ -513,7 +510,7 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
topicPubMsg[4] = buf;
|
||||
}
|
||||
// 海拔高度
|
||||
sprintf(buf, "{lng:%d,lat:%d,alt:%.2f}",
|
||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||
global_position_int.lon,
|
||||
global_position_int.lat,
|
||||
(double)global_position_int.alt / 1000);
|
||||
@ -685,6 +682,22 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_VALUE: // #22:获取飞控参数信息
|
||||
{
|
||||
mavlink_param_value_t param_value;
|
||||
mavlink_msg_param_value_decode(&msg, ¶m_value);
|
||||
|
||||
// 获取参数 格式化 JSON 字符串
|
||||
sprintf(buf, "{\"%s\":%.2f}", param_value.param_id, param_value.param_value);
|
||||
|
||||
if (topicPubMsg[16] != buf)
|
||||
{
|
||||
topicPubMsg[16] = buf;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@ -719,7 +732,7 @@ void pubThread()
|
||||
doc[topicPub[i]] = topicPubMsg[i];
|
||||
}
|
||||
else if (topicPubMsg[i] != oldMsg[i])
|
||||
{
|
||||
{
|
||||
// 非心跳 非飞机状态 有更新 录入成员
|
||||
doc[topicPub[i]] = topicPubMsg[i];
|
||||
oldMsg[i] = topicPubMsg[i];
|
||||
|
Loading…
Reference in New Issue
Block a user