【类 型】:feat

【原  因】:飞控mavlink发送 ADSB数据
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
air 2025-06-19 22:18:07 +08:00
parent 43dfbc91b2
commit 212a9e5da1
2 changed files with 308 additions and 247 deletions

View File

@ -5,7 +5,7 @@
//char* password = "63587839ab"; //wifi密码
char* ssid = "flicube"; //wifi帐号
char* password = "fxmf0622"; //wifi密码
char* mqttServer = "szdot.top"; //mqtt地址
char* mqttServer = "wxsky.com"; //mqtt地址
int mqttPort = 1883; //mqtt端口
char* mqttName = "admin"; //mqtt帐号
char* mqttPassword = "123456"; //mqtt密码

View File

@ -3,7 +3,8 @@
/**
* @description:
*/
FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int userMqttPort, char* userMqttName, char* userMqttPassword, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, char* userUdpServerIP, uint32_t userUdpServerPort) {
FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int userMqttPort, char *userMqttName, char *userMqttPassword, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, char *userUdpServerIP, uint32_t userUdpServerPort)
{
/*初始化*/
ssid = userSsid; // wifi帐号
password = userPassword; // wifi密码
@ -17,7 +18,8 @@ FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int
udpServerPort = userUdpServerPort; // 云台相机端口
// 初始化飞控通讯串口 波特率
switch (mavlinkSerial) { //初始化指定 串口号
switch (mavlinkSerial)
{ // 初始化指定 串口号
case 0:
Serial.begin(57600);
break;
@ -29,7 +31,8 @@ FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int
break;
}
// 初始化声音模块串口 波特率
switch (voiceSerial) { //初始化指定 串口号
switch (voiceSerial)
{ // 初始化指定 串口号
case 0:
Serial.begin(115200);
break;
@ -47,59 +50,74 @@ FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int
* @description:
* @param {*} val
*/
void FoodCube::log(String val) {
void FoodCube::log(String val)
{
Serial.print(val);
}
void FoodCube::log(char* val) {
void FoodCube::log(char *val)
{
Serial.print(val);
}
void FoodCube::log(int val) {
void FoodCube::log(int val)
{
Serial.print(val);
}
void FoodCube::log(IPAddress val) {
void FoodCube::log(IPAddress val)
{
Serial.print(val);
}
void FoodCube::log(bool val) {
void FoodCube::log(bool val)
{
Serial.print(val);
}
void FoodCube::logln(String val) {
void FoodCube::logln(String val)
{
Serial.println(val);
}
void FoodCube::logln(char* val) {
void FoodCube::logln(char *val)
{
Serial.println(val);
}
void FoodCube::logln(int val) {
void FoodCube::logln(int val)
{
Serial.println(val);
}
void FoodCube::logln(IPAddress val) {
void FoodCube::logln(IPAddress val)
{
Serial.println(val);
}
void FoodCube::logln(bool val) {
void FoodCube::logln(bool val)
{
Serial.print(val);
}
/**
*@description:
*/
bool FoodCube::getIsInit() {
bool FoodCube::getIsInit()
{
return isInit;
}
void FoodCube::setIsInit(bool b) {
void FoodCube::setIsInit(bool b)
{
isInit = b;
}
String FoodCube::getMacAdd() {
String FoodCube::getMacAdd()
{
return macAdd;
}
/**
* @description: wifi
*/
void FoodCube::connectWifi() {
void FoodCube::connectWifi()
{
// 设置wifi帐号密码
WiFi.begin(ssid, password);
// 连接wifi
logln("Connecting Wifi...");
while (WiFi.status() != WL_CONNECTED) {
while (WiFi.status() != WL_CONNECTED)
{
log(".");
delay(150);
}
@ -123,9 +141,11 @@ void FoodCube::connectWifi() {
* @description: mqtt
* @param {String} topicSub
*/
void FoodCube::connectMqtt(String topicSub) {
void FoodCube::connectMqtt(String topicSub)
{
/*尝试连接mqtt*/
if (mqttClient->connect(macAdd.c_str(), mqttName, mqttPassword)) {
if (mqttClient->connect(macAdd.c_str(), mqttName, mqttPassword))
{
logln("MQTT Server Connected.");
log("Server Address: ");
logln(mqttServer);
@ -135,7 +155,9 @@ void FoodCube::connectMqtt(String topicSub) {
// 订阅主题 PS:连接上mqtt服务器 订阅主题 收到信息触发回调函数 receiveCallback
subscribeTopic(topicSub, 1);
playText("服务器,已连接");
} else {
}
else
{
// 失败返回状态码
log("MQTT Server Connect Failed. Client State:");
logln(mqttClient->state());
@ -147,10 +169,14 @@ void FoodCube::connectMqtt(String topicSub) {
* @description: loop函数里 mqtt连接情况
* @param {String} topicSub
*/
void FoodCube::mqttLoop(String topicSub) {
if (mqttClient->connected()) { //检测 如果开发板成功连接服务器
void FoodCube::mqttLoop(String topicSub)
{
if (mqttClient->connected())
{ // 检测 如果开发板成功连接服务器
mqttClient->loop(); // 保持心跳
} else { // 如果开发板未能成功连接服务器
}
else
{ // 如果开发板未能成功连接服务器
connectMqtt(topicSub); // 则尝试连接服务器
}
}
@ -160,7 +186,8 @@ void FoodCube::mqttLoop(String topicSub) {
* @param {String} topicString
* @param {int} Qos 1 ps:
*/
void FoodCube::subscribeTopic(String topicString, int Qos = 1) {
void FoodCube::subscribeTopic(String topicString, int Qos = 1)
{
// 处理主题字符串
topicString = topicString + "/" + macAdd;
char subTopic[topicString.length() + 1];
@ -174,7 +201,8 @@ void FoodCube::subscribeTopic(String topicString, int Qos = 1) {
* @param {String} topicString
* @param {String} messageString
*/
void FoodCube::pubMQTTmsg(String topicString, String messageString) {
void FoodCube::pubMQTTmsg(String topicString, String messageString)
{
// 处理主题字符串
topicString = topicString + "/" + macAdd;
char publishTopic[topicString.length() + 1];
@ -192,9 +220,11 @@ void FoodCube::pubMQTTmsg(String topicString, String messageString) {
* @param {int} len
* @param {uint8_t} swSerial
*/
void FoodCube::SWrite(uint8_t buf[], int len, uint8_t swSerial) {
void FoodCube::SWrite(uint8_t buf[], int len, uint8_t swSerial)
{
// 通过串口发送
switch (swSerial) { //初始化指定 串口号
switch (swSerial)
{ // 初始化指定 串口号
case 0:
Serial.write(buf, len);
break;
@ -207,12 +237,12 @@ void FoodCube::SWrite(uint8_t buf[], int len, uint8_t swSerial) {
}
}
/**
* @description:
* @param {String} str
*/
void FoodCube::playText(String str) {
void FoodCube::playText(String str)
{
/*消息长度*/
int len = str.length(); // 修改信息长度 消息长度
// if (len >= 3996) { //限制信息长度 超长的不播放
@ -232,10 +262,12 @@ void FoodCube::playText(String str) {
command[index++] = 0x01;
command[index++] = 0x04;
/*帧命令 消息段*/
for (int i = 0; i < str.length(); i++) {
for (int i = 0; i < str.length(); i++)
{
command[index++] = (int)str[i];
}
for (int i = 0; i < sizeof(command); i++) {
for (int i = 0; i < sizeof(command); i++)
{
log(command[i]);
log(" ");
}
@ -248,28 +280,33 @@ void FoodCube::playText(String str) {
* @description:
* @return {uint8_t} 0x4E 78: 0x4F 79:
*/
uint8_t FoodCube::chekVoiceMcu() {
uint8_t FoodCube::chekVoiceMcu()
{
uint8_t serialData;
uint8_t check[] = {0xFD, 0x00, 0x01, 0x21}; // 检查命令帧
SWrite(check, sizeof(check), voiceSerial); // 发送检查指令
switch (voiceSerial) {
switch (voiceSerial)
{
case 0:
{
while (Serial.available()) { // 当串口接收到信息后
while (Serial.available())
{ // 当串口接收到信息后
serialData = Serial.read(); // 将接收到的信息使用read读取
}
}
break;
case 1:
{
while (Serial1.available()) { // 当串口接收到信息后
while (Serial1.available())
{ // 当串口接收到信息后
serialData = Serial1.read(); // 将接收到的信息使用read读取
}
}
break;
case 2:
{
while (Serial2.available()) { // 当串口接收到信息后
while (Serial2.available())
{ // 当串口接收到信息后
serialData = Serial2.read(); // 将接收到的信息使用read读取
}
}
@ -282,7 +319,8 @@ uint8_t FoodCube::chekVoiceMcu() {
/**
* @description:
*/
void FoodCube::stopVoice() {
void FoodCube::stopVoice()
{
uint8_t stop[] = {0xFD, 0x00, 0x01, 0x22}; // 停止合成命令帧
SWrite(stop, sizeof(stop), voiceSerial); // 发送检查指令
}
@ -292,11 +330,13 @@ void FoodCube::stopVoice() {
* @param {uint8_t[]}
* @param {int} len
*/
uint16_t FoodCube::CRC16_cal(uint8_t* ptr, uint32_t len, uint16_t crc_init) {
uint16_t FoodCube::CRC16_cal(uint8_t *ptr, uint32_t len, uint16_t crc_init)
{
uint16_t crc, oldcrc16;
uint8_t temp;
crc = crc_init;
while (len-- != 0) {
while (len-- != 0)
{
temp = (crc >> 8) & 0xff;
oldcrc16 = crc16_tab[*ptr ^ temp];
crc = (crc << 8) ^ oldcrc16;
@ -305,7 +345,8 @@ uint16_t FoodCube::CRC16_cal(uint8_t* ptr, uint32_t len, uint16_t crc_init) {
return (crc);
}
void FoodCube::crc_check_16bites(uint8_t* pbuf, uint32_t len, uint16_t* p_result) {
void FoodCube::crc_check_16bites(uint8_t *pbuf, uint32_t len, uint16_t *p_result)
{
uint16_t crc_result = 0;
crc_result = CRC16_cal(pbuf, len, 0);
*p_result = crc_result;
@ -315,14 +356,16 @@ void FoodCube::crc_check_16bites(uint8_t* pbuf, uint32_t len, uint16_t* p_result
* @param {uint8_t[]}
* @param {int} len
*/
void FoodCube::udpSendToCamera(uint8_t* p_command, uint32_t len) {
void FoodCube::udpSendToCamera(uint8_t *p_command, uint32_t len)
{
uint16_t result = 0;
uint16_t *p_result = &result;
// 计算校检码
crc_check_16bites(p_command, len, p_result);
// 加上校检码
uint8_t bytes[2 + len];
for (int i = 0; i < len; i++) {
for (int i = 0; i < len; i++)
{
bytes[i] = p_command[i];
}
bytes[len] = static_cast<uint8_t>(result); // 低位 互换
@ -339,24 +382,27 @@ void FoodCube::udpSendToCamera(uint8_t* p_command, uint32_t len) {
* @param {uint8_t} n 0
* @param {uint8_t} isOne 1:1 0:0
*/
String FoodCube::setNBit(String str, uint8_t n, uint8_t i) {
String FoodCube::setNBit(String str, uint8_t n, uint8_t i)
{
char buf[10];
uint16_t val = (uint8_t)str.toInt();
if (i) {
if (i)
{
val |= (1u << n); // 按位设置成1
} else {
}
else
{
val &= ~(1u << n); // 按位设置成0
}
sprintf(buf, "%d", val);
return buf;
}
/**
* @description:
*/
void FoodCube::mav_request_data() {
void FoodCube::mav_request_data()
{
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// 以下注释 把数据流组合到一起
@ -376,7 +422,8 @@ void FoodCube::mav_request_data() {
const int maxStreams = 1; // 遍历次数 (下面组合的长度)
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_ALL}; // 请求的数据流组合 放到一个对象 后面进行遍历
const uint16_t MAVRates[maxStreams] = {0x01}; // 设定发送频率 分别对应上面数据流 ps:0X01 1赫兹 既每秒发送一次
for (int i = 0; i < maxStreams; i++) {
for (int i = 0; i < maxStreams; i++)
{
// 向飞控发送请求
mavlink_msg_request_data_stream_pack(2, 200, &msg, 1, 0, MAVStreams[i], MAVRates[i], 1);
int len = mavlink_msg_to_send_buffer(buf, &msg);
@ -388,22 +435,27 @@ void FoodCube::mav_request_data() {
* @description: mavlink数据流
* @param {pFun} pFun
*/
void FoodCube::comm_receive(void (*pFun)(uint8_t)) {
switch (mavlinkSerial) {
void FoodCube::comm_receive(void (*pFun)(uint8_t))
{
switch (mavlinkSerial)
{
case 0:
while (Serial.available() > 0) { // 判断串口缓存 是否有数据
while (Serial.available() > 0)
{ // 判断串口缓存 是否有数据
uint8_t c = Serial.read(); // 从缓存拿到数据
pFun(c);
}
break;
case 1:
while (Serial1.available() > 0) { // 判断串口缓存 是否有数据
while (Serial1.available() > 0)
{ // 判断串口缓存 是否有数据
uint8_t c = Serial1.read(); // 从缓存拿到数据
pFun(c);
}
break;
case 2:
while (Serial2.available() > 0) { // 判断串口缓存 是否有数据
while (Serial2.available() > 0)
{ // 判断串口缓存 是否有数据
uint8_t c = Serial2.read(); // 从缓存拿到数据
pFun(c);
}
@ -415,7 +467,8 @@ void FoodCube::comm_receive(void (*pFun)(uint8_t)) {
* @description:
* @param {uint8_t} taskcount
*/
void FoodCube::mav_mission_count(uint8_t taskcount) {
void FoodCube::mav_mission_count(uint8_t taskcount)
{
mavlink_message_t msg; // mavlink协议信息(msg)
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
// 设置飞行模式的数据包
@ -440,7 +493,8 @@ void FoodCube::mav_mission_count(uint8_t taskcount) {
* @param {double} y
* @param {double} z
*/
void FoodCube::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 FoodCube::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)
{
mavlink_message_t msg; // mavlink协议信息(msg)
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
// 写入航点数据包
@ -453,7 +507,8 @@ void FoodCube::mav_mission_item(int8_t seq, uint8_t frame, uint8_t command, uint
/**
* @description:
*/
void FoodCube::mav_set_mode(uint8_t SysState) {
void FoodCube::mav_set_mode(uint8_t SysState)
{
mavlink_message_t msg; // mavlink协议信息(msg)
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
// 设置飞行模式的数据包
@ -468,7 +523,8 @@ void FoodCube::mav_set_mode(uint8_t SysState) {
* @param {uint8_t} controlType 3:
* @param {uint16_t} param[]
*/
void FoodCube::mav_command(uint8_t controlType, uint16_t param[]) {
void FoodCube::mav_command(uint8_t controlType, uint16_t param[])
{
mavlink_message_t msg; // mavlink协议信息(msg)
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
// 设置飞行模式的数据包
@ -476,12 +532,14 @@ void FoodCube::mav_command(uint8_t controlType, uint16_t param[]) {
cmd.target_system = 1;
cmd.target_component = 1;
cmd.confirmation = 0;
if (controlType == 3) { //飞机加解锁
if (controlType == 3)
{ // 飞机加解锁
cmd.command = MAV_CMD_COMPONENT_ARM_DISARM;
cmd.param1 = param[0]; // 0:加锁 1解锁
cmd.param2 = param[1]; // 0:符合条件加解锁 21196:强制加解锁
}
if (controlType == 6) { //测试起飞
if (controlType == 6)
{ // 测试起飞
float p = (float)param[0];
cmd.command = MAV_CMD_NAV_TAKEOFF;
cmd.param1 = 0;
@ -492,10 +550,12 @@ void FoodCube::mav_command(uint8_t controlType, uint16_t param[]) {
cmd.param6 = 0;
cmd.param7 = p; // 起飞高度
}
if (controlType == 8) { //降落
if (controlType == 8)
{ // 降落
cmd.command = MAV_CMD_NAV_LAND;
}
if (controlType == 11) { //磁罗盘校准
if (controlType == 11)
{ // 磁罗盘校准
cmd.command = MAV_CMD_DO_START_MAG_CAL;
cmd.param1 = 0;
cmd.param2 = 1;
@ -510,7 +570,8 @@ void FoodCube::mav_command(uint8_t controlType, uint16_t param[]) {
* @description:
* @param {uint16_t} chan[]
*/
void FoodCube::mav_channels_override(uint16_t chan[]) {
void FoodCube::mav_channels_override(uint16_t chan[])
{
mavlink_message_t msg; // mavlink协议信息(msg)
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
// 控制油门