Browse Source

1、添加2023试行 2025GB 5.1实行 国标协议库
2、对ODID载荷数据进行转换得到GB数据包
3、对wifi和ble对应的广播包国标接口进行添加
4、国标只要求bt5 对于wifi的格式只要求了 beacon信标帧 配置上与开源基本一致
5、lock=-1 可通过web升级 反馈给飞控的心跳 和 当前状态
6、根据protocol进行选择发送哪个标准的广播包
7、默认remoteid处理接口通过uart 后续可以考虑设置成可配置参数 或者 分别提供两个不同固件

zhuts 2 weeks ago
parent
commit
b93d779f93

BIN
GB+46750-2025.pdf


+ 249 - 25
RemoteIDModule/BLE_TX.cpp

@@ -97,20 +97,20 @@ bool BLE_TX::init(void)
     // setup power levels
     // setup power levels
     legacy_adv_params.tx_power = dBm_to_tx_power(g.bt4_power);
     legacy_adv_params.tx_power = dBm_to_tx_power(g.bt4_power);
     ext_adv_params_coded.tx_power = dBm_to_tx_power(g.bt5_power);
     ext_adv_params_coded.tx_power = dBm_to_tx_power(g.bt5_power);
-
+    
     // set min/max interval based on output rate    
     // set min/max interval based on output rate    
     legacy_adv_params.interval_max =  (1000/(g.bt4_rate*7))/0.625;
     legacy_adv_params.interval_max =  (1000/(g.bt4_rate*7))/0.625;
     legacy_adv_params.interval_min = 0.75*legacy_adv_params.interval_max;
     legacy_adv_params.interval_min = 0.75*legacy_adv_params.interval_max;
     ext_adv_params_coded.interval_max =  (1000/(g.bt5_rate))/0.625;
     ext_adv_params_coded.interval_max =  (1000/(g.bt5_rate))/0.625;
     ext_adv_params_coded.interval_min = 0.75*ext_adv_params_coded.interval_max;
     ext_adv_params_coded.interval_min = 0.75*ext_adv_params_coded.interval_max;
-
+    // 调试抓包
     // generate random mac address
     // generate random mac address
     uint8_t mac_addr[6];
     uint8_t mac_addr[6];
     generate_random_mac(mac_addr);
     generate_random_mac(mac_addr);
 
 
     // set as a bluetooth random static address
     // set as a bluetooth random static address
     mac_addr[0] |= 0xc0;
     mac_addr[0] |= 0xc0;
-
+   
     advert.setAdvertisingParams(0, &legacy_adv_params);
     advert.setAdvertisingParams(0, &legacy_adv_params);
     advert.setInstanceAddress(0, mac_addr);
     advert.setInstanceAddress(0, mac_addr);
     advert.setDuration(0);
     advert.setDuration(0);
@@ -124,7 +124,8 @@ bool BLE_TX::init(void)
         Serial.printf("Failed to setup S8 coding\n");
         Serial.printf("Failed to setup S8 coding\n");
     }
     }
 
 
-    memset(&msg_counters,0, sizeof(msg_counters));
+    memset(&msg_counters_CNDID,0, sizeof(msg_counters_CNDID));
+    memset(&msg_counters_ODID,0, sizeof(msg_counters_ODID));
     return true;
     return true;
 }
 }
 
 
@@ -139,9 +140,10 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
     if (length <= 0) {
     if (length <= 0) {
         return false;
         return false;
     }
     }
-
+    // Serial.printf("ble4 tx power %d\n", legacy_adv_params.tx_power);
+    // Serial.printf("ble5 tx power %d\n", ext_adv_params_coded.tx_power);
     // setup ASTM header
     // setup ASTM header
-    const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters[ODID_MSG_COUNTER_PACKED]++) };
+    const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters_ODID[ODID_MSG_COUNTER_PACKED]++) };
 
 
     // combine header with payload
     // combine header with payload
     memcpy(longrange_payload, header, sizeof(header));
     memcpy(longrange_payload, header, sizeof(header));
@@ -151,6 +153,8 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
     advert.setAdvertisingData(1, longrange_length, longrange_payload);
     advert.setAdvertisingData(1, longrange_length, longrange_payload);
 
 
     // we start advertising when we have the first lot of data to send
     // we start advertising when we have the first lot of data to send
+    // Serial.printf("started is %d\n", started);
+    // Serial.printf("longrange is %s\n", longrange_payload);
     if (!started) {
     if (!started) {
         advert.start();
         advert.start();
     }
     }
@@ -162,6 +166,8 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
 bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
 {
 {
     init();
     init();
+    // Serial.printf("ble4 tx power %d\n", legacy_adv_params.tx_power);
+    // Serial.printf("ble5 tx power %d\n", ext_adv_params_coded.tx_power);
     static uint8_t legacy_phase = 0;
     static uint8_t legacy_phase = 0;
     int legacy_length = 0;
     int legacy_length = 0;
     // setup ASTM header
     // setup ASTM header
@@ -181,9 +187,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_LOCATION]++;
-            //msg_counters[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_LOCATION]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
@@ -199,9 +205,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
-            //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
@@ -217,9 +223,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_SELF_ID]++;
-            //msg_counters[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
@@ -235,9 +241,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_SYSTEM]++;
-            //msg_counters[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
@@ -253,9 +259,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_OPERATOR_ID]++;
-            //msg_counters[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
@@ -271,9 +277,9 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
                 break;
                 break;
             }
             }
 
 
-            memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
-            msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
-            //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
+            msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID]++;
+            //msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
 
 
             memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
             memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
             legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
             legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
@@ -285,7 +291,7 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
         char legacy_name[28] {};
         char legacy_name[28] {};
         const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
         const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
         const uint8_t ID_len = strlen(UAS_ID);
         const uint8_t ID_len = strlen(UAS_ID);
-        const uint8_t ID_tail = IMIN(4, ID_len);
+        const uint8_t ID_tail = IMIN(4, ID_len); 
         snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
         snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
 
 
         memset(legacy_payload, 0, sizeof(legacy_payload));
         memset(legacy_payload, 0, sizeof(legacy_payload));
@@ -308,7 +314,46 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
     }
     }
 
 
     advert.setAdvertisingData(0, legacy_length, legacy_payload);
     advert.setAdvertisingData(0, legacy_length, legacy_payload);
+    // Serial.printf("started is %d\n", started);
+    // Serial.printf("legacy is %s\n", legacy_payload);
+    if (!started) {
+        advert.start();
+    }
+    started = true;
 
 
+    return true;
+}
+
+
+// bt5 蓝牙发送国标数据
+bool BLE_TX::transmit_cn_longrange(CNDID_UAS_Data &UAS_data)
+{
+     init();
+    // create a packed UAS data message
+    uint8_t payload[250];
+    int length = cndid_message_build_pack(&UAS_data, payload, 255);
+    if (length <= 0) {
+        return false;
+    }
+
+    // setup ASTM header American Society for Testing and Materials
+    const uint8_t header[] { uint8_t(length+5),   // 头字段1:总长度(payload长度 + 5个固定头字节)
+        0x16,  // 头字段2:ASTM协议固定标识(Remote ID相关)
+        0xfa,  // 头字段3:厂商/类型标识(自定义或标准值)
+        0xff,  // 头字段4:保留/扩展位
+        0x0d,  // 头字段5:消息类型(如打包的UAS数据类型)
+        uint8_t(msg_counters_CNDID[CNDID_MSG_COUNTER_PACKED]++) }; // 头字段6:消息计数器(自增,防丢包/重放)
+
+    // // 拼接协议头和payload到最终发送缓冲区longrange_payload
+    memcpy(longrange_payload, header, sizeof(header)); // 先拷贝协议头
+    memcpy(&longrange_payload[sizeof(header)], payload, length);  // 再拷贝payload
+    int longrange_length = sizeof(header) + length;  // 计算最终数据包总长度
+    // 设置BLE广播数据(参数:广播类型1,数据长度,数据缓冲区)
+    advert.setAdvertisingData(1, longrange_length, longrange_payload);
+    // 首次发送时启动BLE广播(避免重复启动)    
+    // we start advertising when we have the first lot of data to send
+    // Serial.printf("started is %d\n", started);
+    // Serial.printf("longrange is %s\n", longrange_payload);
     if (!started) {
     if (!started) {
         advert.start();
         advert.start();
     }
     }
@@ -316,3 +361,182 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
 
 
     return true;
     return true;
 }
 }
+
+// bt4 蓝牙发送国标数据
+bool BLE_TX::transmit_cn_legacy(CNDID_UAS_Data &UAS_data)
+{
+    init();
+    static uint8_t legacy_phase = 0;
+    int legacy_length = 0;
+    // 设置ASTM标头 这个标头可能要根据国标修改
+    const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; // 排除消息计数器
+    // 将头部与有效载荷结合起来
+    memset(legacy_payload, 0, sizeof(legacy_payload));
+    memcpy(legacy_payload, header, sizeof(header));
+    legacy_length = sizeof(header);
+
+    switch (legacy_phase)
+    {
+    case  0: {
+        if (UAS_data.LocationValid) {
+            CNDID_Location_encoded location_encoded;
+            memset(&location_encoded, 0, sizeof(location_encoded));
+            if (encodeCNLocationMessage(&location_encoded, &UAS_data.Location) != CNDID_SUCCESS) {
+                break;
+            }
+
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION], 1); //set packet counter
+            msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION]++;
+            //msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
+
+            memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
+        }
+        break;
+    }
+
+    case  1: {
+        if (UAS_data.BasicIDValid[0]) {
+            CNDID_BasicID_encoded basicid_encoded;
+            memset(&basicid_encoded, 0, sizeof(basicid_encoded));
+            if (encodeCNBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != CNDID_SUCCESS) {
+                break;
+            }
+
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
+            msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID]++;
+            //msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
+
+            memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
+        }
+        break;
+    }
+
+    case  2: {
+        if (UAS_data.SelfIDValid) {
+            CNDID_SelfID_encoded selfid_encoded;
+            memset(&selfid_encoded, 0, sizeof(selfid_encoded));
+            if (encodeCNSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != CNDID_SUCCESS) {
+                break;
+            }
+
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID], 1); //set packet counter
+            msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID]++;
+            //msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
+
+            memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
+        }
+        break;
+    }
+
+    case  3: {
+        if (UAS_data.SystemValid) {
+            CNDID_System_encoded system_encoded;
+            memset(&system_encoded, 0, sizeof(system_encoded));
+            if (encodeCNSystemMessage(&system_encoded, &UAS_data.System) != CNDID_SUCCESS) {
+                break;
+            }
+
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM], 1); //set packet counter
+            msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM]++;
+            //msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
+
+            memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
+        }
+        break;
+    }
+
+    case  4: //in case of dual basic ID 在存在双重基本身份标识的情况下
+        if (UAS_data.BasicIDValid[1]) {
+            CNDID_BasicID_encoded basicid2_encoded;
+            memset(&basicid2_encoded, 0, sizeof(basicid2_encoded));
+            if (encodeCNBasicIDMessage(&basicid2_encoded, &UAS_data.BasicID[1]) != CNDID_SUCCESS) {
+                break;
+            }
+
+            memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
+            msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID]++;
+            //msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID] %= 256; //可能不需要,因为它被定义为unint_8
+
+            memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
+        }
+        break;
+
+    case  5: {
+        //set BLE name  构造BLE设备名称:CN_RemoteID_XXXX(XXXX是无人机ID后4位)
+        char legacy_name[28] {};
+        const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
+        const uint8_t ID_len = strlen(UAS_ID);
+        const uint8_t ID_tail = IMIN(4, ID_len);
+        snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
+         // 清空缓冲区,构造BLE名称广播标头(符合BLE AD规范)
+        memset(legacy_payload, 0, sizeof(legacy_payload));
+        const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
+         // 拷贝名称标头 + 名称内容
+        memcpy(legacy_payload, legacy_name_header, sizeof(legacy_name_header));
+        memcpy(&legacy_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
+        // 更新广播长度(标头+名称+结束符)
+        legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
+        break;
+    }
+    }
+
+    legacy_phase++; // 每次发送后阶段自增
+
+    if (UAS_data.BasicIDValid[1]) { // 根据是否有双重基础ID,控制阶段循环范围
+        legacy_phase %= 6; 
+    } else {
+        legacy_phase %= 5;
+    }
+    // 设置BLE广播数据(长度+内容)
+    advert.setAdvertisingData(0, legacy_length, legacy_payload);
+    // 若广播未启动则启动,标记为已启动
+    // Serial.printf("started is %d\n", started);
+    // Serial.printf("legacy is %s\n", legacy_payload);
+    if (!started) {
+        advert.start();
+    }
+    started = true;
+
+    return true;
+}
+// 以下数据包不再准寻报文加集合报文的形式 无法再进行legacy这种分报文发送的形式
+bool BLE_TX::transmit_GB2025_longrange(UavIdentificationData &UAS_data)
+{
+    init();
+    // create a packed UAS data message
+    uint8_t payload[250];
+    int length = did_GB2025_message_build_pack(&UAS_data, payload, 255);
+    if (length <= 0) {
+        return false;
+    }
+
+    // setup ASTM header American Society for Testing and Materials
+    const uint8_t header[] { uint8_t(length+5),   // 头字段1:总长度(payload长度 + 5个固定头字节)
+        0x16,  // 头字段2:ASTM协议固定标识(Remote ID相关)
+        0xfa,  // 头字段3:厂商/类型标识(自定义或标准值)
+        0xff,  // 头字段4:保留/扩展位
+        0x0d,  // 头字段5:消息类型(如打包的UAS数据类型)
+        uint8_t(msg_counters_GB2025++) }; // 头字段6:消息计数器(自增,防丢包/重放)
+
+    // // 拼接协议头和payload到最终发送缓冲区longrange_payload
+    memcpy(longrange_payload, header, sizeof(header)); // 先拷贝协议头
+    memcpy(&longrange_payload[sizeof(header)], payload, length);  // 再拷贝payload
+    int longrange_length = sizeof(header) + length;  // 计算最终数据包总长度
+    // 设置BLE广播数据(参数:广播类型1,数据长度,数据缓冲区)
+    advert.setAdvertisingData(1, longrange_length, longrange_payload);
+    // 首次发送时启动BLE广播(避免重复启动)    
+    // we start advertising when we have the first lot of data to send
+    // Serial.printf("started is %d\n", started);
+    // Serial.printf("longrange is %s\n", longrange_payload);
+    if (!started) {
+        advert.start();
+    }
+    started = true;
+
+    return true;
+}

+ 8 - 4
RemoteIDModule/BLE_TX.h

@@ -8,12 +8,16 @@
 class BLE_TX : public Transmitter {
 class BLE_TX : public Transmitter {
 public:
 public:
     bool init(void) override;
     bool init(void) override;
-    bool transmit_longrange(ODID_UAS_Data &UAS_data);
-    bool transmit_legacy(ODID_UAS_Data &UAS_data);
-
+    bool transmit_cn_longrange(CNDID_UAS_Data &UAS_data); // 国标蓝牙协议发送
+    bool transmit_cn_legacy(CNDID_UAS_Data &UAS_data);   // 国标蓝牙协议发送
+    bool transmit_longrange(ODID_UAS_Data &UAS_data);    // 国际蓝牙协议发送
+    bool transmit_legacy(ODID_UAS_Data &UAS_data);       // 国际蓝牙协议发送
+    bool transmit_GB2025_longrange(UavIdentificationData  &UAS_data);             // GB2025 包协议发送
 private:
 private:
     bool initialised;
     bool initialised;
-    uint8_t msg_counters[ODID_MSG_COUNTER_AMOUNT];
+    uint8_t msg_counters_ODID[ODID_MSG_COUNTER_AMOUNT];  // 国际计数器
+    uint8_t msg_counters_CNDID[CNDID_MSG_COUNTER_AMOUNT]; // 国标计数器
+    uint8_t msg_counters_GB2025;
     uint8_t legacy_payload[36];
     uint8_t legacy_payload[36];
     uint8_t longrange_payload[250];
     uint8_t longrange_payload[250];
     bool started;
     bool started;

+ 18 - 4
RemoteIDModule/Makefile

@@ -8,14 +8,21 @@ ESPTOOL=$(ESP32_TOOLS)/esptool.py
 ESP32_FQBN=esp32:esp32:$(CHIP)
 ESP32_FQBN=esp32:esp32:$(CHIP)
 SERDEV := $(wildcard /dev/serial/by-id/usb-Espressif_*)
 SERDEV := $(wildcard /dev/serial/by-id/usb-Espressif_*)
 ARDUINO_CLI=../bin/arduino-cli
 ARDUINO_CLI=../bin/arduino-cli
-APP_PARTITION_SIZE=2031616
+APP_PARTITION_SIZE=2031616 # 给程序分配0x1F0000空间 目前 0x165560
 
 
 # ensure python tools are in $PATH
 # ensure python tools are in $PATH
 export PATH := $(HOME)/.local/bin:$(PATH)
 export PATH := $(HOME)/.local/bin:$(PATH)
 
 
 .PHONY: headers
 .PHONY: headers
+# 不管你的文件夹里有没有叫 headers 的文件 / 文件夹,只要你在终端敲 make headers,
+# 电脑就必须执行你给 headers 定好的那些命令(比如复制头文件、生成文件),不会找任何借口偷懒。 
+# 没有 .PHONY 时:电脑会先看有没有叫 headers 的文件,如果有,就觉得 “这事儿已经做完了”,直接说 “不用弄了”,不执行你写的命令
+# 加了 .PHONY: headers 后:电脑不管有没有这个文件,都当 “这事儿还没做”,乖乖执行你安排的命令,绝不偷懒
 
 
-all: headers esp32s3dev esp32c3dev bluemark-db200 bluemark-db110 jw-tbd mro-rid jwrid-esp32s3 bluemark-db202 bluemark-db210 bluemark-db203 holybro-RemoteID CUAV-RID
+# all: headers esp32s3dev esp32c3dev bluemark-db200 bluemark-db110 jw-tbd mro-rid jwrid-esp32s3 bluemark-db202 bluemark-db210 bluemark-db203 holybro-RemoteID CUAV-RID VKUAV-RID
+# 电脑会按你写的顺序来 —— 先跑 headers 的命令,跑完再跑 esp32s3dev,以此类推,前面的没做完,后面的不会开始
+# 如果你不想全做,只想做其中一个(比如只编译 esp32c3dev),也可以敲 make esp32c3dev,电脑只会执行这一个指令
+all: headers esp32s3dev
 
 
 esp32s3dev: CHIP=esp32s3
 esp32s3dev: CHIP=esp32s3
 esp32s3dev: ArduRemoteID-ESP32S3_DEV.bin
 esp32s3dev: ArduRemoteID-ESP32S3_DEV.bin
@@ -53,15 +60,22 @@ holybro-RemoteID: ArduRemoteID-Holybro_RemoteID.bin
 CUAV-RID: CHIP=esp32s3
 CUAV-RID: CHIP=esp32s3
 CUAV-RID: ArduRemoteID-CUAV_RID.bin
 CUAV-RID: ArduRemoteID-CUAV_RID.bin
 
 
+VKUAV-RID: CHIP=esp32s3
+VKUAV-RID: ArduRemoteID-VKUAV_RID.bin
+# 让 Arduino 命令行工具(arduino-cli)更新硬件库的 “索引列表”
+# 安装指定版本($(ESP32_VER) 是提前定义的版本号,比如 2.0.14)的 ESP32 核心开发包
+# 自动安装 “Adafruit NeoPixel” 这个第三方库(用来控制灯带的常用库)
 setup:
 setup:
 	@echo "Installing ESP32 support"
 	@echo "Installing ESP32 support"
 	$(ARDUINO_CLI) core update-index --config-file arduino-cli.yaml
 	$(ARDUINO_CLI) core update-index --config-file arduino-cli.yaml
 	$(ARDUINO_CLI) core install esp32:esp32@$(ESP32_VER)
 	$(ARDUINO_CLI) core install esp32:esp32@$(ESP32_VER)
 	$(ARDUINO_CLI) lib install "Adafruit NeoPixel"
 	$(ARDUINO_CLI) lib install "Adafruit NeoPixel"
-
+# 电脑会自动去执行上级目录下 scripts 文件夹里的 git-version.sh 这个脚本文件 
 gitversion:
 gitversion:
 	@../scripts/git-version.sh
 	@../scripts/git-version.sh
-
+# 根据刚获取的 Git 版本信息,重新生成项目的头文件 具体
+# 主要做两件事:生成 MAVLink2 和 DroneCAN 通信协议的头文件(让 ESP32 能和无人机 / 飞控通信)
+# 再更新 RemoteIDModule 模块的 Git 版本信息,全程自动化不用手动改代码
 headers: gitversion
 headers: gitversion
 	@cd .. && scripts/regen_headers.sh
 	@cd .. && scripts/regen_headers.sh
 
 

+ 593 - 76
RemoteIDModule/RemoteIDModule.ino

@@ -12,6 +12,7 @@
 #include <time.h>
 #include <time.h>
 #include <sys/time.h>
 #include <sys/time.h>
 #include <opendroneid.h>
 #include <opendroneid.h>
+#include "cndroneid.h"
 #include "mavlink.h"
 #include "mavlink.h"
 #include "DroneCAN.h"
 #include "DroneCAN.h"
 #include "WiFi_TX.h"
 #include "WiFi_TX.h"
@@ -24,8 +25,9 @@
 #include <esp_ota_ops.h>
 #include <esp_ota_ops.h>
 #include "efuse.h"
 #include "efuse.h"
 #include "led.h"
 #include "led.h"
-
-
+// did_GB2025 是GB 46750—2025相关的协议实现
+// cn_did     是2023年的试运行协议实现 本质与opendroneid没有太大区别
+// 发给mavlink 的消息也会被调试串口转发 一个是心跳 一个是错误状态
 #if AP_DRONECAN_ENABLED
 #if AP_DRONECAN_ENABLED
 static DroneCAN dronecan;
 static DroneCAN dronecan;
 #endif
 #endif
@@ -42,6 +44,8 @@ static BLE_TX ble;
 
 
 // OpenDroneID output data structure
 // OpenDroneID output data structure
 ODID_UAS_Data UAS_data;
 ODID_UAS_Data UAS_data;
+CNDID_UAS_Data CN_UAS_data; // 国标输出结构体 每个报文的大小都是25字节 走转发
+UavIdentificationData GB2025_UAS_data;
 String status_reason;
 String status_reason;
 static uint32_t last_location_ms;
 static uint32_t last_location_ms;
 static WebInterface webif;
 static WebInterface webif;
@@ -52,33 +56,86 @@ static WebInterface webif;
 static bool arm_check_ok = false; // goes true for LED arm check status
 static bool arm_check_ok = false; // goes true for LED arm check status
 static bool pfst_check_ok = false;
 static bool pfst_check_ok = false;
 
 
+void print_g_struct()
+{
+    Serial.println("\n========== GLOBAL STRUCTURE g ==========");
+    
+    // 基础配置
+    Serial.printf("LOCK_LEVEL         = %d\n", g.lock_level);
+    Serial.printf("CAN_NODE           = %u\n", g.can_node);
+#if defined(PIN_CAN_TERM)
+    Serial.printf("CAN_TERMINATE      = %u\n", g.can_term);
+#endif
+    
+    // UAS 相关
+    Serial.printf("UAS_TYPE           = %u\n", g.ua_type);
+    Serial.printf("UAS_ID_TYPE        = %u\n", g.id_type);
+    Serial.printf("UAS_ID             = %s\n", g.uas_id);
+    Serial.printf("UAS_TYPE_2         = %u\n", g.ua_type_2);
+    Serial.printf("UAS_ID_TYPE_2      = %u\n", g.id_type_2);
+    Serial.printf("UAS_ID_2           = %s\n", g.uas_id_2);
+    
+    // 通信配置
+    Serial.printf("BAUDRATE           = %lu\n", g.baudrate);
+    Serial.printf("WIFI_NAN_RATE      = %.2f\n", g.wifi_nan_rate);
+    Serial.printf("WIFI_BEACON_RATE   = %.2f\n", g.wifi_beacon_rate);
+    Serial.printf("WIFI_POWER         = %.2f dBm\n", g.wifi_power);
+    
+    // 蓝牙配置(重点!)
+    Serial.printf("BT4_RATE           = %.2f Hz\n", g.bt4_rate);
+    Serial.printf("BT4_POWER          = %.2f dBm\n", g.bt4_power);
+    Serial.printf("BT5_RATE           = %.2f Hz\n", g.bt5_rate);
+    Serial.printf("BT5_POWER          = %.2f dBm\n", g.bt5_power);
+    
+    // Web 和 WiFi
+    Serial.printf("WEBSERVER_EN       = %u\n", g.webserver_enable);
+    Serial.printf("WIFI_SSID          = %s\n", g.wifi_ssid);
+    Serial.printf("WIFI_PASSWORD      = %s\n", g.wifi_password);  // 注意:生产环境慎打密码
+    Serial.printf("WIFI_CHANNEL       = %u\n", g.wifi_channel);
+    
+    // 其他配置
+    Serial.printf("BCAST_POWERUP      = %u\n", g.bcast_powerup);
+    Serial.printf("MAVLINK_SYSID      = %u\n", g.mavlink_sysid);
+    Serial.printf("OPTIONS            = %u\n", g.options);
+    Serial.printf("TO_DEFAULTS        = %u\n", g.to_factory_defaults);
+    Serial.printf("DONE_INIT          = %u\n", g.done_init);
+    Serial.printf("PROTOCOL           = %u\n", g.protocol);
+    Serial.println("==========================================\n");
+}
+
 /*
 /*
   setup serial ports
   setup serial ports
  */
  */
 void setup()
 void setup()
 {
 {
+    // delay(2000);
+
     // disable brownout checking
     // disable brownout checking
     WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
     WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
 
 
     g.init();
     g.init();
 
 
+  
     led.set_state(Led::LedState::INIT);
     led.set_state(Led::LedState::INIT);
     led.update();
     led.update();
 
 
-    if (g.webserver_enable) {
-        // need WiFi for web server
-        wifi.init();
-    }
-
     // Serial for debug printf
     // Serial for debug printf
     Serial.begin(g.baudrate);
     Serial.begin(g.baudrate);
 
 
+    // print_g_struct();
+    // g.protocol = 1;
     // Serial1 for MAVLink
     // Serial1 for MAVLink
     Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
     Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
 
 
+    if (g.webserver_enable) {
+        // need WiFi for web server
+        wifi.init();
+    }
+
     // set all fields to invalid/initial values
     // set all fields to invalid/initial values
     odid_initUasData(&UAS_data);
     odid_initUasData(&UAS_data);
-
+    cndid_initUasData(&CN_UAS_data);
+    uav_identification_data_init(&GB2025_UAS_data);
 #if AP_MAVLINK_ENABLED
 #if AP_MAVLINK_ENABLED
     mavlink1.init();
     mavlink1.init();
     mavlink2.init();
     mavlink2.init();
@@ -133,63 +190,367 @@ void setup()
 
 
     esp_ota_mark_app_valid_cancel_rollback();
     esp_ota_mark_app_valid_cancel_rollback();
 }
 }
-
 #define IMIN(x,y) ((x)<(y)?(x):(y))
 #define IMIN(x,y) ((x)<(y)?(x):(y))
 #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
 #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
-
+/**
+ * mavlink 到 GB2025 转换
+ */
+int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
+    if (!odid || !gb) return -1;
+    
+    uav_identification_data_init(gb);
+    gb->coord_type = COORD_WGS84;
+    
+    /* ========== 001-唯一产品识别码 ========== */
+    if (odid->BasicIDValid[0]) {
+        // BasicID总是有值的,即使无效也有默认值
+        memcpy(gb->unique_code, odid->BasicID[0].UASID, 20);
+        // 不需要有效性标志,因为这是固定字段
+    }
+    
+    /* ========== 002-实名登记标志 ========== */
+    if (odid->OperatorIDValid) {
+        char last_8[9] = {0};
+        size_t actual_len = strlen(odid->OperatorID.OperatorId);
+
+        if (actual_len >= 8) {
+            strcpy(last_8, &odid->OperatorID.OperatorId[actual_len - 8]);
+        }
+        // 当长度<8时,last_8全为0,复制过去就是8个0x00
+        memcpy(gb->register_id, last_8, 8);
+    }
+    
+    /* ========== 003-运行类别 ========== */
+    if (odid->SystemValid) {
+        // 检查枚举值范围
+        if (odid->System.CategoryEU >= 0 && odid->System.CategoryEU < 4) {
+            gb->run_class = (UavRunClass)odid->System.CategoryEU;
+            gb->flag_run_class = true;
+        } else {
+            gb->run_class = UAV_RUN_UNDEFINED;
+            gb->flag_run_class = false;  // 标记为未收到有效值
+        }
+    }
+    
+    /* ========== 004-无人机分类 ========== */
+    if (odid->BasicIDValid[0]) {
+        // 检查UAType是否在有效范围内
+        if (odid->BasicID[0].UAType >= 0 && (UavType)odid->BasicID[0].UAType < 5) {
+            gb->uav_type = (UavType)odid->BasicID[0].UAType;
+        } else {
+            gb->uav_type = UAV_TYPE_RESERVED;  // 设为预留值
+        }
+    }
+    
+    /* ========== 006/008-经纬度处理 ========== */
+    if (odid->LocationValid) {
+        // 检查经纬度是否有效
+        bool lat_valid = (odid->Location.Latitude >= -90 && 
+                          odid->Location.Latitude <= 90 &&
+                          odid->Location.Latitude != 0);  // 0通常是无效值
+        
+        bool lon_valid = (odid->Location.Longitude >= -180 && 
+                          odid->Location.Longitude <= 180 &&
+                          odid->Location.Longitude != 0);
+        
+        if (lat_valid && lon_valid) {
+            gb->uav_lat = odid->Location.Latitude;
+            gb->uav_lon = odid->Location.Longitude;
+            gb->is_uav_pos_valid = true;
+        } else {
+            // 非法经纬度:标记为无效,编码时会自动处理
+            gb->uav_lat = 0;
+            gb->uav_lon = 0;
+            gb->is_uav_pos_valid = false;
+        }
+    }
+    
+    /* ========== 009-航迹角 ========== */
+    if (odid->LocationValid) {
+        // 航迹角有效范围:0-360,且不是无效值361
+        if (odid->Location.Direction >= 0 && 
+            odid->Location.Direction <= 360 && 
+            odid->Location.Direction != INV_DIR) {
+            gb->track_angle = odid->Location.Direction;
+            gb->is_track_angle_valid = true;
+        } else {
+            gb->track_angle = 0;
+            gb->is_track_angle_valid = false;
+        }
+    }
+    
+    /* ========== 010-地速 ========== */
+    if (odid->LocationValid) {
+        // 地速有效范围:0-254.25,且不是无效值255
+        if (odid->Location.SpeedHorizontal >= 0 && 
+            odid->Location.SpeedHorizontal <= MAX_SPEED_H &&
+            odid->Location.SpeedHorizontal != INV_SPEED_H) {
+            gb->ground_speed = odid->Location.SpeedHorizontal;
+            gb->is_ground_speed_valid = true;
+        } else {
+            gb->ground_speed = 0;
+            gb->is_ground_speed_valid = false;
+        }
+    }
+    
+    /* ========== 012-垂直速度 ========== */
+    if (odid->LocationValid) {
+        // 垂直速度有效范围:-62 到 62,且不是无效值63
+        if (odid->Location.SpeedVertical >= MIN_SPEED_V && 
+            odid->Location.SpeedVertical <= MAX_SPEED_V &&
+            odid->Location.SpeedVertical != INV_SPEED_V) {
+            gb->uav_vert_speed = odid->Location.SpeedVertical;
+            gb->is_vert_speed_valid = true;
+            gb->flag_vert_speed = true;
+        } else {
+            gb->uav_vert_speed = 0;
+            gb->is_vert_speed_valid = false;
+            gb->flag_vert_speed = false;  // 标记为未收到
+        }
+    }
+    
+    /* ========== 高度类处理(013/014/007/011) ========== */
+    if (odid->LocationValid) {
+        // 大地高度
+        if (odid->Location.AltitudeGeo > MIN_ALT && 
+            odid->Location.AltitudeGeo <= MAX_ALT) {
+            gb->uav_geo_alt = odid->Location.AltitudeGeo;
+            gb->is_uav_geo_alt_valid = true;
+        } else {
+            gb->uav_geo_alt = 0;
+            gb->is_uav_geo_alt_valid = false;
+        }
+        
+        // 气压高度
+        if (odid->Location.AltitudeBaro > MIN_ALT && 
+            odid->Location.AltitudeBaro <= MAX_ALT) {
+            gb->uav_press_alt = odid->Location.AltitudeBaro;
+            gb->is_press_alt_valid = true;
+            gb->flag_press_alt = true;
+        } else {
+            gb->uav_press_alt = 0;
+            gb->is_press_alt_valid = false;
+            gb->flag_press_alt = false;
+        }
+        
+        // 相对高度
+        if (odid->Location.Height > MIN_ALT && 
+            odid->Location.Height <= MAX_ALT) {
+            gb->uav_rel_alt = odid->Location.Height;
+            gb->is_rel_alt_valid = true;
+            gb->flag_rel_alt = true;
+        } else {
+            gb->uav_rel_alt = 0;
+            gb->is_rel_alt_valid = false;
+            gb->flag_rel_alt = false;
+        }
+    }
+    
+    /* ========== 015-运行状态 ========== */
+    if (odid->LocationValid) {
+        // 检查状态值范围
+        if (odid->Location.Status >= 0 && odid->Location.Status < 6) {
+            gb->run_state = (UavRunState)odid->Location.Status;
+        } else {
+            gb->run_state = UAV_STATE_UNREPORTED;
+        }
+    }
+    
+    /* ========== 精度枚举值处理 ========== */
+    if (odid->LocationValid) {
+        // 水平精度(0-15有效)
+        gb->hori_accuracy = (odid->Location.HorizAccuracy >= 0 && odid->Location.HorizAccuracy <= 12) ? 
+                             (UavHorizontalAccuracy_t)odid->Location.HorizAccuracy : UAV_HOR_ACC_UNKNOWN;
+        
+        // 垂直精度(0-6有效,7-15预留)
+        gb->vert_accuracy = (odid->Location.VertAccuracy >=0 && odid->Location.VertAccuracy <= 6) ? 
+                             (UavVerticalAccuracy_t)odid->Location.VertAccuracy : UAV_VER_ACC_UNKNOWN;
+        
+        // 速度精度(0-4有效,5-15预留)
+        gb->speed_accuracy = (odid->Location.SpeedAccuracy >=0 && odid->Location.SpeedAccuracy <= 4) ? 
+                              (UAVSpeedAccuracy_t)odid->Location.SpeedAccuracy : UAV_SPEED_ACC_UNKNOWN;
+        
+        // 时间戳精度(0-8都有效)
+        gb->time_accuracy = (odid->Location.TSAccuracy >= 0 && odid->Location.TSAccuracy <= 8)?
+                                (UavTimestampAccuracy_t)odid->Location.TSAccuracy : UAV_TIME_ACC_UNKNOWN;
+    }
+    
+    /* ========== 020-时间戳 ========== */
+    if (odid->LocationValid) {
+        if (odid->Location.TimeStamp != INV_TIMESTAMP && 
+            odid->Location.TimeStamp <= MAX_TIMESTAMP) {
+            gb->timestamp = (uint64_t)(odid->Location.TimeStamp * 1000);
+            gb->is_timestamp_valid = true;
+        } else {
+            gb->timestamp = 0;
+            gb->is_timestamp_valid = false;
+        }
+    }
+    
+    /* ========== 遥控站位置 ========== */
+    if (odid->SystemValid) {
+        // 检查遥控站经纬度
+        bool sta_lat_valid = (odid->System.OperatorLatitude >= -90 && 
+                               odid->System.OperatorLatitude <= 90);
+        bool sta_lon_valid = (odid->System.OperatorLongitude >= -180 && 
+                               odid->System.OperatorLongitude <= 180);
+        
+        if (sta_lat_valid && sta_lon_valid && 
+            (odid->System.OperatorLatitude != 0 || odid->System.OperatorLongitude != 0)) {
+            gb->station_lat = odid->System.OperatorLatitude;
+            gb->station_lon = odid->System.OperatorLongitude;
+            gb->is_station_pos_valid = true;
+        } else {
+            gb->station_lat = 0;
+            gb->station_lon = 0;
+            gb->is_station_pos_valid = false;
+        }
+        
+        // 遥控站高度
+        if (odid->System.OperatorAltitudeGeo > MIN_ALT && 
+            odid->System.OperatorAltitudeGeo <= MAX_ALT) {
+            gb->station_geo_alt = odid->System.OperatorAltitudeGeo;
+            gb->is_station_alt_valid = true;
+        } else {
+            gb->station_geo_alt = 0;
+            gb->is_station_alt_valid = false;
+        }
+    }
+    
+    return 0;
+}
 /*
 /*
   check parsing of UAS_data, this checks ranges of values to ensure we
   check parsing of UAS_data, this checks ranges of values to ensure we
   will produce a valid pack
   will produce a valid pack
   returns nullptr on no error, or a string error
   returns nullptr on no error, or a string error
+  检查UAS数据的解析情况,这会检查值的范围以确保我们能生成一个有效的数据包。
+  无错误时返回空指针,否则返回字符串形式的错误信息。
  */
  */
 static const char *check_parse(void)
 static const char *check_parse(void)
 {
 {
     String ret = "";
     String ret = "";
-
+    
+    if(g.protocol  == PROTOCOL_EU)
     {
     {
-        ODID_Location_encoded encoded {};
-        if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
-            ret += "LOC ";
+        {
+            ODID_Location_encoded encoded {};
+            if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
+                ret += "LOC ";
+            }
         }
         }
-    }
-    {
-        ODID_System_encoded encoded {};
-        if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
-            ret += "SYS ";
+        {
+            ODID_System_encoded encoded {};
+            if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
+                ret += "SYS ";
+            }
         }
         }
-    }
-    {
-        ODID_BasicID_encoded encoded {};
-        if (UAS_data.BasicIDValid[0] == 1) {
-            if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
-                ret += "ID_1 ";
+        {
+            ODID_BasicID_encoded encoded {};
+            if (UAS_data.BasicIDValid[0] == 1) {
+                if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
+                    ret += "ID_1 ";
+                }
+            }
+            memset(&encoded, 0, sizeof(encoded));
+            if (UAS_data.BasicIDValid[1] == 1) {
+                if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
+                    ret += "ID_2 ";
+                }
             }
             }
         }
         }
-        memset(&encoded, 0, sizeof(encoded));
-        if (UAS_data.BasicIDValid[1] == 1) {
-            if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
-                ret += "ID_2 ";
+        {
+            ODID_SelfID_encoded encoded {};
+            if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
+                ret += "SELF_ID ";
             }
             }
         }
         }
-    }
+        {
+            ODID_OperatorID_encoded encoded {};
+            if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
+                ret += "OP_ID ";
+            }
+        }
+       
+    }else if(g.protocol  == PROTOCOL_CN2023) // 国标状态处理
     {
     {
-        ODID_SelfID_encoded encoded {};
-        if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
-            ret += "SELF_ID ";
+        {
+            CNDID_Location_encoded encoded {};
+            if (encodeCNLocationMessage(&encoded, &CN_UAS_data.Location) != CNDID_SUCCESS) {
+                ret += "LOC ";
+            }
+        }
+        {
+            CNDID_System_encoded encoded {};
+            if (encodeCNSystemMessage(&encoded, &CN_UAS_data.System) != CNDID_SUCCESS) {
+                ret += "SYS ";
+            }
+        }
+        {
+            CNDID_BasicID_encoded encoded {};
+            if (CN_UAS_data.BasicIDValid[0] == 1) {
+                if (encodeCNBasicIDMessage(&encoded, &CN_UAS_data.BasicID[0]) != CNDID_SUCCESS) {
+                    ret += "ID_1 ";
+                }
+            }
+            memset(&encoded, 0, sizeof(encoded));
+            if (CN_UAS_data.BasicIDValid[1] == 1) {
+                if (encodeCNBasicIDMessage(&encoded, &CN_UAS_data.BasicID[1]) != CNDID_SUCCESS) {
+                    ret += "ID_2 ";
+                }
+            }
+        }
+        {
+            CNDID_SelfID_encoded encoded {};
+            if (encodeCNSelfIDMessage(&encoded, &CN_UAS_data.SelfID) != CNDID_SUCCESS) {
+                ret += "SELF_ID ";
+            }
         }
         }
+       
     }
     }
+    else if(g.protocol == PROTOCOL_GB2025)
     {
     {
-        ODID_OperatorID_encoded encoded {};
-        if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
-            ret += "OP_ID ";
+        {
+            CNDID_Location_encoded encoded {};
+            if (encodeCNLocationMessage(&encoded, &CN_UAS_data.Location) != CNDID_SUCCESS) {
+                ret += "LOC ";
+            }
+        }
+        {
+            CNDID_System_encoded encoded {};
+            if (encodeCNSystemMessage(&encoded, &CN_UAS_data.System) != CNDID_SUCCESS) {
+                ret += "SYS ";
+            }
+        }
+        {
+            CNDID_BasicID_encoded encoded {};
+            if (CN_UAS_data.BasicIDValid[0] == 1) {
+                if (encodeCNBasicIDMessage(&encoded, &CN_UAS_data.BasicID[0]) != CNDID_SUCCESS) {
+                    ret += "ID_1 ";
+                }
+            }
+            memset(&encoded, 0, sizeof(encoded));
+            if (CN_UAS_data.BasicIDValid[1] == 1) {
+                if (encodeCNBasicIDMessage(&encoded, &CN_UAS_data.BasicID[1]) != CNDID_SUCCESS) {
+                    ret += "ID_2 ";
+                }
+            }
+        }
+        {
+            CNDID_SelfID_encoded encoded {};
+            if (encodeCNSelfIDMessage(&encoded, &CN_UAS_data.SelfID) != CNDID_SUCCESS) {
+                ret += "SELF_ID ";
+            }
         }
         }
     }
     }
     if (ret.length() > 0) {
     if (ret.length() > 0) {
         // if all errors would occur in this function, it will fit in
         // if all errors would occur in this function, it will fit in
         // 50 chars that is also the max for the arm status message
         // 50 chars that is also the max for the arm status message
+        // 如果所有错误都发生在这个函数中,它会刚好容纳
+        // 50个字符,这也是臂状态消息的最大长度
         static char return_string[50];
         static char return_string[50];
         memset(return_string, 0, sizeof(return_string));
         memset(return_string, 0, sizeof(return_string));
         snprintf(return_string, sizeof(return_string)-1, "bad %s data", ret.c_str());
         snprintf(return_string, sizeof(return_string)-1, "bad %s data", ret.c_str());
+        Serial.printf("error %s\n", return_string);
         return return_string;
         return return_string;
     }
     }
     return nullptr;
     return nullptr;
@@ -198,16 +559,17 @@ static const char *check_parse(void)
 /*
 /*
   fill in UAS_data from MAVLink packets
   fill in UAS_data from MAVLink packets
  */
  */
-static void set_data(Transport &t)
-{
-    const auto &operator_id = t.get_operator_id();
+static void set_data(Transport &t) // 两种类型都获取 广播按照需要的进行广播
+{   // 从mavlink获取数据包
+    const auto &operator_id = t.get_operator_id(); 
     const auto &basic_id = t.get_basic_id();
     const auto &basic_id = t.get_basic_id();
     const auto &system = t.get_system();
     const auto &system = t.get_system();
     const auto &self_id = t.get_self_id();
     const auto &self_id = t.get_self_id();
     const auto &location = t.get_location();
     const auto &location = t.get_location();
 
 
     odid_initUasData(&UAS_data);
     odid_initUasData(&UAS_data);
-
+    cndid_initUasData(&CN_UAS_data); // 复位UAS数据结构体
+    uav_identification_data_init(&GB2025_UAS_data);
     /*
     /*
       if we don't have BasicID info from parameters and we have it
       if we don't have BasicID info from parameters and we have it
       from the DroneCAN or MAVLink transport then copy it to the
       from the DroneCAN or MAVLink transport then copy it to the
@@ -230,23 +592,39 @@ static void set_data(Transport &t)
             ODID_COPY_STR(uas_id, basic_id.uas_id);
             ODID_COPY_STR(uas_id, basic_id.uas_id);
             g.set_by_name_string("UAS_ID", uas_id);
             g.set_by_name_string("UAS_ID", uas_id);
         }
         }
-    }
-
+    } // 是否配置了保存基本ID的选项 == 存到eeprom 可以用国际的协议存储BASE ID
+    
     // BasicID
     // BasicID
     if (g.have_basic_id_info() && !(g.options & OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS)) {
     if (g.have_basic_id_info() && !(g.options & OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS)) {
         // from parameters
         // from parameters
         UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
         UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
         UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
         UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
+        // 国际国标 的 基础ID参数是一样的 拷贝
+        CN_UAS_data.BasicID[0].UAType = (CNDID_UAType_t)g.ua_type;
+        CN_UAS_data.BasicID[0].IDType = (CNDID_IDType_t)g.id_type;
+
         ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
         ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
+        ODID_COPY_STR(CN_UAS_data.BasicID[0].UASID, g.uas_id); // 拷贝
+
         UAS_data.BasicIDValid[0] = 1;
         UAS_data.BasicIDValid[0] = 1;
+        CN_UAS_data.BasicIDValid[0] = 1; // 拷贝
 
 
         // BasicID 2
         // BasicID 2
         if (g.have_basic_id_2_info()) {
         if (g.have_basic_id_2_info()) {
             // from parameters
             // from parameters
             UAS_data.BasicID[1].UAType = (ODID_uatype_t)g.ua_type_2;
             UAS_data.BasicID[1].UAType = (ODID_uatype_t)g.ua_type_2;
             UAS_data.BasicID[1].IDType = (ODID_idtype_t)g.id_type_2;
             UAS_data.BasicID[1].IDType = (ODID_idtype_t)g.id_type_2;
+            
+            // 国际国标 的 基础ID参数是一样的 拷贝
+            CN_UAS_data.BasicID[1].UAType = (CNDID_UAType_t)g.ua_type;
+            CN_UAS_data.BasicID[1].IDType = (CNDID_IDType_t)g.id_type;
+
             ODID_COPY_STR(UAS_data.BasicID[1].UASID, g.uas_id_2);
             ODID_COPY_STR(UAS_data.BasicID[1].UASID, g.uas_id_2);
+            ODID_COPY_STR(CN_UAS_data.BasicID[1].UASID, g.uas_id_2); // 拷贝
+
+
             UAS_data.BasicIDValid[1] = 1;
             UAS_data.BasicIDValid[1] = 1;
+            CN_UAS_data.BasicIDValid[1] = 1; // 拷贝
         } else if (strcmp((const char*)g.uas_id, (const char*)basic_id.uas_id) != 0) {
         } else if (strcmp((const char*)g.uas_id, (const char*)basic_id.uas_id) != 0) {
             /*
             /*
               no BasicID 2 in the parameters, if one is provided on MAVLink
               no BasicID 2 in the parameters, if one is provided on MAVLink
@@ -259,6 +637,11 @@ static void set_data(Transport &t)
                 UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
                 UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
                 ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
                 ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
                 UAS_data.BasicIDValid[1] = 1;
                 UAS_data.BasicIDValid[1] = 1;
+                // 拷贝
+                CN_UAS_data.BasicID[1].UAType = (CNDID_UAType_t)basic_id.ua_type;
+                CN_UAS_data.BasicID[1].IDType = (CNDID_IDType_t)basic_id.id_type;
+                ODID_COPY_STR(CN_UAS_data.BasicID[1].UASID, basic_id.uas_id);
+                CN_UAS_data.BasicIDValid[1] = 1;
             }
             }
         }
         }
     }
     }
@@ -272,28 +655,45 @@ static void set_data(Transport &t)
                 UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
                 UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
                 ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
                 ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
                 UAS_data.BasicIDValid[1] = 1;
                 UAS_data.BasicIDValid[1] = 1;
+
+                 // 拷贝
+                CN_UAS_data.BasicID[1].UAType = (CNDID_UAType_t)basic_id.ua_type;
+                CN_UAS_data.BasicID[1].IDType = (CNDID_IDType_t)basic_id.id_type;
+                ODID_COPY_STR(CN_UAS_data.BasicID[1].UASID, basic_id.uas_id);
+                CN_UAS_data.BasicIDValid[1] = 1;
             } else {
             } else {
                 UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
                 UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
                 UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
                 UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
                 ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
                 ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
                 UAS_data.BasicIDValid[0] = 1;
                 UAS_data.BasicIDValid[0] = 1;
+                // 拷贝
+                CN_UAS_data.BasicID[0].UAType = (CNDID_UAType_t)basic_id.ua_type;
+                CN_UAS_data.BasicID[0].IDType = (CNDID_IDType_t)basic_id.id_type;
+                ODID_COPY_STR(CN_UAS_data.BasicID[0].UASID, basic_id.uas_id); // 拷贝
+                CN_UAS_data.BasicIDValid[0] = 1; // 拷贝
             }
             }
         }
         }
     }
     }
-
+    
     // OperatorID
     // OperatorID
     if (strlen(operator_id.operator_id) > 0) {
     if (strlen(operator_id.operator_id) > 0) {
         UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
         UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
         ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
         ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
         UAS_data.OperatorIDValid = 1;
         UAS_data.OperatorIDValid = 1;
     }
     }
-
+    // 
     // SelfID
     // SelfID
     if (strlen(self_id.description) > 0) {
     if (strlen(self_id.description) > 0) {
         UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
         UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
         ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
         ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
         UAS_data.SelfIDValid = 1;
         UAS_data.SelfIDValid = 1;
     }
     }
+    // SelfID CN
+    if (strlen(self_id.description) > 0) {
+        CN_UAS_data.SelfID.DescType= (CNDID_DescType_t)self_id.description_type;
+        ODID_COPY_STR(CN_UAS_data.SelfID.Desc, self_id.description); // 拷贝函数通用
+        CN_UAS_data.SelfIDValid = 1;
+    }
 
 
     // System
     // System
     if (system.timestamp != 0) {
     if (system.timestamp != 0) {
@@ -311,7 +711,25 @@ static void set_data(Transport &t)
         UAS_data.System.Timestamp = system.timestamp;
         UAS_data.System.Timestamp = system.timestamp;
         UAS_data.SystemValid = 1;
         UAS_data.SystemValid = 1;
     }
     }
+    // System CN
+    if (system.timestamp != 0) {
 
 
+        CN_UAS_data.System.Coord_Type = (CNDID_CoordType_t)CN_COORD_TYPE; // 坐标系建议写死
+        CN_UAS_data.System.OperatorLocationType = (CNDID_operator_location_type_t)system.operator_location_type;
+        CN_UAS_data.System.Classification_Type = (CNDID_classification_type_t)system.classification_type;
+        CN_UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
+        CN_UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
+        CN_UAS_data.System.AreaCount = system.area_count;
+        CN_UAS_data.System.AreaRadius = system.area_radius;
+        CN_UAS_data.System.AreaCeiling = system.area_ceiling;
+        CN_UAS_data.System.AreaFloor = system.area_floor;
+        CN_UAS_data.System.CategoryCN = (CNDID_category_CN_t)system.category_eu; // 右边是mvlink自动生成的结构体成员不能更改
+        CN_UAS_data.System.ClassCN = (CNDID_class_CN_t)system.class_eu; // 右边是mvlink自动生成的结构体成员不能更改 
+
+        CN_UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
+        CN_UAS_data.System.Timestamp = system.timestamp;
+        CN_UAS_data.SystemValid = 1;
+    }
     // Location
     // Location
     if (location.timestamp != 0) {
     if (location.timestamp != 0) {
         UAS_data.Location.Status = (ODID_status_t)location.status;
         UAS_data.Location.Status = (ODID_status_t)location.status;
@@ -333,13 +751,61 @@ static void set_data(Transport &t)
         UAS_data.LocationValid = 1;
         UAS_data.LocationValid = 1;
     }
     }
 
 
-    const char *reason = check_parse();
-    t.arm_status_check(reason);
-    t.set_parse_fail(reason);
+       // Location CN
+    if (location.timestamp != 0) {
+        CN_UAS_data.Location.Status = (CNDID_Status_t)location.status;
+        CN_UAS_data.Location.Direction = location.direction*0.01;
+        CN_UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
+        CN_UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
+        CN_UAS_data.Location.Latitude = location.latitude*1.0e-7;
+        CN_UAS_data.Location.Longitude = location.longitude*1.0e-7;
+        CN_UAS_data.Location.AltitudeBaro = location.altitude_barometric;
+        CN_UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
+        CN_UAS_data.Location.HeightType = (CNDID_HeightReference_t)location.height_reference;
+        CN_UAS_data.Location.Height = location.height;
+        CN_UAS_data.Location.HorizAccuracy = (CNDID_HorizontalAccuracy_t)location.horizontal_accuracy;
+        CN_UAS_data.Location.VertAccuracy = (CNDID_VerticalAccuracy_t)location.vertical_accuracy;
+        CN_UAS_data.Location.BaroAccuracy = (CNDID_VerticalAccuracy_t)location.barometer_accuracy;
+        CN_UAS_data.Location.SpeedAccuracy = (CNDID_SpeedAccuracy_t)location.speed_accuracy;
+        CN_UAS_data.Location.TSAccuracy = (CNDID_TimeStampAccuracy_t)location.timestamp_accuracy;
+        CN_UAS_data.Location.TimeStamp = location.timestamp;
+        CN_UAS_data.LocationValid = 1;
+    }
+   // GB2025 数据转换 
+   odid_to_gb2025_safe(&UAS_data, &GB2025_UAS_data);
+    // memcpy(GB2025_UAS_data.unique_code, basic_id.uas_id, 20);
+    // memcpy(GB2025_UAS_data.register_id, operator_id.operator_id, 8); // 从操作员ID里复用
+    // GB2025_UAS_data.uav_type = basic_id.ua_type;
+    // GB2025_UAS_data.run_class = system.category_eu;
+    // GB2025_UAS_data.station_type = system.operator_location_type;
+    // GB2025_UAS_data.station_lat = system.operator_latitude * 1.0e-7;
+    // GB2025_UAS_data.station_lon = system.operator_longitude * 1.0e-7;
+    // GB2025_UAS_data.station_geo_alt = system.operator_altitude_geo;
+
+    // GB2025_UAS_data.uav_lat = location.latitude*1.0e-7;
+    // GB2025_UAS_data.uav_lon =  location.longitude*1.0e-7;
+    // GB2025_UAS_data.track_angle = location.direction*0.01;
+    // GB2025_UAS_data.ground_speed = location.speed_horizontal*0.01;
+    // GB2025_UAS_data.uav_rel_alt = location.height_reference;
+    // GB2025_UAS_data.uav_vert_speed = location.speed_vertical*0.01;
+    // GB2025_UAS_data.uav_geo_alt = location.altitude_geodetic;
+    // GB2025_UAS_data.uav_press_alt = location.altitude_barometric;
+
+    // GB2025_UAS_data.run_state = location.status;
+    // GB2025_UAS_datacoord_type = COORD_WGS84;
+    // GB2025_UAS_data.hori_accuracy = location.horizontal_accuracy;
+    // GB2025_UAS_data.vert_accuracy = location.vertical_accuracy;
+    // GB2025_UAS_data.speed_accuracy = location.speed_accuracy;
+    // GB2025_UAS_data.timestamp = (uint64_t)(odid->Location.TimeStamp * 1000);;
+    // GB2025_UAS_data.time_accuracy = location.timestamp_accuracy;
+
+    const char *reason = check_parse(); // 内部以区分国标 国际
+    t.arm_status_check(reason);         // 内部以区分国标 国际
+    t.set_parse_fail(reason);           // 设置错误原因 
 
 
     arm_check_ok = (reason==nullptr);
     arm_check_ok = (reason==nullptr);
-
-    if (g.options & OPTIONS_FORCE_ARM_OK) {
+    
+    if (g.options & OPTIONS_FORCE_ARM_OK) { // 设置强制绿灯?
         arm_check_ok = true;
         arm_check_ok = true;
     }
     }
 
 
@@ -358,19 +824,20 @@ static uint8_t loop_counter = 0;
 void loop()
 void loop()
 {
 {
 #if AP_MAVLINK_ENABLED
 #if AP_MAVLINK_ENABLED
-    mavlink1.update();
-    mavlink2.update();
+    mavlink1.update(); // mavlink实际使用该串口
+    mavlink2.update(); 
 #endif
 #endif
 #if AP_DRONECAN_ENABLED
 #if AP_DRONECAN_ENABLED
-    dronecan.update();
+    dronecan.update(); // 开启了drone can 
 #endif
 #endif
 
 
     const uint32_t now_ms = millis();
     const uint32_t now_ms = millis();
 
 
     // the transports have common static data, so we can just use the
     // the transports have common static data, so we can just use the
     // first for status
     // first for status
+    // 这些传输工具具有共同的静态数据,所以我们只需使用第一个来获取状态
 #if AP_MAVLINK_ENABLED
 #if AP_MAVLINK_ENABLED
-    auto &transport = mavlink1;
+    auto &transport = mavlink1; // 默认使用串口接收 mavlink数据
 #elif AP_DRONECAN_ENABLED
 #elif AP_DRONECAN_ENABLED
     auto &transport = dronecan;
     auto &transport = dronecan;
 #else
 #else
@@ -378,79 +845,129 @@ void loop()
 #endif
 #endif
 
 
     bool have_location = false;
     bool have_location = false;
+    // - last_location_ms:最后一次收到有效位置数据的时间戳(毫秒)
+    // - last_system_ms:最后一次收到飞控系统消息的时间戳(毫秒)
     const uint32_t last_location_ms = transport.get_last_location_ms();
     const uint32_t last_location_ms = transport.get_last_location_ms();
     const uint32_t last_system_ms = transport.get_last_system_ms();
     const uint32_t last_system_ms = transport.get_last_system_ms();
 
 
     led.update();
     led.update();
 
 
-    status_reason = "";
+    status_reason = ""; //  初始化故障原因描述(默认空)
 
 
     if (last_location_ms == 0 ||
     if (last_location_ms == 0 ||
-        now_ms - last_location_ms > 5000) {
-        UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
+        now_ms - last_location_ms > 5000) { 
+        // 判定条件1:位置数据异常(超时/未收到)
+        // - last_location_ms == 0:从未收到过位置数据
+        // - 现在时间 - 最后一次位置时间 > 5000ms:位置数据超时5秒
+        UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; // 相同的故障ID 4 // web页面可视
+        CN_UAS_data.Location.Status = CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE; 
     }
     }
 
 
     if (last_system_ms == 0 ||
     if (last_system_ms == 0 ||
-        now_ms - last_system_ms > 5000) {
+        now_ms - last_system_ms > 5000) { 
+        //判定条件2:系统通信异常(飞控消息超时/未收到)
+        // - last_system_ms == 0:从未收到过飞控系统消息
+        // - 超时5秒:飞控和RemoteID模块断连超过5秒
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
+        CN_UAS_data.Location.Status = CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
     }
     }
-
+    //  判定条件3:数据解析失败(飞控消息格式错误/解析出错)
     if (transport.get_parse_fail() != nullptr) {
     if (transport.get_parse_fail() != nullptr) {
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
-        status_reason = String(transport.get_parse_fail());
-    }
+        CN_UAS_data.Location.Status = CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
+        // 记录解析失败的具体原因(如“GPS数据格式错误”)
+        status_reason = String(transport.get_parse_fail()); // 状态原因上传web页面
+    } // 状态原因还是沿用opendroneid 的 国标没有要求反馈解析失败原因
 
 
     // web update has to happen after we update Status above
     // web update has to happen after we update Status above
+    // 网络更新必须在我们更新上述状态之后进行
     if (g.webserver_enable) {
     if (g.webserver_enable) {
         webif.update();
         webif.update();
-    }
-
-    if (g.bcast_powerup) {
+    } 
+    if (g.bcast_powerup) { // true 上电即广播"模式
         // if we are broadcasting on powerup we always mark location valid
         // if we are broadcasting on powerup we always mark location valid
-        // so the location with default data is sent
+        // so the location with default data is sent 
+        // 如果我们在启动时进行广播,我们总是会标记位置有效
+        // 这样就会发送带有默认数据的位置信息
         if (!UAS_data.LocationValid) {
         if (!UAS_data.LocationValid) {
             UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
             UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
             UAS_data.LocationValid = 1;
             UAS_data.LocationValid = 1;
         }
         }
     } else {
     } else {
         // only broadcast if we have received a location at least once
         // only broadcast if we have received a location at least once
+        // 仅在我们至少接收过一次位置信息时才进行广播
         if (last_location_ms == 0) {
         if (last_location_ms == 0) {
-            delay(1);
+            delay(1); // 没接收到位置信息直接退出该次loop 执行完毕后还会再次进入
             return;
             return;
         }
         }
     }
     }
 
 
     set_data(transport);
     set_data(transport);
 
 
-    static uint32_t last_update_wifi_nan_ms;
+    // Serial.printf("/***********************************/\n");
+    // Serial.printf("ID %s %s\n",UAS_data.BasicID[0].UASID, UAS_data.BasicID[1].UASID);
+    // Serial.printf("OP ID %s\n",UAS_data.OperatorID.OperatorId);
+    // Serial.printf("sys timestamp %d %d\n",UAS_data.System.Timestamp, UAS_data.System.OperatorLocationType);
+    // Serial.printf("loc timestamp %d %d\n",UAS_data.Location.TimeStamp, UAS_data.Location);
+    // Serial.printf("/***********************************/\n");
+
+    static uint32_t last_update_wifi_nan_ms; // wifi_nan_rate发送频率HZ 达到对应的时间了就启动RemoteID WIFI_NAN发送
     if (g.wifi_nan_rate > 0 &&
     if (g.wifi_nan_rate > 0 &&
         now_ms - last_update_wifi_nan_ms > 1000/g.wifi_nan_rate) {
         now_ms - last_update_wifi_nan_ms > 1000/g.wifi_nan_rate) {
         last_update_wifi_nan_ms = now_ms;
         last_update_wifi_nan_ms = now_ms;
-        wifi.transmit_nan(UAS_data);
+        if(g.protocol == PROTOCOL_EU)
+            wifi.transmit_nan(UAS_data);
+        else if(g.protocol == PROTOCOL_CN2023)
+            wifi.transmit_cn_nan(CN_UAS_data); // 这个可要可不要 国标只要求发送wifi beacon 信标帧
+        else if(g.protocol == PROTOCOL_GB2025)
+            wifi.transmit_GB2025_nan(GB2025_UAS_data);
+        // Serial.printf("update_wifi_nan\n");
     }
     }
 
 
-    static uint32_t last_update_wifi_beacon_ms;
+    static uint32_t last_update_wifi_beacon_ms; // wifi_beacon_rate发送频率HZ 达到对应的时间了就启动RemoteID WIFI_BEACON发送
     if (g.wifi_beacon_rate > 0 &&
     if (g.wifi_beacon_rate > 0 &&
         now_ms - last_update_wifi_beacon_ms > 1000/g.wifi_beacon_rate) {
         now_ms - last_update_wifi_beacon_ms > 1000/g.wifi_beacon_rate) {
         last_update_wifi_beacon_ms = now_ms;
         last_update_wifi_beacon_ms = now_ms;
-        wifi.transmit_beacon(UAS_data);
+        if(g.protocol == PROTOCOL_EU)
+            wifi.transmit_beacon(UAS_data);
+        else if(g.protocol == PROTOCOL_CN2023)
+            wifi.transmit_cn_beacon(CN_UAS_data);
+        else if(g.protocol == PROTOCOL_GB2025)
+            wifi.transmit_GB2025_beacon(GB2025_UAS_data);
+        // Serial.printf("update_wifi_beacon\n");
     }
     }
 
 
-    static uint32_t last_update_bt5_ms;
+    static uint32_t last_update_bt5_ms; // BLE 远端蓝牙发送频率 bt5_rate 达到对应的时间了就启动RemoteID BLE5发送
     if (g.bt5_rate > 0 &&
     if (g.bt5_rate > 0 &&
         now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
         now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
         last_update_bt5_ms = now_ms;
         last_update_bt5_ms = now_ms;
-        ble.transmit_longrange(UAS_data);
+        if(g.protocol == PROTOCOL_EU)
+            ble.transmit_longrange(UAS_data);
+        else if(g.protocol == PROTOCOL_CN2023)
+            ble.transmit_cn_longrange(CN_UAS_data);
+        else if(g.protocol == PROTOCOL_GB2025)
+            ble.transmit_GB2025_longrange(GB2025_UAS_data); // 国标只要求bt5
+        // Serial.printf("update_bt5\n");
     }
     }
 
 
-    static uint32_t last_update_bt4_ms;
-    int bt4_states = UAS_data.BasicIDValid[1] ? 7 : 6;
+    static uint32_t last_update_bt4_ms; // BLE 近端蓝牙发送频率 bt4_rate 达到对应的时间了就启动RemoteID BLE4发送
+    int bt4_states = 0;
+    if(g.protocol == PROTOCOL_EU)
+        bt4_states = UAS_data.BasicIDValid[1] ? 7 : 6;
+    else if(g.protocol == PROTOCOL_CN2023)
+        bt4_states = CN_UAS_data.BasicIDValid[1] ? 7 : 6; // CN 最多只发6条其实 为了间隔上同步
+    // Serial.printf("bt4 state %d\n", bt4_states);   
     if (g.bt4_rate > 0 &&
     if (g.bt4_rate > 0 &&
         now_ms - last_update_bt4_ms > (1000.0f/bt4_states)/g.bt4_rate) {
         now_ms - last_update_bt4_ms > (1000.0f/bt4_states)/g.bt4_rate) {
         last_update_bt4_ms = now_ms;
         last_update_bt4_ms = now_ms;
-        ble.transmit_legacy(UAS_data);
-    }
 
 
-    // sleep for a bit for power saving
+        if(g.protocol == PROTOCOL_EU)
+            ble.transmit_legacy(UAS_data);
+        else if(g.protocol  == PROTOCOL_CN2023)
+            ble.transmit_cn_legacy(CN_UAS_data);
+        // Serial.printf("update_bt4\n");   
+    }
+   
+    // sleep for a bit for power saving 节能 
     delay(1);
     delay(1);
 }
 }

+ 167 - 11
RemoteIDModule/WiFi_TX.cpp

@@ -23,27 +23,57 @@ bool WiFi_TX::init(void)
 
 
     mac_addr[0] |= 0x02;  // set MAC local bit
     mac_addr[0] |= 0x02;  // set MAC local bit
     mac_addr[0] &= 0xFE;  // unset MAC multicast bit
     mac_addr[0] &= 0xFE;  // unset MAC multicast bit
-
+    Serial.printf("Setting MAC: %02X:%02X:%02X:%02X:%02X:%02X\n",
+                mac_addr[0], mac_addr[1], mac_addr[2],
+                mac_addr[3], mac_addr[4], mac_addr[5]);
     //set MAC address
     //set MAC address
     esp_base_mac_addr_set(mac_addr);
     esp_base_mac_addr_set(mac_addr);
-
+    // 2.4Gwifi信道默认是信道6   5.8GHZ应使用信道149
     if (g.webserver_enable == 0) {
     if (g.webserver_enable == 0) {
         WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 0); //make it visible and allow no connection
         WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 0); //make it visible and allow no connection
     } else {
     } else {
         WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 1); //make it visible and allow only 1 connection
         WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 1); //make it visible and allow only 1 connection
     }
     }
 
 
-    if (esp_wifi_set_bandwidth(WIFI_IF_AP, WIFI_BW_HT20) != ESP_OK) {
+    if (esp_wifi_set_bandwidth(WIFI_IF_AP, WIFI_BW_HT20) != ESP_OK) { // 国标要求 20MHZ带宽
         return false;
         return false;
     }
     }
 
 
     memcpy(WiFi_mac_addr,mac_addr,6); //use generated random MAC address for OpenDroneID messages
     memcpy(WiFi_mac_addr,mac_addr,6); //use generated random MAC address for OpenDroneID messages
 
 
-    esp_wifi_set_max_tx_power(dBm_to_tx_power(g.wifi_power));
+    esp_wifi_set_max_tx_power(dBm_to_tx_power(g.wifi_power)); // 按国标要求来说设置不同的功率 
+
+    return true;
+}
+
+// 发送中国国标的数据包
+bool WiFi_TX::transmit_cn_nan(CNDID_UAS_Data &UAS_data)
+{
+    init();
+
+    uint8_t buffer[1024] {};
+
+    int length;
+
+     if ((length = cndid_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
+                  buffer,sizeof(buffer))) > 0) {
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
+    }
+
+    if ((length = cndid_wifi_build_message_pack_nan_action_frame(&UAS_data, (char *)WiFi_mac_addr,
+                  ++send_counter_cn_nan,
+                  buffer,sizeof(buffer))) > 0) {
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
+    }
 
 
     return true;
     return true;
 }
 }
 
 
+// 发送国际标准的数据包
 bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
 bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
 {
 {
     init();
     init();
@@ -51,6 +81,7 @@ bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
     uint8_t buffer[1024] {};
     uint8_t buffer[1024] {};
 
 
     int length;
     int length;
+
     if ((length = odid_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
     if ((length = odid_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
                   buffer,sizeof(buffer))) > 0) {
                   buffer,sizeof(buffer))) > 0) {
         if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
         if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
@@ -69,6 +100,56 @@ bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
     return true;
     return true;
 }
 }
 
 
+bool WiFi_TX::transmit_cn_beacon(CNDID_UAS_Data &UAS_data)
+{
+    init();
+
+    uint8_t buffer[1024] {};
+
+    int length;
+    if ((length = cndid_wifi_build_message_pack_beacon_frame(&UAS_data,(char *)WiFi_mac_addr,
+                   "UAS_ID_OPEN", strlen("UAS_ID_OPEN"), //use dummy SSID, as we only extract payload data
+                  1000/g.wifi_beacon_rate, ++send_counter_cn_beacon, buffer, sizeof(buffer))) > 0) {
+
+        //set the RID IE element
+        uint8_t header_offset = 58; // 固定包头长度
+        vendor_ie_data_t IE_data;
+        IE_data.element_id = 0xDD; // 国标要求
+        // 符合国标
+        IE_data.vendor_oui[0] = 0xFA;
+        IE_data.vendor_oui[1] = 0x0B;
+        IE_data.vendor_oui[2] = 0xBC;
+        IE_data.vendor_oui_type = 0x0D;
+        IE_data.length = length - header_offset + 4; // 添加4作为esp_wifi_set_vendor_ie的定义
+        // 也就是 uoi vender类型是4个字节
+        memcpy(IE_data.payload,&buffer[header_offset],length - header_offset);
+
+        // 所以首先移除旧元素,之后添加新元素
+        if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        //也将有效载荷设置为探测请求,以提高手机上的更新速率
+        //因此,先移除旧元素,之后再添加新元素
+        if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        return true;
+	}
+	else {
+		return false;
+	}
+}
+
 //update the payload of the beacon frames in this function
 //update the payload of the beacon frames in this function
 bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
 bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
 {
 {
@@ -81,18 +162,94 @@ bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
                    "UAS_ID_OPEN", strlen("UAS_ID_OPEN"), //use dummy SSID, as we only extract payload data
                    "UAS_ID_OPEN", strlen("UAS_ID_OPEN"), //use dummy SSID, as we only extract payload data
                   1000/g.wifi_beacon_rate, ++send_counter_beacon, buffer, sizeof(buffer))) > 0) {
                   1000/g.wifi_beacon_rate, ++send_counter_beacon, buffer, sizeof(buffer))) > 0) {
 
 
+        //设置厂商 RID的元素
+        uint8_t header_offset = 58; // 定义IE元素头部偏移(58字节是Beacon帧固定头部长度,跳过头部取核心数据)
+        vendor_ie_data_t IE_data; // 定义厂商IE元素结构体(ESP32 WiFi驱动要求的格式)
+        IE_data.element_id = WIFI_VENDOR_IE_ELEMENT_ID; // 固定值,标识是厂商自定义IE
+        IE_data.vendor_oui[0] = 0xFA; // 设置Open Drone ID标准的厂商OUI(FA:0B:BC是无人机Remote ID的专属OUI)
+        IE_data.vendor_oui[1] = 0x0B;
+        IE_data.vendor_oui[2] = 0xBC;
+        IE_data.vendor_oui_type = 0x0D; // Open Drone ID定义的WiFi IE类型值
+        // // 步骤4:设置IE元素长度(核心Remote ID数据长度 + 4字节ESP32驱动要求的额外长度)
+        IE_data.length = length - header_offset + 4; //add 4 as of definition esp_wifi_set_vendor_ie
+        // 拷贝Remote ID核心数据到IE元素的payload(跳过Beacon帧固定头部)
+        memcpy(IE_data.payload,&buffer[header_offset],length - header_offset);
+        // 删除旧的Beacon帧厂商IE元素(false=禁用)
+        // so first remove old element, add new afterwards
+        if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+        // 添加新的Beacon帧厂商IE元素(true=启用)
+        if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+        // 为Probe Response帧(手机探测WiFi时的响应帧)也添加相同的Remote ID IE元素
+        //set the payload also to probe requests, to increase update rate on mobile phones
+        // so first remove old element, add new afterwards
+        if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
+            return false;
+        }
+
+        return true;
+	}
+	else {
+		return false;
+	}
+}
+bool WiFi_TX::transmit_GB2025_nan(UavIdentificationData &UAS_data)
+{
+    init();
+
+    uint8_t buffer[1024] {};
+
+    int length;
+
+    if ((length = did_GB2025_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
+                  buffer,sizeof(buffer))) > 0) {
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
+    }
+
+    if ((length = did_GB2025_wifi_build_message_pack_nan_action_frame(&UAS_data,(char *)WiFi_mac_addr,
+                  ++send_counter_GB2025_nan,
+                  buffer,sizeof(buffer))) > 0) {
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
+    }
+
+    return true;
+}
+bool WiFi_TX::transmit_GB2025_beacon(UavIdentificationData &UAS_data)
+{
+    init();
+
+    uint8_t buffer[1024] {};
+
+    int length;
+    if ((length = did_GB2025_wifi_build_message_pack_beacon_frame(&UAS_data,(char *)WiFi_mac_addr,
+                   "UAS_ID_OPEN", strlen("UAS_ID_OPEN"), //use dummy SSID, as we only extract payload data
+                  1000/g.wifi_beacon_rate, ++send_counter_GB2025_beacon, buffer, sizeof(buffer))) > 0) {
+
         //set the RID IE element
         //set the RID IE element
-        uint8_t header_offset = 58;
+        uint8_t header_offset = 58; // 固定包头长度
         vendor_ie_data_t IE_data;
         vendor_ie_data_t IE_data;
-        IE_data.element_id = WIFI_VENDOR_IE_ELEMENT_ID;
+        IE_data.element_id = 0xDD; // 国标要求
+        // 符合国标
         IE_data.vendor_oui[0] = 0xFA;
         IE_data.vendor_oui[0] = 0xFA;
         IE_data.vendor_oui[1] = 0x0B;
         IE_data.vendor_oui[1] = 0x0B;
         IE_data.vendor_oui[2] = 0xBC;
         IE_data.vendor_oui[2] = 0xBC;
         IE_data.vendor_oui_type = 0x0D;
         IE_data.vendor_oui_type = 0x0D;
-        IE_data.length = length - header_offset + 4; //add 4 as of definition esp_wifi_set_vendor_ie
+        IE_data.length = length - header_offset + 4; // 添加4作为esp_wifi_set_vendor_ie的定义
+        // 也就是 uoi vender类型是4个字节
         memcpy(IE_data.payload,&buffer[header_offset],length - header_offset);
         memcpy(IE_data.payload,&buffer[header_offset],length - header_offset);
 
 
-        // so first remove old element, add new afterwards
+        // 所以首先移除旧元素,之后添加新元素
         if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
         if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
             return false;
             return false;
         }
         }
@@ -101,8 +258,8 @@ bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
             return false;
             return false;
         }
         }
 
 
-        //set the payload also to probe requests, to increase update rate on mobile phones
-        // so first remove old element, add new afterwards
+        //也将有效载荷设置为探测请求,以提高手机上的更新速率
+        //因此,先移除旧元素,之后再添加新元素
         if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
         if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
             return false;
             return false;
         }
         }
@@ -118,7 +275,6 @@ bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
 	}
 	}
 }
 }
 
 
-
 /*
 /*
   map dBm to a TX power
   map dBm to a TX power
  */
  */

+ 10 - 2
RemoteIDModule/WiFi_TX.h

@@ -5,18 +5,26 @@
 
 
 #include "transmitter.h"
 #include "transmitter.h"
 
 
-class WiFi_TX : public Transmitter {
+class WiFi_TX:public Transmitter {
 public:
 public:
     bool init(void) override;
     bool init(void) override;
+    bool transmit_cn_nan(CNDID_UAS_Data &UAS_data);
+    bool transmit_cn_beacon(CNDID_UAS_Data &UAS_data);
     bool transmit_nan(ODID_UAS_Data &UAS_data);
     bool transmit_nan(ODID_UAS_Data &UAS_data);
     bool transmit_beacon(ODID_UAS_Data &UAS_data);
     bool transmit_beacon(ODID_UAS_Data &UAS_data);
+    bool transmit_GB2025_nan(UavIdentificationData &UAS_data);
+    bool transmit_GB2025_beacon(UavIdentificationData &UAS_data);
 
 
 private:
 private:
     bool initialised;
     bool initialised;
     char ssid[32];
     char ssid[32];
     uint8_t WiFi_mac_addr[6];
     uint8_t WiFi_mac_addr[6];
     size_t ssid_length;
     size_t ssid_length;
-    uint8_t send_counter_nan;
+    uint8_t send_counter_cn_nan; // 发送的中国广播nan计数器
+    uint8_t send_counter_cn_beacon; // 发送的中国广播beacon计数器
+    uint8_t send_counter_nan;  
     uint8_t send_counter_beacon;
     uint8_t send_counter_beacon;
+    uint8_t send_counter_GB2025_nan; // 发送的中国GB2025广播nan计数器
+    uint8_t send_counter_GB2025_beacon; // 发送的中国GB2025广播beacon计数器
     uint8_t dBm_to_tx_power(float dBm) const;
     uint8_t dBm_to_tx_power(float dBm) const;
 };
 };

+ 25 - 5
RemoteIDModule/board_config.h

@@ -1,18 +1,22 @@
 /*
 /*
   board configuration file
   board configuration file
- */
+*/
 
 
 #pragma once
 #pragma once
 
 
+#define GB_UAV_REMOTEID 1
+
 #ifdef BOARD_ESP32S3_DEV
 #ifdef BOARD_ESP32S3_DEV
 #define BOARD_ID 1
 #define BOARD_ID 1
-#define PIN_CAN_TX GPIO_NUM_47
-#define PIN_CAN_RX GPIO_NUM_38
-
+// #define PIN_CAN_TX GPIO_NUM_47
+// #define PIN_CAN_RX GPIO_NUM_38
+#define PIN_CAN_TX GPIO_NUM_5
+#define PIN_CAN_RX GPIO_NUM_4
 #define PIN_UART_TX 18
 #define PIN_UART_TX 18
 #define PIN_UART_RX 17
 #define PIN_UART_RX 17
 
 
-#define WS2812_LED_PIN GPIO_NUM_48
+// #define WS2812_LED_PIN GPIO_NUM_48
+#define WS2812_LED_PIN GPIO_NUM_38
 
 
 #elif defined(BOARD_ESP32C3_DEV)
 #elif defined(BOARD_ESP32C3_DEV)
 #define BOARD_ID 2
 #define BOARD_ID 2
@@ -164,6 +168,22 @@
 #define CAN_TERM_EN  LOW
 #define CAN_TERM_EN  LOW
 #define CAN_APP_NODE_NAME "net.cuav.c-rid"
 #define CAN_APP_NODE_NAME "net.cuav.c-rid"
 
 
+#elif defined(BOARD_VKUAV_RID)
+
+#define BOARD_ID 13
+#define PIN_CAN_TX GPIO_NUM_47
+#define PIN_CAN_RX GPIO_NUM_38
+#define PIN_CAN_nSILENT GPIO_NUM_1
+
+#define PIN_UART_TX 18
+#define PIN_UART_RX 17
+
+#define WS2812_LED_PIN GPIO_NUM_48
+
+#define PIN_CAN_TERM GPIO_NUM_37
+#define CAN_TERM_EN  LOW
+
+
 #else
 #else
 #error "unsupported board"
 #error "unsupported board"
 #endif
 #endif

+ 39 - 21
RemoteIDModule/check_firmware.cpp

@@ -4,21 +4,27 @@
 #include "parameters.h"
 #include "parameters.h"
 #include <string.h>
 #include <string.h>
 #include "util.h"
 #include "util.h"
-
+/*
+该函数基于加密上下文(crypto_check_ctx),先初始化签名校验环境(绑定固件签名和公钥)→ 
+分批次传入固件数据(含可选的引导字节)→ 最终验证固件哈希值是否与描述符中的签名匹配,返回校验结果;
+*/
 bool CheckFirmware::check_partition(const uint8_t *flash, uint32_t flash_len,
 bool CheckFirmware::check_partition(const uint8_t *flash, uint32_t flash_len,
                                     const uint8_t *lead_bytes, uint32_t lead_length,
                                     const uint8_t *lead_bytes, uint32_t lead_length,
                                     const app_descriptor_t *ad, const uint8_t public_key[32])
                                     const app_descriptor_t *ad, const uint8_t public_key[32])
 {
 {
-    crypto_check_ctx ctx {};
-    crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx;
-    crypto_check_init(actx, ad->sign_signature, public_key);
-    if (lead_length > 0) {
+    crypto_check_ctx ctx {};  // 1. 初始化加密上下文(清空内存)
+    crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; // 2. 转换为抽象上下文指针(适配通用加密接口)
+    crypto_check_init(actx, ad->sign_signature, public_key); // 3. 绑定固件签名和公钥,初始化校验环境
+    if (lead_length > 0) { // 1. 若有引导字节,先传入引导字节数据
         crypto_check_update(actx, lead_bytes, lead_length);
         crypto_check_update(actx, lead_bytes, lead_length);
     }
     }
-    crypto_check_update(actx, &flash[lead_length], flash_len-lead_length);
-    return crypto_check_final(actx) == 0;
+    crypto_check_update(actx, &flash[lead_length], flash_len-lead_length); // 2. 传入剩余固件数据(总长度 - 引导字节长度)
+    return crypto_check_final(actx) == 0; // 验证最终哈希值是否与描述符中的签名匹配(公钥解密签名后对比)
 }
 }
-
+/*
+OTA 固件合法性校验的核心实现,完整覆盖了 “分区映射→固件描述符校验→板型匹配→公钥签名验证” 
+全流程 —— 只有通过所有校验的固件,才会被判定为合法并允许运行。
+*/
 bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length, uint32_t &board_id)
 bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length, uint32_t &board_id)
 {
 {
     Serial.printf("Checking partition %s\n", part->label);
     Serial.printf("Checking partition %s\n", part->label);
@@ -29,37 +35,43 @@ bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8
         Serial.printf("mmap failed\n");
         Serial.printf("mmap failed\n");
         return false;
         return false;
     }
     }
+    // 1. 反转签名字节序(APP_DESCRIPTOR_REV 是RemoteID厂商 预定义的8字节签名)可自行修改
     const uint8_t sig_rev[] = APP_DESCRIPTOR_REV;
     const uint8_t sig_rev[] = APP_DESCRIPTOR_REV;
     uint8_t sig[8];
     uint8_t sig[8];
     for (uint8_t i=0; i<8; i++) {
     for (uint8_t i=0; i<8; i++) {
         sig[i] = sig_rev[7-i];
         sig[i] = sig_rev[7-i];
     }
     }
+    // 2. 在映射内存中查找签名(定位固件描述符)  必须用脚本签名后才能找到这个app描述符,不然无效
     const app_descriptor_t *ad = (app_descriptor_t *)memmem(ptr, part->size, sig, sizeof(sig));
     const app_descriptor_t *ad = (app_descriptor_t *)memmem(ptr, part->size, sig, sizeof(sig));
     if (ad == nullptr) {
     if (ad == nullptr) {
         Serial.printf("app_descriptor not found\n");
         Serial.printf("app_descriptor not found\n");
-        spi_flash_munmap(handle);
+        spi_flash_munmap(handle); // 必须释放映射,否则内存泄漏
         return false;
         return false;
     }
     }
+
     Serial.printf("app descriptor at 0x%x size=%u id=%u (own id %u)\n", unsigned(ad)-unsigned(ptr), ad->image_size, ad->board_id,BOARD_ID);
     Serial.printf("app descriptor at 0x%x size=%u id=%u (own id %u)\n", unsigned(ad)-unsigned(ptr), ad->image_size, ad->board_id,BOARD_ID);
-    const uint32_t img_len = uint32_t(uintptr_t(ad) - uintptr_t(ptr));
+    // 1. 计算固件实际长度(从分区起始到描述符的偏移)
+    const uint32_t img_len = uint32_t(uintptr_t(ad) - uintptr_t(ptr)); // 固件描述符紧跟在固件的后面
+    // 2. 校验描述符中记录的固件大小是否匹配实际长度
     if (ad->image_size != img_len) {
     if (ad->image_size != img_len) {
         Serial.printf("app_descriptor bad size %u\n", ad->image_size);
         Serial.printf("app_descriptor bad size %u\n", ad->image_size);
         spi_flash_munmap(handle);
         spi_flash_munmap(handle);
         return false;
         return false;
     }
     }
-    board_id = ad->board_id;
-
+    board_id = ad->board_id; // 3. 提取板型ID(输出参数,供上层函数使用)
+    // 无公钥时跳过签名校验(降级策略)
     if (g.no_public_keys()) {
     if (g.no_public_keys()) {
         Serial.printf("No public keys - accepting firmware\n");
         Serial.printf("No public keys - accepting firmware\n");
         spi_flash_munmap(handle);
         spi_flash_munmap(handle);
         return true;
         return true;
     }
     }
-
+    // 遍历公钥校验固件签名(核心安全校验)
     for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
     for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
         uint8_t key[32];
         uint8_t key[32];
-        if (!g.get_public_key(i, key)) {
+        if (!g.get_public_key(i, key)) { // 读取预存的第i个公钥
             continue;
             continue;
         }
         }
+        // 用当前公钥校验固件签名
         if (check_partition((const uint8_t *)ptr, img_len, lead_bytes, lead_length, ad, key)) {
         if (check_partition((const uint8_t *)ptr, img_len, lead_bytes, lead_length, ad, key)) {
             Serial.printf("check firmware good for key %u\n", i);
             Serial.printf("check firmware good for key %u\n", i);
             spi_flash_munmap(handle);
             spi_flash_munmap(handle);
@@ -67,6 +79,9 @@ bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8
         }
         }
         Serial.printf("check failed key %u\n", i);
         Serial.printf("check failed key %u\n", i);
     }
     }
+    // 校验失败处理 
+    // 所有公钥校验失败 → 判定固件非法,返回 false;
+    // 最终释放内存映射,避免泄漏。
     spi_flash_munmap(handle);
     spi_flash_munmap(handle);
     Serial.printf("firmware failed checks\n");
     Serial.printf("firmware failed checks\n");
     return false;
     return false;
@@ -74,33 +89,36 @@ bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8
 
 
 bool CheckFirmware::check_OTA_next(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length)
 bool CheckFirmware::check_OTA_next(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length)
 {
 {
-    Serial.printf("Running partition %s\n", esp_ota_get_running_partition()->label);
+    Serial.printf("Running partition %s\n", esp_ota_get_running_partition()->label); // 打印当前运行分区
 
 
     uint32_t board_id = 0;
     uint32_t board_id = 0;
-    bool sig_ok = check_OTA_partition(part, lead_bytes, lead_length, board_id);
+    bool sig_ok = check_OTA_partition(part, lead_bytes, lead_length, board_id); // 校验目标 OTA 分区固件
 
 
-    if (g.lock_level == -1) {
+    if (g.lock_level == -1) { // 降级策略(lock_level=-1 放行所有固件)
         // only if lock_level is -1 then accept any firmware
         // only if lock_level is -1 then accept any firmware
         return true;
         return true;
     }
     }
 
 
     // if app descriptor has a board ID and the ID is wrong then reject
     // if app descriptor has a board ID and the ID is wrong then reject
-    if (board_id != 0 && board_id != BOARD_ID) {
+    if (board_id != 0 && board_id != BOARD_ID) { // 板型 ID 校验(防止错配固件)
         return false;
         return false;
     }
     }
 
 
     return sig_ok;
     return sig_ok;
 }
 }
-
+/*
+OTA 固件运行合法性校验的核心入口,作用是获取当前正在运行的 OTA 分区信息,
+并调用 check_OTA_partition() 校验该分区固件的合法性(比如是否为合规固件、是否匹配硬件板型等)。
+*/
 bool CheckFirmware::check_OTA_running(void)
 bool CheckFirmware::check_OTA_running(void)
 {
 {
-    const auto *running_part = esp_ota_get_running_partition();
+    const auto *running_part = esp_ota_get_running_partition(); // 获取当前运行的 OTA 分区
     if (running_part == nullptr) {
     if (running_part == nullptr) {
         Serial.printf("No running OTA partition\n");
         Serial.printf("No running OTA partition\n");
         return false;
         return false;
     }
     }
     uint32_t board_id=0;
     uint32_t board_id=0;
-    return check_OTA_partition(running_part, nullptr, 0, board_id);
+    return check_OTA_partition(running_part, nullptr, 0, board_id); // 定义板型 ID 变量并调用校验函数
 }
 }
         
         
 esp_err_t esp_partition_read_raw(const esp_partition_t* partition,
 esp_err_t esp_partition_read_raw(const esp_partition_t* partition,

+ 521 - 0
RemoteIDModule/cn_did_wifi.cpp

@@ -0,0 +1,521 @@
+/*
+Copyright (C) 2020 Simon Wunderlich, Marek Sobe
+Copyright (C) 2020 Doodle Labs
+
+SPDX-License-Identifier: Apache-2.0
+
+Open Drone ID C Library
+
+Maintainer:
+Simon Wunderlich
+sw@simonwunderlich.de
+*/
+/*该文件是对开源wifi修改适配国产标准*/
+#if defined(ARDUINO_ARCH_ESP32)
+#include <Arduino.h>
+int clock_gettime(clockid_t, struct timespec *);
+#else 
+#include <string.h>
+#include <stddef.h>
+#include <stdio.h>
+#endif
+
+#include <errno.h>
+#include <time.h>
+
+#include "cn_did_wifi.h"
+
+#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
+#define cpu_to_le16(x)  (x)
+#define cpu_to_le64(x)  (x)
+#else
+#define cpu_to_le16(x)      (bswap_16(x))
+#define cpu_to_le64(x)      (bswap_64(x))
+#endif
+
+#define IEEE80211_FCTL_FTYPE          0x000c
+#define IEEE80211_FCTL_STYPE          0x00f0
+
+#define IEEE80211_FTYPE_MGMT            0x0000
+#define IEEE80211_STYPE_ACTION          0x00D0
+#define IEEE80211_STYPE_BEACON          0x0080
+
+/* IEEE 802.11-2016 capability info */
+#define IEEE80211_CAPINFO_ESS               0x0001
+#define IEEE80211_CAPINFO_IBSS              0x0002
+#define IEEE80211_CAPINFO_CF_POLLABLE       0x0004
+#define IEEE80211_CAPINFO_CF_POLLREQ        0x0008
+#define IEEE80211_CAPINFO_PRIVACY           0x0010
+#define IEEE80211_CAPINFO_SHORT_PREAMBLE    0x0020
+/* bits 6-7 reserved */
+#define IEEE80211_CAPINFO_SPECTRUM_MGMT     0x0100
+#define IEEE80211_CAPINFO_QOS               0x0200
+#define IEEE80211_CAPINFO_SHORT_SLOTTIME    0x0400
+#define IEEE80211_CAPINFO_APSD              0x0800
+#define IEEE80211_CAPINFO_RADIOMEAS         0x1000
+/* bit 13 reserved */
+#define IEEE80211_CAPINFO_DEL_BLOCK_ACK     0x4000
+#define IEEE80211_CAPINFO_IMM_BLOCK_ACK     0x8000
+
+/* IEEE 802.11 Element IDs */
+#define IEEE80211_ELEMID_SSID		0x00
+#define IEEE80211_ELEMID_RATES		0x01
+#define IEEE80211_ELEMID_VENDOR		0xDD
+
+/* 《邻居感知网络规范》v3.1第2.8.2节
+* NAN集群ID是一个MAC地址,其取值范围为50-6F-9A-01-00-00至50-6F-9A-01-FF-FF,
+* 承载于部分NAN帧的A3字段中。NAN集群ID由发起NAN集群的设备随机选择。
+* 然而,《ASTM远程ID规范》v1.1规定,NAN集群ID必须固定为50-6F-9A-01-00-FF这一值。
+ */
+static const uint8_t *get_nan_cluster_id(void)
+{
+    static const uint8_t cluster_id[6] = { 0x50, 0x6F, 0x9A, 0x01, 0x00, 0xFF };
+    return cluster_id;
+}
+
+static int buf_fill_ieee80211_mgmt(uint8_t *buf, size_t *len, size_t buf_size,
+                                   const uint16_t subtype,
+                                   const uint8_t *dst_addr,
+                                   const uint8_t *src_addr,
+                                   const uint8_t *bssid)
+{
+    if (*len + sizeof(struct ieee80211_mgmt) > buf_size)
+        return -ENOMEM;
+
+    struct ieee80211_mgmt *mgmt = (struct ieee80211_mgmt *)(buf + *len);
+    mgmt->frame_control = (uint16_t) cpu_to_le16(IEEE80211_FTYPE_MGMT | subtype);
+    mgmt->duration = cpu_to_le16(0x0000);
+    memcpy(mgmt->da, dst_addr, sizeof(mgmt->da));
+    memcpy(mgmt->sa, src_addr, sizeof(mgmt->sa));
+    memcpy(mgmt->bssid, bssid, sizeof(mgmt->bssid));
+    mgmt->seq_ctrl = cpu_to_le16(0x0000);
+    *len += sizeof(*mgmt);
+
+    return 0;
+}
+
+static int buf_fill_ieee80211_beacon(uint8_t *buf, size_t *len, size_t buf_size, uint16_t interval_tu)
+{
+    if (*len + sizeof(struct ieee80211_beacon) > buf_size)
+        return -ENOMEM;
+
+    struct ieee80211_beacon *beacon = (struct ieee80211_beacon *)(buf + *len);
+    struct timespec ts;
+    uint64_t mono_us = 0;
+
+#if defined(CLOCK_MONOTONIC)
+    clock_gettime(CLOCK_MONOTONIC, &ts);
+    mono_us = (uint64_t)((double) ts.tv_sec * 1e6 + (double) ts.tv_nsec * 1e-3);
+#elif defined(CLOCK_REALTIME)
+    clock_gettime(CLOCK_REALTIME, &ts);
+    mono_us = (uint64_t)((double) ts.tv_sec * 1e6 + (double) ts.tv_nsec * 1e-3);
+#elif defined(ARDUINO)
+#warning "No REALTIME or MONOTONIC clock, using micros()."
+    mono_us = micros();
+#else
+#warning "Unable to set wifi timestamp."
+#endif
+    beacon->timestamp = cpu_to_le64(mono_us);
+    beacon->beacon_interval = cpu_to_le16(interval_tu);
+    beacon->capability = cpu_to_le16(IEEE80211_CAPINFO_SHORT_SLOTTIME | IEEE80211_CAPINFO_SHORT_PREAMBLE);
+    *len += sizeof(*beacon);
+
+    return 0;
+}
+
+/* void* 不能用 可能是编译器版本的问题 改成uint8_t* 了*/
+int cndid_message_build_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen)
+{
+    CNDID_MessagePack_data msg_pack;
+    CNDID_MessagePack_encoded *msg_pack_enc;
+    size_t len;
+
+    /* create a complete message pack 不知道这里为什么不允许void* 都改成对应的指针类别了*/
+    msg_pack.SingleMessageSize = CNDID_MESSAGE_SIZE;
+    msg_pack.MsgPackSize = 0;
+    for (int i = 0; i < CNDID_BASIC_ID_MAX_MESSAGES; i++) {
+        if (UAS_Data->BasicIDValid[i]) {
+            if (msg_pack.MsgPackSize >= CNDID_PACK_MAX_MESSAGES)
+                return -EINVAL;
+            if (encodeCNBasicIDMessage((CNDID_BasicID_encoded*)(&msg_pack.Messages[msg_pack.MsgPackSize]), &UAS_Data->BasicID[i]) == CNDID_SUCCESS)
+                msg_pack.MsgPackSize++;
+        }
+    }
+    if (UAS_Data->LocationValid) {
+        if (msg_pack.MsgPackSize >= CNDID_PACK_MAX_MESSAGES)
+            return -EINVAL;
+        if (encodeCNLocationMessage((CNDID_Location_encoded*)(&msg_pack.Messages[msg_pack.MsgPackSize]), &UAS_Data->Location) == CNDID_SUCCESS)
+            msg_pack.MsgPackSize++;
+    }
+    
+    if (UAS_Data->SelfIDValid) {
+        if (msg_pack.MsgPackSize >= CNDID_PACK_MAX_MESSAGES)
+            return -EINVAL;
+        if (encodeCNSelfIDMessage((CNDID_SelfID_encoded*)(&msg_pack.Messages[msg_pack.MsgPackSize]), &UAS_Data->SelfID) == CNDID_SUCCESS)
+            msg_pack.MsgPackSize++;
+    }
+    if (UAS_Data->SystemValid) {
+        if (msg_pack.MsgPackSize >= CNDID_PACK_MAX_MESSAGES)
+            return -EINVAL;
+        if (encodeCNSystemMessage((CNDID_System_encoded*)(&msg_pack.Messages[msg_pack.MsgPackSize]), &UAS_Data->System) == CNDID_SUCCESS)
+            msg_pack.MsgPackSize++;
+    }
+    /* check that there is at least one message to send. */
+    if (msg_pack.MsgPackSize == 0)
+        return -EINVAL;
+
+    /* calculate the exact encoded message pack size. */
+    len = sizeof(*msg_pack_enc) - (CNDID_PACK_MAX_MESSAGES - msg_pack.MsgPackSize) * CNDID_MESSAGE_SIZE;
+
+    /* check if there is enough space for the message pack. */
+    if (len > buflen)
+        return -ENOMEM;
+
+    msg_pack_enc = (CNDID_MessagePack_encoded *) pack;
+    if (encodeCNMessagePack(msg_pack_enc, &msg_pack) != CNDID_SUCCESS)
+        return -1;
+
+    return (int) len;
+}
+// 里面的服务id可能后面要改 还有一些指向 open droneid的
+int cndid_wifi_build_nan_sync_beacon_frame(char *mac, uint8_t *buf, size_t buf_size)
+{
+    /* Broadcast address */
+    uint8_t target_addr[6] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A };
+    /* "org.opendroneid.remoteid" hash */
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 };
+    const uint8_t *cluster_id = get_nan_cluster_id();
+    struct ieee80211_vendor_specific *vendor;
+    struct nan_master_indication_attribute *master_indication_attr;
+    struct nan_cluster_attribute *cluster_attr;
+    struct nan_service_id_list_attribute *nsila;
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_BEACON, target_addr, (uint8_t *)mac, cluster_id);
+    if (ret <0)
+        return ret;
+
+    /* Beacon */
+    ret = buf_fill_ieee80211_beacon(buf, &len, buf_size, 0x0200);
+    if (ret <0)
+        return ret;
+
+    /* Vendor Specific */
+    if (len + sizeof(*vendor) > buf_size)
+        return -ENOMEM;
+
+    vendor = (struct ieee80211_vendor_specific *)(buf + len);
+    memset(vendor, 0, sizeof(*vendor));
+    vendor->element_id = IEEE80211_ELEMID_VENDOR;
+    vendor->length = 0x22;
+    memcpy(vendor->oui, wifi_alliance_oui, sizeof(vendor->oui));
+    vendor->oui_type = 0x13; 
+    len += sizeof(*vendor);
+
+    /* NAN Master Indication attribute */
+    if (len + sizeof(*master_indication_attr) > buf_size)
+        return -ENOMEM;
+
+    master_indication_attr = (struct nan_master_indication_attribute *)(buf + len);
+    memset(master_indication_attr, 0, sizeof(*master_indication_attr));
+    master_indication_attr->header.attribute_id = 0x00;
+    master_indication_attr->header.length = cpu_to_le16(0x0002);
+    /* Information that is used to indicate a NAN Device’s preference to serve
+     * as the role of Master, with a larger value indicating a higher
+     * preference. Values 1 and 255 are used for testing purposes only.
+     */
+    master_indication_attr->master_preference = 0xFE;
+    /* Random factor value 0xEA is recommended by the European Standard */
+    master_indication_attr->random_factor = 0xEA;
+    len += sizeof(*master_indication_attr);
+
+    /* NAN Cluster attribute */
+    if (len + sizeof(*cluster_attr) > buf_size)
+        return -ENOMEM;
+
+    cluster_attr = (struct nan_cluster_attribute *)(buf + len);
+    memset(cluster_attr, 0, sizeof(*cluster_attr));
+    cluster_attr->header.attribute_id = 0x1;
+    cluster_attr->header.length = cpu_to_le16(0x000D);
+    memcpy(cluster_attr->device_mac, mac, sizeof(cluster_attr->device_mac));
+    cluster_attr->random_factor = 0xEA;
+    cluster_attr->master_preference = 0xFE;
+    cluster_attr->hop_count_to_anchor_master = 0x00;
+    memset(cluster_attr->anchor_master_beacon_transmission_time, 0, sizeof(cluster_attr->anchor_master_beacon_transmission_time));
+    len += sizeof(*cluster_attr);
+
+    /* NAN attributes */
+    if (len + sizeof(*nsila) > buf_size)
+        return -ENOMEM;
+
+    nsila = (struct nan_service_id_list_attribute *)(buf + len);
+    memset(nsila, 0, sizeof(*nsila));
+    nsila->header.attribute_id = 0x02;
+    nsila->header.length = cpu_to_le16(0x0006);
+    memcpy(nsila->service_id, service_id, sizeof(service_id));
+    len += sizeof(*nsila);
+
+    return (int) len;
+}
+
+int cndid_wifi_build_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data, char *mac,
+                                                  uint8_t send_counter,
+                                                  uint8_t *buf, size_t buf_size)
+{
+    /* Neighbor Awareness Networking Specification v3.0 in section 2.8.1
+     * NAN网络ID要求目标MAC地址为51-6F-9A-01-00-00*/
+    uint8_t target_addr[6] = { 0x51, 0x6F, 0x9A, 0x01, 0x00, 0x00 };
+    /* "org.opendroneid.remoteid 哈希值 国际通用的*/
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 };
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A };
+    const uint8_t *cluster_id = get_nan_cluster_id();
+    struct nan_service_discovery *nsd;
+    struct nan_service_descriptor_attribute *nsda;
+    struct nan_service_descriptor_extension_attribute *nsdea;
+    struct CNDID_service_info *si;
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_ACTION, target_addr, (uint8_t *)mac, cluster_id);
+    if (ret <0)
+        return ret;
+
+    /* NAN Service Discovery header */
+    if (len + sizeof(*nsd) > buf_size)
+        return -ENOMEM;
+
+    nsd = (struct nan_service_discovery *)(buf + len);
+    memset(nsd, 0, sizeof(*nsd));
+    nsd->category = 0x04;               /* IEEE 802.11 Public Action frame */
+    nsd->action_code = 0x09;            /* IEEE 802.11 Public Action frame Vendor Specific*/
+    memcpy(nsd->oui, wifi_alliance_oui, sizeof(nsd->oui));
+    nsd->oui_type = 0x13;               /* Identify Type and version of the NAN */
+    len += sizeof(*nsd);
+
+    /* NAN Attribute for Service Descriptor header */
+    if (len + sizeof(*nsda) > buf_size)
+        return -ENOMEM;
+
+    nsda = (struct nan_service_descriptor_attribute *)(buf + len);
+    nsda->header.attribute_id = 0x3;    /* Service Descriptor Attribute type */
+    memcpy(nsda->service_id, service_id, sizeof(service_id));
+    /* always 1 */
+    nsda->instance_id = 0x01;           /* always 1 */
+    nsda->requestor_instance_id = 0x00; /* from triggering frame */
+    nsda->service_control = 0x10;       /* follow up */
+    len += sizeof(*nsda);
+
+    /* CNDID Service Info Attribute header */
+    if (len + sizeof(*si) > buf_size)
+        return -ENOMEM;
+
+    si = (struct CNDID_service_info *)(buf + len);
+    memset(si, 0, sizeof(*si));
+    si->message_counter = send_counter;
+    len += sizeof(*si);
+
+    ret = cndid_message_build_pack(UAS_Data, buf + len, buf_size - len);
+    if (ret < 0)
+        return ret;
+    len += ret;
+
+    /* set the lengths according to the message pack lengths */
+    nsda->service_info_length = sizeof(*si) + ret;
+    nsda->header.length = cpu_to_le16(sizeof(*nsda) - sizeof(struct nan_attribute_header) + nsda->service_info_length);
+
+    /* NAN Attribute for Service Descriptor extension header */
+    if (len + sizeof(*nsdea) > buf_size)
+        return -ENOMEM;
+
+    nsdea = (struct nan_service_descriptor_extension_attribute *)(buf + len);
+    nsdea->header.attribute_id = 0xE;
+    nsdea->header.length = cpu_to_le16(0x0004);
+    nsdea->instance_id = 0x01;
+    nsdea->control = cpu_to_le16(0x0200);
+    nsdea->service_update_indicator = send_counter;
+    len += sizeof(*nsdea);
+
+    return (int) len;
+}
+
+int cndid_wifi_build_message_pack_beacon_frame(CNDID_UAS_Data *UAS_Data, char *mac,
+                                              const char *SSID, size_t SSID_len,
+                                              uint16_t interval_tu, uint8_t send_counter,
+                                              uint8_t *buf, size_t buf_size)
+{
+    /* Broadcast address */
+    uint8_t target_addr[6] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
+    uint8_t asd_stan_oui[3] = { 0xFA, 0x0B, 0xBC }; // 国标也是0xFA0BBC
+    /* Mgmt Beacon frame mandatory fields + IE 221 */
+    struct ieee80211_ssid *ssid_s;
+    struct ieee80211_supported_rates *rates;
+    struct ieee80211_vendor_specific *vendor;
+
+    /* Message Pack */
+    struct CNDID_service_info *si;
+
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_BEACON, target_addr, (uint8_t *)mac, (uint8_t *)mac);
+    if (ret <0)
+        return ret;
+
+    /* Mandatory Beacon as of 802.11-2016 Part 11 */
+    ret = buf_fill_ieee80211_beacon(buf, &len, buf_size, interval_tu);
+    if (ret <0)
+        return ret;
+
+    /* SSID: 1-32 bytes */
+    if (len + sizeof(*ssid_s) > buf_size)
+        return -ENOMEM;
+
+    ssid_s = (struct ieee80211_ssid *)(buf + len);
+    if(!SSID || (SSID_len ==0) || (SSID_len > 32))
+        return -EINVAL;
+    ssid_s->element_id = IEEE80211_ELEMID_SSID;
+    ssid_s->length = (uint8_t) SSID_len;
+    memcpy(ssid_s->ssid, SSID, ssid_s->length);
+    len += sizeof(*ssid_s) + SSID_len;
+
+    /* Supported Rates: 1 record at minimum */
+    if (len + sizeof(*rates) > buf_size)
+        return -ENOMEM;
+
+    rates = (struct ieee80211_supported_rates *)(buf + len);
+    rates->element_id = IEEE80211_ELEMID_RATES;
+    rates->length = 1; // One rate only
+    rates->supported_rates = 0x8C;     // 6 Mbps
+    len += sizeof(*rates);
+
+    /* Vendor Specific Information Element (IE 221) */
+    if (len + sizeof(*vendor) > buf_size)
+        return -ENOMEM;
+
+    vendor = (struct ieee80211_vendor_specific *)(buf + len);
+    vendor->element_id = IEEE80211_ELEMID_VENDOR;
+    vendor->length = 0x00;  // Length updated at end of function
+    memcpy(vendor->oui, asd_stan_oui, sizeof(vendor->oui));
+    vendor->oui_type = 0x0D;
+    len += sizeof(*vendor);
+
+    /* CNDID Service Info Attribute header */
+    if (len + sizeof(*si) > buf_size)
+        return -ENOMEM;
+
+    si = (struct CNDID_service_info *)(buf + len);
+    memset(si, 0, sizeof(*si));
+    si->message_counter = send_counter;
+    len += sizeof(*si);
+
+    ret = cndid_message_build_pack(UAS_Data, buf + len, buf_size - len);
+    if (ret < 0)
+        return ret;
+    len += ret;
+
+    /* set the lengths according to the message pack lengths */
+    vendor->length = sizeof(vendor->oui) + sizeof(vendor->oui_type) + sizeof(*si) + ret;
+
+    return (int) len;
+}
+
+int cndid_message_process_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen)
+{
+    CNDID_MessagePack_encoded *msg_pack_enc = (CNDID_MessagePack_encoded *) pack;
+    size_t size = sizeof(*msg_pack_enc) - CNDID_MESSAGE_SIZE * (CNDID_PACK_MAX_MESSAGES - msg_pack_enc->MsgPackSize);
+    if (size > buflen)
+        return -ENOMEM;
+
+    cndid_initUasData(UAS_Data);
+
+    if (decodeCNMessagePack(UAS_Data, msg_pack_enc) != CNDID_SUCCESS)
+        return -1;
+
+    return (int) size;
+}
+
+int cndid_wifi_receive_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data,
+                                                    char *mac, uint8_t *buf, size_t buf_size)
+{
+    struct ieee80211_mgmt *mgmt; // 802.11管理帧头
+    struct nan_service_discovery *nsd; // NAN服务发现帧头
+    struct nan_service_descriptor_attribute *nsda; // NAN服务描述符属性
+    struct nan_service_descriptor_extension_attribute *nsdea;  // NAN服务描述符扩展属性
+    struct CNDID_service_info *si; // 中国远程ID服务信息
+    uint8_t target_addr[6] = { 0x51, 0x6F, 0x9A, 0x01, 0x00, 0x00 };  // 远程ID(Remote ID)分配的专用组播地址
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A }; // Wi-Fi联盟OUI
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 }; // 远程ID服务ID 国际通用的 不需要改
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    if (len + sizeof(*mgmt) > buf_size) // 检查缓冲区是否足够容纳一个管理帧头
+        return -EINVAL;
+    mgmt = (struct ieee80211_mgmt *)(buf + len);
+    if ((mgmt->frame_control & cpu_to_le16(IEEE80211_FCTL_FTYPE | IEEE80211_FCTL_STYPE)) !=
+        cpu_to_le16(IEEE80211_FTYPE_MGMT | IEEE80211_STYPE_ACTION))
+        return -EINVAL;
+    if (memcmp(mgmt->da, target_addr, sizeof(mgmt->da)) != 0)
+        return -EINVAL;
+    memcpy(mac, mgmt->sa, sizeof(mgmt->sa));
+
+    len += sizeof(*mgmt);
+
+    /* NAN Service Discovery header */
+    if (len + sizeof(*nsd) > buf_size)
+        return -EINVAL;
+    nsd = (struct nan_service_discovery *)(buf + len);
+    if (nsd->category != 0x04)
+        return -EINVAL;
+    if (nsd->action_code != 0x09)
+        return -EINVAL;
+    if (memcmp(nsd->oui, wifi_alliance_oui, sizeof(wifi_alliance_oui)) != 0)
+        return -EINVAL;
+    if (nsd->oui_type != 0x13)
+        return -EINVAL;
+    len += sizeof(*nsd);
+
+    /* NAN Attribute for Service Descriptor header */
+    if (len + sizeof(*nsda) > buf_size)
+        return -EINVAL;
+    nsda = (struct nan_service_descriptor_attribute *)(buf + len);
+    if (nsda->header.attribute_id != 0x3)
+        return -EINVAL;
+    if (memcmp(nsda->service_id, service_id, sizeof(service_id)) != 0)
+        return -EINVAL;
+    if (nsda->instance_id != 0x01)
+        return -EINVAL;
+    if (nsda->service_control != 0x10)
+        return -EINVAL;
+    len += sizeof(*nsda);
+
+    si = (struct CNDID_service_info *)(buf + len);
+    ret = cndid_message_process_pack(UAS_Data, buf + len + sizeof(*si), buf_size - len - sizeof(*nsdea));
+    if (ret < 0)
+        return -EINVAL;
+    if (nsda->service_info_length != (sizeof(*si) + ret))
+        return -EINVAL;
+    if (nsda->header.length != (cpu_to_le16(sizeof(*nsda) - sizeof(struct nan_attribute_header) + nsda->service_info_length)))
+        return -EINVAL;
+    len += sizeof(*si) + ret;
+
+    /* NAN Attribute for Service Descriptor extension header */
+    if (len + sizeof(*nsdea) > buf_size)
+        return -ENOMEM;
+    nsdea = (struct nan_service_descriptor_extension_attribute *)(buf + len);
+    if (nsdea->header.attribute_id != 0xE)
+        return -EINVAL;
+    if (nsdea->header.length != cpu_to_le16(0x0004))
+        return -EINVAL;
+    if (nsdea->instance_id != 0x01)
+        return -EINVAL;
+    if (nsdea->control != cpu_to_le16(0x0200))
+        return -EINVAL;
+
+    return 0;
+}

+ 24 - 0
RemoteIDModule/cn_did_wifi.h

@@ -0,0 +1,24 @@
+/*
+Copyright (C) 2019 Intel Corporation
+
+SPDX-License-Identifier: Apache-2.0
+
+Open Drone ID C Library
+
+Maintainer:
+Gabriel Cox
+gabriel.c.cox@intel.com
+*/
+/*由opendroneid而来 暂时符合opendroneid的wifi形式*/
+#pragma once
+#include "stdint.h"
+#include "odid_wifi.h"
+#include "cndroneid.h"
+/* 国标元素ID */
+#define CN_WIFI_VENDOR_IE_ELEMENT_ID 0xDD
+
+struct __attribute__((__packed__)) CNDID_service_info {
+    uint8_t message_counter;
+    CNDID_MessagePack_encoded cndid_message_pack[];
+};
+

+ 1241 - 0
RemoteIDModule/cndroneid.cpp

@@ -0,0 +1,1241 @@
+/*
+Copyright (C) 2019 Intel Corporation
+
+SPDX-License-Identifier: Apache-2.0
+
+Open Drone ID C Library
+
+Maintainer:
+Gabriel Cox
+gabriel.c.cox@intel.com
+*/
+/*看到最后发现,国标跟国际的区别:去掉认证 认证ID 系统里对保留的3bit用了2bit作为坐标系 其他完全一样*/
+#include "cndroneid.h"
+#include <math.h>
+#include <stdio.h>
+#define ENABLE_DEBUG 1
+
+const float CN_SPEED_DIV[2] = {0.25f, 0.75f};
+const float CN_VSPEED_DIV = 0.5f;
+const int32_t CN_LATLON_MULT = 10000000;
+const float CN_ALT_DIV = 0.5f;
+const int CN_ALT_ADDER = 1000;
+
+static char *safe_dec_copyfill(char *dstStr, const char *srcStr, int dstSize);
+static int intRangeMax(int64_t inValue, int startRange, int endRange);
+static int intInRange(int inValue, int startRange, int endRange);
+
+
+
+/**
+* Initialize basic ID data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+void cndid_initBasicIDData(CNDID_BasicID_data *data)
+{
+    if (!data)
+        return;
+    memset(data, 0, sizeof(CNDID_BasicID_data));
+}
+
+/**
+* Initialize location data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+void cndid_initLocationData(CNDID_Location_data *data)
+{
+    if (!data)
+        return;
+    memset(data, 0, sizeof(CNDID_Location_data));
+    data->Direction = CN_INV_DIR;
+    data->SpeedHorizontal = CN_INV_SPEED_H;
+    data->SpeedVertical = CN_INV_SPEED_V;
+    data->AltitudeBaro = CN_INV_ALT;
+    data->AltitudeGeo = CN_INV_ALT;
+    data->Height = CN_INV_ALT;
+}
+
+/**
+* Initialize self ID data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+void cndid_initSelfIDData(CNDID_SelfID_data *data)
+{
+    if (!data)
+        return;
+    memset(data, 0, sizeof(CNDID_SelfID_data));
+}
+
+/**
+* Initialize system data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+
+void cndid_initSystemData(CNDID_System_data *data)
+{
+    if (!data)
+        return;
+    memset(data, 0, sizeof(CNDID_System_data));
+    data->AreaCount = 1;
+    data->AreaCeiling = CN_INV_ALT;
+    data->AreaFloor = CN_INV_ALT;
+    data->OperatorAltitudeGeo = CN_INV_ALT;
+}
+
+
+/**
+* Initialize message pack data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+
+void cndid_initMessagePackData(CNDID_MessagePack_data *data)
+{
+    if (!data)
+        return;
+    memset(data, 0, sizeof(CNDID_MessagePack_data));
+    data->SingleMessageSize = CNDID_MESSAGE_SIZE;
+}
+
+/**
+* Initialize UAS data fields to their default values
+*
+* @param data (non encoded/packed) structure
+*/
+
+void cndid_initUasData(CNDID_UAS_Data *data)
+{
+    if (!data)
+        return;
+    for (int i = 0; i < CNDID_BASIC_ID_MAX_MESSAGES; i++) {
+        data->BasicIDValid[i] = 0;
+        cndid_initBasicIDData(&data->BasicID[i]);
+    }
+    data->LocationValid = 0;
+    cndid_initLocationData(&data->Location);
+    data->SelfIDValid = 0;
+    cndid_initSelfIDData(&data->SelfID);
+    data->SystemValid = 0;
+    cndid_initSystemData(&data->System);
+
+}
+
+/**
+* Encode direction as defined by Open Drone ID
+*
+* The encoding method uses 8 bits for the direction in degrees and
+* one extra bit for indicating the East/West direction.
+*
+* @param Direcction in degrees. 0 <= x < 360. Route course based on true North
+* @param EWDirection Bit flag indicating whether the direction is towards
+                     East (0 - 179 degrees) or West (180 - 359)
+* @return Encoded Direction in a single byte
+*/
+static uint8_t encodeDirection(float Direction, uint8_t *EWDirection)
+{
+    unsigned int direction_int = (unsigned int) roundf(Direction);
+    if (direction_int < 180) {
+        *EWDirection = 0;
+    } else {
+        *EWDirection = 1;
+        direction_int -= 180;
+    }
+    return (uint8_t) intRangeMax(direction_int, 0, UINT8_MAX);
+}
+
+/**
+* Encode speed into units defined by Open Drone ID
+*
+* The quantization algorithm allows for speed to be stored in units of 0.25 m/s
+* on the low end of the scale and 0.75 m/s on the high end of the scale.
+* This allows for more precise speeds to be represented in a single Uint8 byte
+* rather than using a large float value.
+*
+* @param Speed_data Speed (and decimal) in m/s
+* @param mult a (write only) value that sets the multiplier flag
+* @return Encoded Speed in a single byte or max speed if over max encoded speed.
+*/
+static uint8_t encodeSpeedHorizontal(float Speed_data, uint8_t *mult)
+{
+    if (Speed_data <= UINT8_MAX * CN_SPEED_DIV[0]) {
+        *mult = 0;
+        return (uint8_t) (Speed_data / CN_SPEED_DIV[0]);
+    } else {
+        *mult = 1;
+        int big_value = (int) ((Speed_data - (UINT8_MAX * CN_SPEED_DIV[0])) / CN_SPEED_DIV[1]);
+        return (uint8_t) intRangeMax(big_value, 0, UINT8_MAX);
+    }
+}
+
+/**
+* Encode Vertical Speed into a signed Integer CNDID format
+*
+* @param SpeedVertical_data vertical speed (in m/s)
+* @return Encoded vertical speed
+*/
+static int8_t encodeSpeedVertical(float SpeedVertical_data)
+{
+    int encValue = (int) (SpeedVertical_data / CN_VSPEED_DIV);
+    return (int8_t) intRangeMax(encValue, INT8_MIN, INT8_MAX);
+}
+
+/**
+* Encode Latitude or Longitude value into a signed Integer CNDID format
+*
+* This encodes a 64bit double into a 32 bit integer yet still maintains
+* 10^7 of a degree of accuracy (about 1cm)
+*
+* @param LatLon_data Either Lat or Lon double float value
+* @return Encoded Lat or Lon
+*/
+static int32_t encodeLatLon(double LatLon_data)
+{
+    return (int32_t) intRangeMax((int64_t) (LatLon_data * CN_LATLON_MULT), -180 * CN_LATLON_MULT, 180 * CN_LATLON_MULT);
+}
+
+/**
+* Encode Altitude value into an int16 CNDID format
+*
+* This encodes a 32bit floating point altitude into an uint16 compressed
+* scale that starts at -1000m.
+*
+* @param Alt_data Altitude to encode (in meters)
+* @return Encoded Altitude
+*/
+static uint16_t encodeAltitude(float Alt_data)
+{
+    return (uint16_t) intRangeMax( (int) ((Alt_data + (float) CN_ALT_ADDER) / CN_ALT_DIV), 0, UINT16_MAX);
+}
+
+/**
+* Encode timestamp data in CNDID format
+*
+* This encodes a fractional seconds value into a 2 byte int16
+* on a scale of tenths of seconds since after the hour.
+*
+* @param Seconds_data Seconds (to at least 1 decimal place) since the hour
+* @return Encoded timestamp (Tenths of seconds since the hour)
+*/
+static uint16_t encodeTimeStamp(float Seconds_data)
+{
+    if (Seconds_data == CN_INV_TIMESTAMP)
+        return CN_INV_TIMESTAMP;
+    else
+        return (uint16_t) intRangeMax((int64_t) roundf(Seconds_data*10), 0, CN_MAX_TIMESTAMP * 10);
+}
+
+/**
+* Encode area radius data in CNDID format
+*
+* This encodes the area radius in meters into a 1 byte value
+*
+* @param Radius The radius of the drone area/swarm
+* @return Encoded area radius
+*/
+static uint8_t encodeAreaRadius(uint16_t Radius)
+{
+    return (uint8_t) intRangeMax(Radius / 10, 0, 255);
+}
+
+/**
+* Encode Basic ID message (packed, ready for broadcast)
+*
+* @param outEncoded Output (encoded/packed) structure
+* @param inData     Input data (non encoded/packed) structure
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int encodeCNBasicIDMessage(CNDID_BasicID_encoded *outEncoded, CNDID_BasicID_data *inData)
+{
+    if (!outEncoded || !inData ||
+        !intInRange(inData->IDType, 0, 15) ||
+        !intInRange(inData->UAType, 0, 15))
+        return CNDID_FAIL;
+
+    outEncoded->MessageType = CNDID_MESSAGETYPE_BASIC_ID;
+    outEncoded->ProtoVersion = CNDID_PROTOCOL_VERSION;
+    outEncoded->IDType = inData->IDType;
+    outEncoded->UAType = inData->UAType;
+    strncpy(outEncoded->UASID, inData->UASID, sizeof(outEncoded->UASID));
+    memset(outEncoded->Reserved, 0, sizeof(outEncoded->Reserved));
+    return CNDID_SUCCESS;
+}
+
+/**
+* Encode Location message (packed, ready for broadcast)
+*
+* @param outEncoded Output (encoded/packed) structure
+* @param inData     Input data (non encoded/packed) structure
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int encodeCNLocationMessage(CNDID_Location_encoded *outEncoded, CNDID_Location_data *inData)
+{
+    uint8_t bitflag;
+    if (!outEncoded || !inData ||
+        !intInRange(inData->Status, 0, 15) ||
+        !intInRange(inData->HeightType, 0, 1) ||
+        !intInRange(inData->HorizAccuracy, 0, 15) ||
+        !intInRange(inData->VertAccuracy, 0, 15) ||
+        !intInRange(inData->BaroAccuracy, 0, 15) ||
+        !intInRange(inData->SpeedAccuracy, 0, 15) ||
+        !intInRange(inData->TSAccuracy, 0, 15))
+        return CNDID_FAIL;
+
+    if (inData->Direction < CN_MIN_DIR || inData->Direction > CN_INV_DIR ||
+        (inData->Direction > CN_MAX_DIR && inData->Direction < CN_INV_DIR))
+        return CNDID_FAIL;
+
+    if (inData->SpeedHorizontal < CN_MIN_SPEED_H || inData->SpeedHorizontal > CN_INV_SPEED_H ||
+        (inData->SpeedHorizontal > CN_MAX_SPEED_H && inData->SpeedHorizontal < CN_INV_SPEED_H))
+        return CNDID_FAIL;
+
+    if (inData->SpeedVertical < CN_MIN_SPEED_V || inData->SpeedVertical > CN_INV_SPEED_V ||
+        (inData->SpeedVertical > CN_MAX_SPEED_V && inData->SpeedVertical < CN_INV_SPEED_V))
+        return CNDID_FAIL;
+
+    if (inData->Latitude < CN_MIN_LAT || inData->Latitude > CN_MAX_LAT ||
+        inData->Longitude < CN_MIN_LON || inData->Longitude > CN_MAX_LON)
+        return CNDID_FAIL;
+
+    if (inData->AltitudeBaro < CN_MIN_ALT || inData->AltitudeBaro > CN_MAX_ALT ||
+        inData->AltitudeGeo < CN_MIN_ALT || inData->AltitudeGeo > CN_MAX_ALT ||
+        inData->Height < CN_MIN_ALT || inData->Height > CN_MAX_ALT)
+        return CNDID_FAIL;
+
+    if (inData->TimeStamp < 0 ||
+        (inData->TimeStamp > CN_MAX_TIMESTAMP && inData->TimeStamp != CN_INV_TIMESTAMP))
+        return CNDID_FAIL;
+
+    outEncoded->MessageType = CNDID_MESSAGETYPE_LOCATION;
+    outEncoded->ProtoVersion = CNDID_PROTOCOL_VERSION;
+    outEncoded->Status = inData->Status;
+    outEncoded->Reserved = 0;
+    outEncoded->Direction = encodeDirection(inData->Direction, &bitflag);
+    outEncoded->EWDirection = bitflag;
+    outEncoded->SpeedHorizontal = encodeSpeedHorizontal(inData->SpeedHorizontal, &bitflag);
+    outEncoded->SpeedMult = bitflag;
+    outEncoded->SpeedVertical = encodeSpeedVertical(inData->SpeedVertical);
+    outEncoded->Latitude = encodeLatLon(inData->Latitude);
+    outEncoded->Longitude = encodeLatLon(inData->Longitude);
+    outEncoded->AltitudeBaro = encodeAltitude(inData->AltitudeBaro);
+    outEncoded->AltitudeGeo = encodeAltitude(inData->AltitudeGeo);
+    outEncoded->HeightType = inData->HeightType;
+    outEncoded->Height = encodeAltitude(inData->Height);
+    outEncoded->HorizAccuracy = inData->HorizAccuracy;
+    outEncoded->VertAccuracy = inData->VertAccuracy;
+    outEncoded->BaroAccuracy = inData->BaroAccuracy;
+    outEncoded->SpeedAccuracy = inData->SpeedAccuracy;
+    outEncoded->TSAccuracy = inData->TSAccuracy;
+    outEncoded->Reserved2 = 0;
+    outEncoded->TimeStamp = encodeTimeStamp(inData->TimeStamp);
+    outEncoded->Reserved3 = 0;
+    return CNDID_SUCCESS;
+}
+
+
+/**
+* Encode Self ID message (packed, ready for broadcast)
+*
+* @param outEncoded Output (encoded/packed) structure
+* @param inData     Input data (non encoded/packed) structure
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int encodeCNSelfIDMessage(CNDID_SelfID_encoded *outEncoded, CNDID_SelfID_data *inData)
+{
+    if (!outEncoded || !inData || !intInRange(inData->DescType, 0, 255))
+        return CNDID_FAIL;
+
+    outEncoded->MessageType = CNDID_MESSAGETYPE_SELF_ID;
+    outEncoded->ProtoVersion = CNDID_PROTOCOL_VERSION;
+    outEncoded->DescType = inData->DescType;
+    strncpy(outEncoded->Desc, inData->Desc, sizeof(outEncoded->Desc));
+    return CNDID_SUCCESS;
+}
+
+/**
+* Encode System message (packed, ready for broadcast)
+*
+* @param outEncoded Output (encoded/packed) structure
+* @param inData     Input data (non encoded/packed) structure
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int encodeCNSystemMessage(CNDID_System_encoded *outEncoded, CNDID_System_data *inData)
+{
+    if (!outEncoded || !inData ||
+        !intInRange(inData->OperatorLocationType, 0, 3) ||
+        !intInRange(inData->Classification_Type, 0, 7) ||
+        !intInRange(inData->CategoryCN, 0, 15) ||
+        !intInRange(inData->ClassCN, 0, 15)||
+        !intInRange(inData->Coord_Type,0, 3)) // 坐标系类型
+        return CNDID_FAIL;
+
+    if (inData->OperatorLatitude < CN_MIN_LAT || inData->OperatorLatitude > CN_MAX_LAT ||
+        inData->OperatorLongitude < CN_MIN_LON || inData->OperatorLongitude > CN_MAX_LON)
+        return CNDID_FAIL;
+
+    if (inData->AreaRadius > CN_MAX_AREA_RADIUS)
+        return CNDID_FAIL;
+
+    if (inData->AreaCeiling < CN_MIN_ALT || inData->AreaCeiling > CN_MAX_ALT ||
+        inData->AreaFloor < CN_MIN_ALT || inData->AreaFloor > CN_MAX_ALT ||
+        inData->OperatorAltitudeGeo < CN_MIN_ALT || inData->OperatorAltitudeGeo > CN_MAX_ALT)
+        return CNDID_FAIL;
+
+    outEncoded->MessageType = CNDID_MESSAGETYPE_SYSTEM;
+    outEncoded->ProtoVersion = CNDID_PROTOCOL_VERSION;
+    outEncoded->Reserved = 0;
+    outEncoded->CoordType = inData->Coord_Type;
+    outEncoded->OperatorLocationType = inData->OperatorLocationType;
+    outEncoded->ClassificationType = inData->Classification_Type;
+    outEncoded->OperatorLatitude = encodeLatLon(inData->OperatorLatitude);
+    outEncoded->OperatorLongitude = encodeLatLon(inData->OperatorLongitude);
+    outEncoded->AreaCount = inData->AreaCount;
+    outEncoded->AreaRadius = encodeAreaRadius(inData->AreaRadius);
+    outEncoded->AreaCeiling = encodeAltitude(inData->AreaCeiling);
+    outEncoded->AreaFloor = encodeAltitude(inData->AreaFloor);
+    outEncoded->CategoryCN = inData->CategoryCN;
+    outEncoded->ClassCN = inData->ClassCN;
+    outEncoded->OperatorAltitudeGeo = encodeAltitude(inData->OperatorAltitudeGeo);
+    outEncoded->Timestamp = inData->Timestamp;
+    outEncoded->Reserved2 = 0;
+    return CNDID_SUCCESS;
+}
+
+
+/**
+* 检查数据包结构的数据字段是否有效
+*
+* @param msgs   指向包含消息的缓冲区的指针
+* @param amount 数据包中的消息数量
+* @return       CNDID_SUCCESS 或 CNDID_FAIL;
+*/
+static int checkPackContent(CNDID_Message_encoded *msgs, int amount)
+{
+    if (amount <= 0 || amount > CNDID_PACK_MAX_MESSAGES)
+        return CNDID_FAIL;
+    int numMessages[4] = { 0 }; // CNDID_messagetype_t相关部分的计数器
+    for (int i = 0; i < amount; i++) {
+        uint8_t MessageType = decodeCNMessageType(msgs[i].rawData[0]);
+
+        // 检查非法内容。这也避免了之间的递归调用
+        // decodeOpenDroneID()以及decodeMessagePack()/checkPackContent()
+        if (MessageType <= CNDID_MESSAGETYPE_SYSTEM)  // 对待发送组包消息进行格式检查 最后一条消息就是系统报文
+            numMessages[MessageType]++;
+        else
+            return CNDID_FAIL;
+    }
+
+    // 除基本ID和授权外,每条消息最多允许出现一次。
+    if (numMessages[CNDID_MESSAGETYPE_BASIC_ID] > CNDID_BASIC_ID_MAX_MESSAGES ||
+        numMessages[CNDID_MESSAGETYPE_LOCATION] > 1 ||
+        numMessages[CNDID_MESSAGETYPE_SELF_ID] > 1 ||
+        numMessages[CNDID_MESSAGETYPE_SYSTEM] > 1 )
+        return CNDID_FAIL;
+
+    return CNDID_SUCCESS;
+}
+
+/**
+* Encode message pack. I.e. a collection of multiple encoded messages
+*
+* @param outEncoded Output (encoded/packed) structure
+* @param inData     Input data (non encoded/packed) structure
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int encodeCNMessagePack(CNDID_MessagePack_encoded *outEncoded, CNDID_MessagePack_data *inData)
+{
+    if (!outEncoded || !inData || inData->SingleMessageSize != CNDID_MESSAGE_SIZE)
+        return CNDID_FAIL;
+
+    if (checkPackContent(inData->Messages, inData->MsgPackSize) != CNDID_SUCCESS)
+        return CNDID_FAIL;
+
+    outEncoded->MessageType = CNDID_MESSAGETYPE_PACKED;
+    outEncoded->ProtoVersion = CNDID_PROTOCOL_VERSION;
+
+    outEncoded->SingleMessageSize = inData->SingleMessageSize;
+    outEncoded->MsgPackSize = inData->MsgPackSize;
+
+    for (int i = 0; i < inData->MsgPackSize; i++)
+        memcpy(&outEncoded->Messages[i], &inData->Messages[i], CNDID_MESSAGE_SIZE);
+
+    return CNDID_SUCCESS;
+}
+
+/**
+* Dencode direction from Open Drone ID packed message
+*
+* @param Direction_enc encoded direction
+* @param EWDirection East/West direction flag
+* @return direction in degrees (0 - 359)
+*/
+static float decodeDirection(uint8_t Direction_enc, uint8_t EWDirection)
+{
+    if (EWDirection)
+        return (float) Direction_enc + 180;
+    else
+        return (float) Direction_enc;
+}
+
+/**
+* Dencode speed from Open Drone ID packed message
+*
+* @param Speed_enc encoded speed
+* @param mult multiplier flag
+* @return decoded speed in m/s
+*/
+static float decodeSpeedHorizontal(uint8_t Speed_enc, uint8_t mult)
+{
+    if (mult)
+        return ((float) Speed_enc * CN_SPEED_DIV[1]) + (UINT8_MAX * CN_SPEED_DIV[0]);
+    else
+        return (float) Speed_enc * CN_SPEED_DIV[0];
+}
+
+/**
+* Decode Vertical Speed from Open Drone ID Packed Message
+*
+* @param SpeedVertical_enc Encoded Vertical Speed
+* @return decoded Vertical Speed in m/s
+*/
+static float decodeSpeedVertical(int8_t SpeedVertical_enc)
+{
+    return (float) SpeedVertical_enc * CN_VSPEED_DIV;
+}
+
+/**
+* Decode Latitude or Longitude value into a signed Integer CNDID format
+*
+* @param LatLon_enc Either Lat or Lon ecoded int value
+* @return decoded (double) Lat or Lon
+*/
+static double decodeLatLon(int32_t LatLon_enc)
+{
+    return (double) LatLon_enc / CN_LATLON_MULT;
+}
+
+/**
+* Decode Altitude from CNDID packed format
+*
+* @param Alt_enc Encoded Altitude to decode
+* @return decoded Altitude (in meters)
+*/
+static float decodeAltitude(uint16_t Alt_enc)
+{
+    return (float) Alt_enc * CN_ALT_DIV - (float) CN_ALT_ADDER;
+}
+
+/**
+* Decode timestamp data from CNDID packed format
+*
+* @param Seconds_enc Encoded Timestamp
+* @return Decoded timestamp (seconds since the hour)
+*/
+static float decodeTimeStamp(uint16_t Seconds_enc)
+{
+    if (Seconds_enc == CN_INV_TIMESTAMP)
+        return CN_INV_TIMESTAMP;
+    else
+        return (float) Seconds_enc / 10;
+}
+
+/**
+* Decode area radius data from CNDID format
+*
+* This decodes a 1 byte value to the area radius in meters
+*
+* @param Radius_enc Encoded area radius
+* @return The radius of the drone area/swarm in meters
+*/
+static uint16_t decodeAreaRadius(uint8_t Radius_enc)
+{
+    return (uint16_t) ((int) Radius_enc * 10);
+}
+
+/**
+* Get the ID type of the basic ID message
+*
+* @param inEncoded  Input message (encoded/packed) structure
+* @param idType     Output: The ID type of this basic ID message
+* @return           CNDID_SUCCESS or CNDID_FAIL;
+*/
+int getCNBasicIDType(CNDID_BasicID_encoded *inEncoded, enum CNDID_idtype *idType)
+{
+    if (!inEncoded || !idType || inEncoded->MessageType != CNDID_MESSAGETYPE_BASIC_ID)
+        return CNDID_FAIL;
+
+    *idType = (enum CNDID_idtype) inEncoded->IDType;
+    return CNDID_SUCCESS;
+}
+
+/**
+* 从打包消息中解码基本ID数据
+*
+* @param outData   输出:解码后的消息
+* @param inEncoded 输入消息(已编码/打包)结构
+* @return          CNDID_SUCCESS 或 CNDID_FAIL;
+*/
+int decodeCNBasicIDMessage(CNDID_BasicID_data *outData, CNDID_BasicID_encoded *inEncoded)
+{
+    if (!outData || !inEncoded ||
+        inEncoded->MessageType != CNDID_MESSAGETYPE_BASIC_ID ||
+        !intInRange(inEncoded->IDType, 0, 15) ||
+        !intInRange(inEncoded->UAType, 0, 15))
+        return CNDID_FAIL;
+
+    outData->IDType = (CNDID_IDType_t) inEncoded->IDType; 
+    outData->UAType = (CNDID_UAType_t) inEncoded->UAType;
+    safe_dec_copyfill(outData->UASID, inEncoded->UASID, sizeof(outData->UASID));
+    return CNDID_SUCCESS;
+}
+
+
+/**
+* Decode Location data from packed message
+*
+* @param outData   Output: decoded message
+* @param inEncoded Input message (encoded/packed) structure
+* @return          CNDID_SUCCESS or CNDID_FAIL;
+*/
+int decodeCNLocationMessage(CNDID_Location_data *outData, CNDID_Location_encoded *inEncoded)
+{
+    if (!outData || !inEncoded ||
+        inEncoded->MessageType != CNDID_MESSAGETYPE_LOCATION ||
+        !intInRange(inEncoded->Status, 0, 15))
+        return CNDID_FAIL;
+
+    outData->Status = (CNDID_Status_t) inEncoded->Status;
+    outData->Direction = decodeDirection(inEncoded->Direction, inEncoded-> EWDirection);
+    outData->SpeedHorizontal = decodeSpeedHorizontal(inEncoded->SpeedHorizontal, inEncoded->SpeedMult);
+    outData->SpeedVertical = decodeSpeedVertical(inEncoded->SpeedVertical);
+    outData->Latitude = decodeLatLon(inEncoded->Latitude);
+    outData->Longitude = decodeLatLon(inEncoded->Longitude);
+    outData->AltitudeBaro = decodeAltitude(inEncoded->AltitudeBaro);
+    outData->AltitudeGeo = decodeAltitude(inEncoded->AltitudeGeo);
+    outData->HeightType = (CNDID_HeightReference_t) inEncoded->HeightType;
+    outData->Height = decodeAltitude(inEncoded->Height);
+    outData->HorizAccuracy = (CNDID_HorizontalAccuracy_t) inEncoded->HorizAccuracy;
+    outData->VertAccuracy = (CNDID_VerticalAccuracy_t) inEncoded->VertAccuracy;
+    outData->BaroAccuracy = (CNDID_VerticalAccuracy_t) inEncoded->BaroAccuracy;
+    outData->SpeedAccuracy = (CNDID_SpeedAccuracy_t) inEncoded->SpeedAccuracy;
+    outData->TSAccuracy = (CNDID_TimeStampAccuracy_t) inEncoded->TSAccuracy;
+    outData->TimeStamp = decodeTimeStamp(inEncoded->TimeStamp);
+    return CNDID_SUCCESS;
+}
+
+
+
+/**
+* Decode Self ID data from packed message
+*
+* @param outData   Output: decoded message
+* @param inEncoded Input message (encoded/packed) structure
+* @return          CNDID_SUCCESS or CNDID_FAIL;
+*/
+int decodeCNSelfIDMessage(CNDID_SelfID_data *outData, CNDID_SelfID_encoded *inEncoded)
+{
+    if (!outData || !inEncoded ||
+        inEncoded->MessageType != CNDID_MESSAGETYPE_SELF_ID)
+        return CNDID_FAIL;
+
+    outData->DescType = (CNDID_DescType_t) inEncoded->DescType;
+    safe_dec_copyfill(outData->Desc, inEncoded->Desc, sizeof(outData->Desc));
+    return CNDID_SUCCESS;
+}
+
+/**
+* Decode System data from packed message
+*
+* @param outData   Output: decoded message
+* @param inEncoded Input message (encoded/packed) structure
+* @return          CNDID_SUCCESS or CNDID_FAIL;
+*/
+int decodeCNSystemMessage(CNDID_System_data *outData, CNDID_System_encoded *inEncoded)
+{
+    if (!outData || !inEncoded ||
+        inEncoded->MessageType != CNDID_MESSAGETYPE_SYSTEM)
+        return CNDID_FAIL;
+
+    outData->OperatorLocationType =
+        (CNDID_operator_location_type_t) inEncoded->OperatorLocationType;
+    outData->Classification_Type =
+        (CNDID_classification_type_t) inEncoded->ClassificationType;
+    outData->Coord_Type =
+        (CNDID_CoordType_t) inEncoded->CoordType;
+    outData->OperatorLatitude = decodeLatLon(inEncoded->OperatorLatitude);
+    outData->OperatorLongitude = decodeLatLon(inEncoded->OperatorLongitude);
+    outData->AreaCount = inEncoded->AreaCount;
+    outData->AreaRadius = decodeAreaRadius(inEncoded->AreaRadius);
+    outData->AreaCeiling = decodeAltitude(inEncoded->AreaCeiling);
+    outData->AreaFloor = decodeAltitude(inEncoded->AreaFloor);
+    outData->CategoryCN = (CNDID_category_CN_t) inEncoded->CategoryCN;
+    outData->ClassCN = (CNDID_class_CN_t) inEncoded->ClassCN;
+    outData->OperatorAltitudeGeo = decodeAltitude(inEncoded->OperatorAltitudeGeo);
+    outData->Timestamp = inEncoded->Timestamp;
+    return CNDID_SUCCESS;
+}
+
+
+
+/**
+* Decode Message Pack from packed message
+*
+* The various Valid flags in uasData are set true whenever a message has been
+* decoded and the corresponding data structure has been filled. The caller must
+* clear these flags before calling decodeMessagePack().
+*
+* @param uasData Output: Structure containing buffers for all message data
+* @param pack    Pointer to an encoded packed message
+* @return        CNDID_SUCCESS or CNDID_FAIL;
+*/
+int decodeCNMessagePack(CNDID_UAS_Data *uasData, CNDID_MessagePack_encoded *pack)
+{
+    if (!uasData || !pack || pack->MessageType != CNDID_MESSAGETYPE_PACKED)
+        return CNDID_FAIL;
+
+    if (pack->SingleMessageSize != CNDID_MESSAGE_SIZE)
+        return CNDID_FAIL;
+
+    if (checkPackContent(pack->Messages, pack->MsgPackSize) != CNDID_SUCCESS)
+        return CNDID_FAIL;
+
+    for (int i = 0; i < pack->MsgPackSize; i++) {
+        decodeCNDroneID(uasData, pack->Messages[i].rawData);
+    }
+    return CNDID_SUCCESS;
+}
+
+/**
+* Decodes the message type of a packed Open Drone ID message
+*
+* @param byte   The first byte of the message
+* @return       The message type: CNDID_messagetype_t
+*/
+CNDID_MessageType_t decodeCNMessageType(uint8_t byte)
+{
+    switch (byte >> 4)
+    {
+    case CNDID_MESSAGETYPE_BASIC_ID:
+        return CNDID_MESSAGETYPE_BASIC_ID;
+    case CNDID_MESSAGETYPE_LOCATION:
+        return CNDID_MESSAGETYPE_LOCATION;
+    case CNDID_MESSAGETYPE_SELF_ID:
+        return CNDID_MESSAGETYPE_SELF_ID;
+    case CNDID_MESSAGETYPE_SYSTEM:
+        return CNDID_MESSAGETYPE_SYSTEM;
+    case CNDID_MESSAGETYPE_PACKED:
+        return CNDID_MESSAGETYPE_PACKED;
+    default:
+        return CNDID_MESSAGETYPE_INVALID;
+    }
+}
+
+/**
+* Parse encoded Open Drone ID data to identify the message type. Then decode
+* from Open Drone ID packed format into the appropriate Open Drone ID structure
+*
+* This function assumes that msgData points to a buffer containing all
+* CNDID_MESSAGE_SIZE bytes of an Open Drone ID message.
+*
+* The various Valid flags in uasData are set true whenever a message has been
+* decoded and the corresponding data structure has been filled. The caller must
+* clear these flags before calling decodeOpenDroneID().
+*
+* @param uasData    Structure containing buffers for all message data
+* @param msgData    Pointer to a buffer containing a full encoded Open Drone ID
+*                   message
+* @return           The message type: CNDID_messagetype_t
+*/
+CNDID_MessageType_t decodeCNDroneID(CNDID_UAS_Data *uasData, uint8_t *msgData)
+{
+    if (!uasData || !msgData)
+        return CNDID_MESSAGETYPE_INVALID;
+
+    switch (decodeCNMessageType(msgData[0]))
+    {
+    case CNDID_MESSAGETYPE_BASIC_ID: {
+        CNDID_BasicID_encoded *basicId = (CNDID_BasicID_encoded *) msgData;
+        enum CNDID_idtype idType;
+        if (getCNBasicIDType(basicId, &idType) == CNDID_SUCCESS) {
+            // 找到一个空闲位置来存储当前消息,或者覆盖相同类型的旧数据。
+            for (int i = 0; i < CNDID_BASIC_ID_MAX_MESSAGES; i++) {
+                enum CNDID_idtype storedType = uasData->BasicID[i].IDType;
+                if (storedType == CNDID_IDTYPE_NONE || storedType == idType) {
+                    if (decodeCNBasicIDMessage(&uasData->BasicID[i], basicId) == CNDID_SUCCESS) {
+                        uasData->BasicIDValid[i] = 1; // 重复ID ID非法
+                        return CNDID_MESSAGETYPE_BASIC_ID;
+                    }
+                }
+            }
+        }
+        break;
+    }
+    case CNDID_MESSAGETYPE_LOCATION: {
+        CNDID_Location_encoded *location = (CNDID_Location_encoded *) msgData;
+        if (decodeCNLocationMessage(&uasData->Location, location) == CNDID_SUCCESS) {
+            uasData->LocationValid = 1;
+            return CNDID_MESSAGETYPE_LOCATION;
+        }
+        break;
+    }
+    case CNDID_MESSAGETYPE_SELF_ID: {
+        CNDID_SelfID_encoded *selfId = (CNDID_SelfID_encoded *) msgData;
+        if (decodeCNSelfIDMessage(&uasData->SelfID, selfId) == CNDID_SUCCESS) {
+            uasData->SelfIDValid = 1;
+            return CNDID_MESSAGETYPE_SELF_ID;
+        }
+        break;
+    }
+    case CNDID_MESSAGETYPE_SYSTEM: {
+        CNDID_System_encoded *system = (CNDID_System_encoded *) msgData;
+        if (decodeCNSystemMessage(&uasData->System, system) == CNDID_SUCCESS) {
+            uasData->SystemValid = 1;
+            return CNDID_MESSAGETYPE_SYSTEM;
+        }
+        break;
+    }
+   
+    case CNDID_MESSAGETYPE_PACKED: {
+        CNDID_MessagePack_encoded *pack = (CNDID_MessagePack_encoded *) msgData;
+        if (decodeCNMessagePack(uasData, pack) == CNDID_SUCCESS)
+            return CNDID_MESSAGETYPE_PACKED;
+        break;
+    }
+    default:
+        break;
+    }
+
+    return CNDID_MESSAGETYPE_INVALID;
+}
+
+/**
+* Safely fill then copy string to destination (when decoding)
+*
+* This prevents overrun and guarantees copy behavior (fully null padded)
+* This function was specially made because the encoded data may not be null
+* terminated (if full size).
+* Therefore, the destination must use the last byte for a null (and is +1 in size)
+*
+* @param dstStr Destination string
+* @param srcStr Source string
+* @param dstSize Destination size
+*/
+static char *safe_dec_copyfill(char *dstStr, const char *srcStr, int dstSize)
+{
+    memset(dstStr, 0, dstSize);  // fills destination with nulls
+    strncpy(dstStr, srcStr, dstSize-1); // copy only up to dst size-1 (no overruns)
+    return dstStr;
+}
+
+/**
+* Safely range check a value and return the minimum or max within the range if exceeded
+*
+* @param inValue Value to range-check
+* @param startRange Start of range to compare
+* @param endRange End of range to compare
+* @return same value if it fits, otherwise, min or max of range as appropriate.
+*/
+static int intRangeMax(int64_t inValue, int startRange, int endRange) {
+    if ( inValue < startRange ) {
+        return startRange;
+    } else if (inValue > endRange) {
+        return endRange;
+    } else {
+        return (int) inValue;
+    }
+}
+
+/**
+ * Determine if an Int is in range
+ *
+ * @param inValue Value to range-check
+ * @param startRange Start of range to compare
+ * @param endRange End of range to compare
+ * @return 1 = yes, 0 = no
+ */
+static int intInRange(int inValue, int startRange, int endRange)
+{
+    if (inValue < startRange || inValue > endRange) {
+        return 0;
+    } else {
+        return 1;
+    }
+}
+
+/**
+* This converts a horizontal accuracy float value to the corresponding enum
+*
+* @param Accuracy The horizontal accuracy in meters
+* @return Enum value representing the accuracy
+*/
+CNDID_HorizontalAccuracy_t createCNEnumHorizontalAccuracy(float Accuracy)
+{
+    if (Accuracy >= 18520)
+        return CNDID_HOR_ACC_UNKNOWN;
+    else if (Accuracy >= 7408)
+        return CNDID_HOR_ACC_10NM;
+    else if (Accuracy >= 3704)
+        return CNDID_HOR_ACC_4NM;
+    else if (Accuracy >= 1852)
+        return CNDID_HOR_ACC_2NM;
+    else if (Accuracy >= 926)
+        return CNDID_HOR_ACC_1NM;
+    else if (Accuracy >= 555.6f)
+        return CNDID_HOR_ACC_0_5NM;
+    else if (Accuracy >= 185.2f)
+        return CNDID_HOR_ACC_0_3NM;
+    else if (Accuracy >= 92.6f)
+        return CNDID_HOR_ACC_0_1NM;
+    else if (Accuracy >= 30)
+        return CNDID_HOR_ACC_0_05NM;
+    else if (Accuracy >= 10)
+        return CNDID_HOR_ACC_30_METER;
+    else if (Accuracy >= 3)
+        return CNDID_HOR_ACC_10_METER;
+    else if (Accuracy >= 1)
+        return CNDID_HOR_ACC_3_METER;
+    else if (Accuracy > 0)
+        return CNDID_HOR_ACC_1_METER;
+    else
+        return CNDID_HOR_ACC_UNKNOWN;
+}
+
+/**
+* This converts a vertical accuracy float value to the corresponding enum
+*
+* @param Accuracy The vertical accuracy in meters
+* @return Enum value representing the accuracy
+*/
+CNDID_VerticalAccuracy_t createCNEnumVerticalAccuracy(float Accuracy)
+{
+    if (Accuracy >= 150)
+        return CNDID_VER_ACC_UNKNOWN;
+    else if (Accuracy >= 45)
+        return CNDID_VER_ACC_150_METER;
+    else if (Accuracy >= 25)
+        return CNDID_VER_ACC_45_METER;
+    else if (Accuracy >= 10)
+        return CNDID_VER_ACC_25_METER;
+    else if (Accuracy >= 3)
+        return CNDID_VER_ACC_10_METER;
+    else if (Accuracy >= 1)
+        return CNDID_VER_ACC_3_METER;
+    else if (Accuracy > 0)
+        return CNDID_VER_ACC_1_METER;
+    else
+        return CNDID_VER_ACC_UNKNOWN;
+}
+
+/**
+* This converts a speed accuracy float value to the corresponding enum
+*
+* @param Accuracy The speed accuracy in m/s
+* @return Enum value representing the accuracy
+*/
+CNDID_SpeedAccuracy_t createCNEnumSpeedAccuracy(float Accuracy)
+{
+    if (Accuracy >= 10)
+        return CNDID_SPEED_ACC_UNKNOWN;
+    else if (Accuracy >= 3)
+        return CNDID_SPEED_ACC_10_METERS_PER_SECOND;
+    else if (Accuracy >= 1)
+        return CNDID_SPEED_ACC_3_METERS_PER_SECOND;
+    else if (Accuracy >= 0.3f)
+        return CNDID_SPEED_ACC_1_METERS_PER_SECOND;
+    else if (Accuracy > 0)
+        return CNDID_SPEED_ACC_0_3_METERS_PER_SECOND;
+    else
+        return CNDID_SPEED_ACC_UNKNOWN;
+}
+
+/**
+* This converts a timestamp accuracy float value to the corresponding enum
+*
+* @param Accuracy The timestamp accuracy in seconds
+* @return Enum value representing the accuracy
+*/
+CNDID_TimeStampAccuracy_t createCNEnumTimestampAccuracy(float Accuracy)
+{
+    if (Accuracy > 1.5f)
+        return CNDID_TIME_ACC_UNKNOWN;
+    else if (Accuracy > 1.4f)
+        return CNDID_TIME_ACC_1_5_SECOND;
+    else if (Accuracy > 1.3f)
+        return CNDID_TIME_ACC_1_4_SECOND;
+    else if (Accuracy > 1.2f)
+        return CNDID_TIME_ACC_1_3_SECOND;
+    else if (Accuracy > 1.1f)
+        return CNDID_TIME_ACC_1_2_SECOND;
+    else if (Accuracy > 1.0f)
+        return CNDID_TIME_ACC_1_1_SECOND;
+    else if (Accuracy > 0.9f)
+        return CNDID_TIME_ACC_1_0_SECOND;
+    else if (Accuracy > 0.8f)
+        return CNDID_TIME_ACC_0_9_SECOND;
+    else if (Accuracy > 0.7f)
+        return CNDID_TIME_ACC_0_8_SECOND;
+    else if (Accuracy > 0.6f)
+        return CNDID_TIME_ACC_0_7_SECOND;
+    else if (Accuracy > 0.5f)
+        return CNDID_TIME_ACC_0_6_SECOND;
+    else if (Accuracy > 0.4f)
+        return CNDID_TIME_ACC_0_5_SECOND;
+    else if (Accuracy > 0.3f)
+        return CNDID_TIME_ACC_0_4_SECOND;
+    else if (Accuracy > 0.2f)
+        return CNDID_TIME_ACC_0_3_SECOND;
+    else if (Accuracy > 0.1f)
+        return CNDID_TIME_ACC_0_2_SECOND;
+    else if (Accuracy > 0.0f)
+        return CNDID_TIME_ACC_0_1_SECOND;
+    else
+        return CNDID_TIME_ACC_UNKNOWN;
+}
+
+/**
+* This decodes a horizontal accuracy enum to the corresponding float value
+*
+* @param Accuracy Enum value representing the accuracy
+* @return The maximum horizontal accuracy in meters
+*/
+float decodeCNHorizontalAccuracy(CNDID_HorizontalAccuracy_t Accuracy)
+{
+    switch (Accuracy)
+    {
+    case CNDID_HOR_ACC_UNKNOWN:
+        return 18520;
+    case CNDID_HOR_ACC_10NM:
+        return 18520;
+    case CNDID_HOR_ACC_4NM:
+        return 7808;
+    case CNDID_HOR_ACC_2NM:
+        return 3704;
+    case CNDID_HOR_ACC_1NM:
+        return 1852;
+    case CNDID_HOR_ACC_0_5NM:
+        return 926;
+    case CNDID_HOR_ACC_0_3NM:
+        return 555.6f;
+    case CNDID_HOR_ACC_0_1NM:
+        return 185.2f;
+    case CNDID_HOR_ACC_0_05NM:
+        return 92.6f;
+    case CNDID_HOR_ACC_30_METER:
+        return 30;
+    case CNDID_HOR_ACC_10_METER:
+        return 10;
+    case CNDID_HOR_ACC_3_METER:
+        return 3;
+    case CNDID_HOR_ACC_1_METER:
+        return 1;
+    default:
+        return 18520;
+    }
+}
+
+/**
+* This decodes a vertical accuracy enum to the corresponding float value
+*
+* @param Accuracy Enum value representing the accuracy
+* @return The maximum vertical accuracy in meters
+*/
+float decodeCNVerticalAccuracy(CNDID_VerticalAccuracy_t Accuracy)
+{
+    switch (Accuracy)
+    {
+    case CNDID_VER_ACC_UNKNOWN:
+        return 150;
+    case CNDID_VER_ACC_150_METER:
+        return 150;
+    case CNDID_VER_ACC_45_METER:
+        return 45;
+    case CNDID_VER_ACC_25_METER:
+        return 25;
+    case CNDID_VER_ACC_10_METER:
+        return 10;
+    case CNDID_VER_ACC_3_METER:
+        return 3;
+    case CNDID_VER_ACC_1_METER:
+        return 1;
+    default:
+        return 150;
+    }
+}
+
+/**
+* This decodes a speed accuracy enum to the corresponding float value
+*
+* @param Accuracy Enum value representing the accuracy
+* @return The maximum speed accuracy in m/s
+*/
+float decodeCNSpeedAccuracy(CNDID_SpeedAccuracy_t Accuracy)
+{
+    switch (Accuracy)
+    {
+    case CNDID_SPEED_ACC_UNKNOWN:
+        return 10;
+    case CNDID_SPEED_ACC_10_METERS_PER_SECOND:
+        return 10;
+    case CNDID_SPEED_ACC_3_METERS_PER_SECOND:
+        return 3;
+    case CNDID_SPEED_ACC_1_METERS_PER_SECOND:
+        return 1;
+    case CNDID_SPEED_ACC_0_3_METERS_PER_SECOND:
+        return 0.3f;
+    default:
+        return 10;
+    }
+}
+
+/**
+* This decodes a timestamp accuracy enum to the corresponding float value
+*
+* @param Accuracy Enum value representing the accuracy
+* @return The maximum timestamp accuracy in seconds
+*/
+float decodeCNTimestampAccuracy(CNDID_TimeStampAccuracy_t Accuracy)
+{
+    switch (Accuracy)
+    {
+    case CNDID_TIME_ACC_UNKNOWN:
+        return 0.0f;
+    case CNDID_TIME_ACC_0_1_SECOND:
+        return 0.1f;
+    case CNDID_TIME_ACC_0_2_SECOND:
+        return 0.2f;
+    case CNDID_TIME_ACC_0_3_SECOND:
+        return 0.3f;
+    case CNDID_TIME_ACC_0_4_SECOND:
+        return 0.4f;
+    case CNDID_TIME_ACC_0_5_SECOND:
+        return 0.5f;
+    case CNDID_TIME_ACC_0_6_SECOND:
+        return 0.6f;
+    case CNDID_TIME_ACC_0_7_SECOND:
+        return 0.7f;
+    case CNDID_TIME_ACC_0_8_SECOND:
+        return 0.8f;
+    case CNDID_TIME_ACC_0_9_SECOND:
+        return 0.9f;
+    case CNDID_TIME_ACC_1_0_SECOND:
+        return 1.0f;
+    case CNDID_TIME_ACC_1_1_SECOND:
+        return 1.1f;
+    case CNDID_TIME_ACC_1_2_SECOND:
+        return 1.2f;
+    case CNDID_TIME_ACC_1_3_SECOND:
+        return 1.3f;
+    case CNDID_TIME_ACC_1_4_SECOND:
+        return 1.4f;
+    case CNDID_TIME_ACC_1_5_SECOND:
+        return 1.5f;
+    default:
+        return 0.0f;
+    }
+}
+
+#ifndef CNDID_DISABLE_PRINTF
+
+/**
+* Print array of bytes as a hex string
+*
+* @param byteArray Array of bytes to be printed
+* @param asize Size of array of bytes to be printed
+*/
+
+void PrintByteArray(uint8_t *byteArray, uint16_t asize, int spaced)
+{
+    if (ENABLE_DEBUG) {
+        int x;
+        for (x=0;x<asize;x++) {
+            printf("%02x", (unsigned int) byteArray[x]);
+            if (spaced) {
+                printf(" ");
+            }
+        }
+        printf("\n");
+    }
+}
+
+/**
+* Print formatted BasicID Data
+*
+* @param BasicID structure to be printed
+*/
+void PrintBasicID_data(CNDID_BasicID_data *BasicID)
+{
+    // Ensure the ID is null-terminated
+    char buf[CNDID_ID_SIZE + 1] = { 0 };
+    memcpy(buf, BasicID->UASID, CNDID_ID_SIZE);
+
+    const char CNDID_BasicID_data_format[] =
+        "UAType: %d\nIDType: %d\nUASID: %s\n";
+    printf(CNDID_BasicID_data_format, BasicID->IDType, BasicID->UAType, buf);
+}
+
+/**
+* Print formatted Location Data
+*
+* @param Location structure to be printed
+*/
+void PrintLocation_data(CNDID_Location_data *Location)
+{
+    const char CNDID_Location_data_format[] =
+        "Status: %d\nDirection: %.1f\nSpeedHori: %.2f\nSpeedVert: "\
+        "%.2f\nLat/Lon: %.7f, %.7f\nAlt: Baro, Geo, Height above %s: %.2f, "\
+        "%.2f, %.2f\nHoriz, Vert, Baro, Speed, TS Accuracy: %.1f, %.1f, %.1f, "\
+        "%.1f, %.1f\nTimeStamp: %.2f\n";
+    printf(CNDID_Location_data_format, Location->Status,
+        (double) Location->Direction, (double) Location->SpeedHorizontal,
+        (double) Location->SpeedVertical, Location->Latitude,
+        Location->Longitude, Location->HeightType ? "Ground" : "TakeOff",
+        (double) Location->AltitudeBaro, (double) Location->AltitudeGeo,
+        (double) Location->Height,
+        (double) decodeCNHorizontalAccuracy(Location->HorizAccuracy),
+        (double) decodeCNVerticalAccuracy(Location->VertAccuracy),
+        (double) decodeCNVerticalAccuracy(Location->BaroAccuracy),
+        (double) decodeCNSpeedAccuracy(Location->SpeedAccuracy),
+        (double) decodeCNTimestampAccuracy(Location->TSAccuracy),
+        (double) Location->TimeStamp);
+}
+
+
+/**
+* Print formatted SelfID Data
+*
+* @param SelfID structure to be printed
+*/
+void PrintSelfID_data(CNDID_SelfID_data *SelfID)
+{
+    // Ensure the description is null-terminated
+    char buf[CNDID_STR_SIZE + 1] = { 0 };
+    memcpy(buf, SelfID->Desc, CNDID_STR_SIZE);
+
+    const char CNDID_SelfID_data_format[] = "DescType: %d\nDesc: %s\n";
+    printf(CNDID_SelfID_data_format, SelfID->DescType, buf);
+}
+
+/**
+* Print formatted System Data
+*
+* @param System_data structure to be printed
+*/
+void PrintSystem_data(CNDID_System_data *System_data)
+{
+    const char CNDID_System_data_format[] = "Operator Location Type: %d\n"
+        "Classification Type: %d\nLat/Lon: %.7f, %.7f\n"
+        "Area Count, Radius, Ceiling, Floor: %d, %d, %.2f, %.2f\n"
+        "Category EU: %d, Class EU: %d, Altitude: %.2f, Timestamp: %u\n";
+    printf(CNDID_System_data_format, System_data->OperatorLocationType,
+        System_data->Classification_Type,
+        System_data->OperatorLatitude, System_data->OperatorLongitude,
+        System_data->AreaCount, System_data->AreaRadius,
+        (double) System_data->AreaCeiling, (double) System_data->AreaFloor,
+        System_data->CategoryCN, System_data->ClassCN,
+        (double) System_data->OperatorAltitudeGeo, System_data->Timestamp);
+}
+
+#endif // CNDID_DISABLE_PRINTF

+ 562 - 0
RemoteIDModule/cndroneid.h

@@ -0,0 +1,562 @@
+/*
+Copyright (C) 2019 Intel Corporation
+
+SPDX-License-Identifier: Apache-2.0
+
+Open Drone ID C Library
+
+Maintainer:
+Gabriel Cox
+gabriel.c.cox@intel.com
+*/
+/*整体来看国标是开源标准的阉割板 系统报文略有区别 缺少认证报文、操作源ID识别报文*/
+/*民航轻微小型无人驾驶航空器试运行*/
+#pragma once
+
+#include <stdint.h>
+#include <string.h>
+
+#define CNDID_MESSAGE_SIZE 25 // 单报文字节大小
+#define CNDID_ID_SIZE 20   // USA ID 长度
+#define CNDID_STR_SIZE 23 // 描述字符串长度
+
+#define CNDID_PROTOCOL_VERSION 1 // UAS 报文版本
+
+
+#ifndef CNDID_BASIC_ID_MAX_MESSAGES
+#define CNDID_BASIC_ID_MAX_MESSAGES 2 // 可手动设置ID个数
+#endif
+#if (CNDID_BASIC_ID_MAX_MESSAGES < 1) || (CNDID_BASIC_ID_MAX_MESSAGES > 5)
+#error "CNDID_BASIC_ID_MAX_MESSAGES must be between 1 and 5."
+#endif
+
+#define CNDID_PACK_MAX_MESSAGES 10 // 最多打包10条报文
+
+#define CNDID_SUCCESS    0
+#define CNDID_FAIL       1
+
+#define CN_MIN_DIR         0       // Minimum direction
+#define CN_MAX_DIR         360     // Maximum direction
+#define CN_INV_DIR         361     // Invalid direction
+#define CN_MIN_SPEED_H     0       // Minimum speed horizontal
+#define CN_MAX_SPEED_H     254.25f // Maximum speed horizontal
+#define CN_INV_SPEED_H     255     // Invalid speed horizontal
+#define CN_MIN_SPEED_V     (-62)   // Minimum speed vertical
+#define CN_MAX_SPEED_V     62      // Maximum speed vertical
+#define CN_INV_SPEED_V     63      // Invalid speed vertical
+#define CN_MIN_LAT         (-90)   // Minimum latitude
+#define CN_MAX_LAT         90      // Maximum latitude
+#define CN_MIN_LON         (-180)  // Minimum longitude
+#define CN_MAX_LON         180     // Maximum longitude
+#define CN_MIN_ALT         (-1000) // Minimum altitude
+#define CN_MAX_ALT         31767.5f// Maximum altitude
+#define CN_INV_ALT         CN_MIN_ALT // Invalid altitude
+#define CN_MAX_TIMESTAMP   (60 * 60)
+#define CN_INV_TIMESTAMP   0xFFFF  // Invalid, No Value or Unknown Timestamp
+#define CN_MAX_AREA_RADIUS 2550
+
+
+#define CN_COORD_TYPE 0
+// #define COORDTYPE 1
+// #define COORDTYPE 2
+// #define COORDTYPE 3
+
+// 消息类型枚举
+typedef enum CNDID_messagetype {
+    CNDID_MESSAGETYPE_BASIC_ID = 0,
+    CNDID_MESSAGETYPE_LOCATION = 1,
+    // CNDID_MESSAGETYPE_RVS1 = 2,
+    CNDID_MESSAGETYPE_SELF_ID = 3,
+    CNDID_MESSAGETYPE_SYSTEM = 4,
+    // CNDID_MESSAGETYPE_RVS2 = 5,
+    CNDID_MESSAGETYPE_PACKED = 0xF,
+    CNDID_MESSAGETYPE_INVALID = 0xFF,
+} CNDID_MessageType_t;
+
+// 每种消息类型都必须维护其自身的消息uint8_t计数器。
+// 如果消息内容发生变化,该计数器必须递增。对于相同消息内容的重复传输,
+// 计数器的递增是可选的。
+typedef enum CNDID_msg_counter {
+    CNDID_MSG_COUNTER_BASIC_ID = 0,
+    CNDID_MSG_COUNTER_LOCATION = 1,
+    // CNDID_MSG_COUNTER_RVS1 = 2,
+    CNDID_MSG_COUNTER_SELF_ID = 3,
+    CNDID_MSG_COUNTER_SYSTEM = 4,
+    // CNDID_MSG_COUNTER_RVS2 = 5,
+    CNDID_MSG_COUNTER_PACKED = 6,
+    CNDID_MSG_COUNTER_AMOUNT = 7,
+} CNDID_MsgCounter_t;
+/***************************************0x0 ID报文*******************************************/
+//  ID类型 ASTMF3411-22a标准的表5
+typedef enum CNDID_idtype {
+    CNDID_IDTYPE_NONE = 0,
+    CNDID_IDTYPE_SERIAL_NUMBER = 1,
+    CNDID_IDTYPE_CAA_REGISTRATION_ID = 2, // 民航局
+    CNDID_IDTYPE_UTM_ASSIGNED_UUID = 3,   // 无人机系统(UAS,即无人驾驶航空器系统)交通管理
+    CNDID_IDTYPE_SPECIFIC_SESSION_ID = 4, // 确切的id类型由UASID的第一个字节指定,这些类型
+                                         // 这些值由国际民用航空组织(ICAO)管理。0 被保留。1 - 224 由国际民用航空组织(ICAO)管理。
+                                         // 225 - 255 仅可用于私人实验用途
+    // 5 to 15 reserved
+} CNDID_IDType_t;
+// UA 类型
+typedef enum CNDID_uatype {
+    CNDID_UATYPE_NONE = 0,
+    CNDID_UATYPE_AEROPLANE = 1, // Fixed wing
+    CNDID_UATYPE_HELICOPTER_OR_MULTIROTOR = 2,
+    CNDID_UATYPE_GYROPLANE = 3,
+    CNDID_UATYPE_HYBRID_LIFT = 4, // Fixed wing aircraft that can take off vertically
+    CNDID_UATYPE_ORNITHOPTER = 5,
+    CNDID_UATYPE_GLIDER = 6,
+    CNDID_UATYPE_KITE = 7,
+    CNDID_UATYPE_FREE_BALLOON = 8,
+    CNDID_UATYPE_CAPTIVE_BALLOON = 9,
+    CNDID_UATYPE_AIRSHIP = 10, // Such as a blimp
+    CNDID_UATYPE_FREE_FALL_PARACHUTE = 11, // Unpowered
+    CNDID_UATYPE_ROCKET = 12,
+    CNDID_UATYPE_TETHERED_POWERED_AIRCRAFT = 13,
+    CNDID_UATYPE_GROUND_OBSTACLE = 14,
+    CNDID_UATYPE_OTHER = 15,
+} CNDID_UAType_t;
+
+typedef struct CNDID_BasicID_data {
+    CNDID_UAType_t UAType;
+    CNDID_IDType_t IDType;
+    char UASID[CNDID_ID_SIZE+1]; // 额外的字节用于在标准形式中容纳空终止符。用NULL填充未使用的空间
+} CNDID_BasicID_data;
+
+/**
+* @Name CNDID_PackedStructs
+* 为广播准备的压缩数据结构
+* 最好不要直接访问这些数据。请使用编码器/解码器。
+*/
+typedef struct __attribute__((__packed__)) CNDID_BasicID_encoded {
+    // Byte 0 [MessageType][ProtoVersion]  -- must define LSb first
+    uint8_t ProtoVersion: 4;
+    uint8_t MessageType : 4;
+    // Byte 1 [IDType][UAType]  -- must define LSb first
+    uint8_t UAType: 4;
+    uint8_t IDType: 4;
+
+    // Bytes 2-21
+    char UASID[CNDID_ID_SIZE];
+
+    // 22-23
+    char Reserved[3];
+} CNDID_BasicID_encoded;
+/***************************************0x1 向量报文*******************************************/
+// 状态  ASTMF3411-22a标准的表6
+typedef enum CNDID_status {
+    CNDID_STATUS_UNDECLARED = 0,
+    CNDID_STATUS_GROUND = 1,
+    CNDID_STATUS_AIRBORNE = 2,
+    CNDID_STATUS_EMERGENCY = 3,
+    CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
+    // 3 to 15 reserved
+} CNDID_Status_t;
+// 高度类型
+typedef enum CNDID_Height_reference {
+    CNDID_HEIGHT_REF_OVER_TAKEOFF = 0,
+    CNDID_HEIGHT_REF_OVER_GROUND = 1,
+} CNDID_HeightReference_t;
+// 水平精度
+typedef enum CNDID_Horizontal_accuracy {
+    CNDID_HOR_ACC_UNKNOWN = 0,
+    CNDID_HOR_ACC_10NM = 1,      // Nautical Miles. 18.52 km
+    CNDID_HOR_ACC_4NM = 2,       // 7.408 km
+    CNDID_HOR_ACC_2NM = 3,       // 3.704 km
+    CNDID_HOR_ACC_1NM = 4,       // 1.852 km
+    CNDID_HOR_ACC_0_5NM = 5,     // 926 m
+    CNDID_HOR_ACC_0_3NM = 6,     // 555.6 m
+    CNDID_HOR_ACC_0_1NM = 7,     // 185.2 m
+    CNDID_HOR_ACC_0_05NM = 8,    // 92.6 m
+    CNDID_HOR_ACC_30_METER = 9,
+    CNDID_HOR_ACC_10_METER = 10,
+    CNDID_HOR_ACC_3_METER = 11,
+    CNDID_HOR_ACC_1_METER = 12,
+    // 13 to 15 reserved
+} CNDID_HorizontalAccuracy_t;
+// 垂直精度
+typedef enum CNDID_Vertical_accuracy {
+    CNDID_VER_ACC_UNKNOWN = 0,
+    CNDID_VER_ACC_150_METER = 1,
+    CNDID_VER_ACC_45_METER = 2,
+    CNDID_VER_ACC_25_METER = 3,
+    CNDID_VER_ACC_10_METER = 4,
+    CNDID_VER_ACC_3_METER = 5,
+    CNDID_VER_ACC_1_METER = 6,
+    // 7 to 15 reserved
+} CNDID_VerticalAccuracy_t;
+// 速度精度
+typedef enum CNDID_Speed_accuracy {
+    CNDID_SPEED_ACC_UNKNOWN = 0,
+    CNDID_SPEED_ACC_10_METERS_PER_SECOND = 1,
+    CNDID_SPEED_ACC_3_METERS_PER_SECOND = 2,
+    CNDID_SPEED_ACC_1_METERS_PER_SECOND = 3,
+    CNDID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
+    // 5 to 15 reserved
+} CNDID_SpeedAccuracy_t;
+// 时间戳精度
+typedef enum CNDID_Timestamp_accuracy {
+    CNDID_TIME_ACC_UNKNOWN = 0,
+    CNDID_TIME_ACC_0_1_SECOND = 1,
+    CNDID_TIME_ACC_0_2_SECOND = 2,
+    CNDID_TIME_ACC_0_3_SECOND = 3,
+    CNDID_TIME_ACC_0_4_SECOND = 4,
+    CNDID_TIME_ACC_0_5_SECOND = 5,
+    CNDID_TIME_ACC_0_6_SECOND = 6,
+    CNDID_TIME_ACC_0_7_SECOND = 7,
+    CNDID_TIME_ACC_0_8_SECOND = 8,
+    CNDID_TIME_ACC_0_9_SECOND = 9,
+    CNDID_TIME_ACC_1_0_SECOND = 10,
+    CNDID_TIME_ACC_1_1_SECOND = 11,
+    CNDID_TIME_ACC_1_2_SECOND = 12,
+    CNDID_TIME_ACC_1_3_SECOND = 13,
+    CNDID_TIME_ACC_1_4_SECOND = 14,
+    CNDID_TIME_ACC_1_5_SECOND = 15,
+} CNDID_TimeStampAccuracy_t;
+
+typedef struct CNDID_Location_data {
+    CNDID_Status_t Status;    // 状态
+    float Direction;          // 度数。0 ≤ x < 360。基于真北的航线航向。无效、无值或未知:361度
+    float SpeedHorizontal;    // 米/秒。仅为正值。无效、无值或未知:255米/秒。如果速度≥254.25米/秒:254.25米/秒
+    float SpeedVertical;      // 米/秒。无效、无值或未知:63米/秒。如果速度≥62米/秒:62米/秒
+    double Latitude;          // 无效、无值或未知:0度(纬度/经度均为0度)
+    double Longitude;         // 无效、无值或未知:0度(纬度/经度均为0度)
+    float AltitudeBaro;       // 米(参考值29.92英寸汞柱,1013.24毫巴)。无效、无值或未知:-1000米
+    float AltitudeGeo;        // 米(WGS84 - HAE)。无效、无值或未知:-1000米
+    CNDID_HeightReference_t HeightType;
+    float Height;             // 米。无效、无值或未知:-1000米
+    CNDID_HorizontalAccuracy_t HorizAccuracy;
+    CNDID_VerticalAccuracy_t VertAccuracy;
+    CNDID_VerticalAccuracy_t BaroAccuracy;
+    CNDID_SpeedAccuracy_t SpeedAccuracy;
+    CNDID_TimeStampAccuracy_t TSAccuracy;
+    float TimeStamp;          // 相对于UTC的整点过后的秒数。无效、无值或未知:0xFFFF
+} CNDID_Location_data;
+// byte 0 是报头
+typedef struct __attribute__((__packed__)) CNDID_Location_encoded {
+    // Byte 0 [MessageType][ProtoVersion]  -- must define LSb first
+    uint8_t ProtoVersion: 4;
+    uint8_t MessageType : 4;
+    // Byte 1  -- 必须先定义 低位
+    uint8_t SpeedMult: 1; 
+    uint8_t EWDirection: 1;
+    uint8_t HeightType: 1;
+    uint8_t Reserved: 1;
+    uint8_t Status: 4;
+
+    // Bytes 2-17
+    uint8_t Direction;
+    uint8_t SpeedHorizontal;
+    int8_t SpeedVertical;
+    int32_t Latitude;
+    int32_t Longitude;
+    uint16_t AltitudeBaro;
+    uint16_t AltitudeGeo;
+    uint16_t Height;
+
+    // Byte 19 [VertAccuracy][HorizAccuracy]  -- must define LSb first 国标的PDF这里有错误
+    uint8_t HorizAccuracy:4;
+    uint8_t VertAccuracy:4;
+
+    // Byte 20 [BaroAccuracy][SpeedAccuracy]  -- must define LSb first
+    uint8_t SpeedAccuracy:4;
+    uint8_t BaroAccuracy:4;
+
+    // Byte 21-22
+    uint16_t TimeStamp;
+
+    // Byte 23 [Reserved2][TSAccuracy]  -- must define LSb first
+    uint8_t TSAccuracy:4;
+    uint8_t Reserved2:4;
+
+    // Byte 24
+    char Reserved3;
+} CNDID_Location_encoded;
+/***************************************0x3 运行描述报文*******************************************/
+// 行为描述 0x3报文 可选
+typedef enum {
+    CNDID_OPERATOR_ID = 0, // 文字描述
+    // 1 to 200 reserved
+    // 201 to 255 available for private use
+} CNDID_DescType_t;
+
+typedef struct CNDID_SelfID_data {
+    CNDID_DescType_t DescType;
+    char Desc[CNDID_STR_SIZE+1]; // 额外的字节用于在标准形式中容纳空终止符。用NULL填充未使用的空间。
+} CNDID_SelfID_data;
+// 字节0是报文头
+typedef struct __attribute__((__packed__)) CNDID_SelfID_encoded {
+    // Byte 0 [MessageType][ProtoVersion]  -- must define LSb first
+    uint8_t ProtoVersion: 4;
+    uint8_t MessageType : 4;
+    // Byte 1
+    uint8_t DescType;
+
+    // Byte 2-24
+    char Desc[CNDID_STR_SIZE];
+} CNDID_SelfID_encoded;
+/***************************************0x4 系统报文*******************************************/
+
+// 坐标系类型
+typedef enum {
+    CNDID_COORD_TYPE_WGS84    = 0x00,  // 00:WGS-84坐标系(GPS/北斗通用,国标默认)
+    CNDID_COORD_TYPE_GCJ02    = 0x01,  // 01:GCJ-02火星坐标系(中国国测局加密)
+    CNDID_COORD_TYPE_BD09     = 0x02,  // 10:BD-09坐标系(北斗专用)
+    CNDID_COORD_TYPE_CGCS2000 = 0x03,  // 11:CGCS2000国家大地坐标系(中国新一代)
+} CNDID_CoordType_t;
+// 等级分类归属区域
+typedef enum  {
+    CNDID_CLASSIFICATION_TYPE_UNDECLARED = 0,
+    CNDID_CLASSIFICATION_TYPE_EU = 1, // European Union
+    CNDID_CLASSIFICATION_TYPE_CN = 2, // 中国
+    // 2 to 7 reserved
+} CNDID_classification_type_t;
+// 控制站位置类型
+typedef enum CNDID_operator_location_type {
+    CNDID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,   // Takeoff location and altitude
+    CNDID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1, // Dynamic/Live location and altitude
+    CNDID_OPERATOR_LOCATION_TYPE_FIXED = 2,     // Fixed location and altitude
+    // 3 to 255 reserved
+} CNDID_operator_location_type_t;
+
+// UA运行类别定义
+typedef enum {
+    CNDID_CATA_CN_UNDEFINED = 0x00,      // 未定义
+    CNDID_CATA_CN_OPEN = 0x01,           // 开放类
+    CNDID_CATA_CN_SPECIAL = 0x02,        // 特许类
+    CNDID_CATA_CN_CERTIFIED = 0x03       // 审定类
+} CNDID_category_CN_t;
+// 无人机等级
+typedef enum {
+    CNDID_CLASS_CN_MICRO = 0,     // 微型无人机
+    CNDID_CLASS_CN_LIGHT = 1,     // 轻型无人机
+    CNDID_CLASS_CN_SMALL = 2,      // 小型无人机
+    CNDID_CLASS_CN_IDF_OTHER = 3,  // 可识别的其他类型
+
+} CNDID_class_CN_t;
+
+typedef struct CNDID_System_data {
+
+    CNDID_CoordType_t Coord_Type; // 坐标系类型 多出来的 国际是保留的
+    CNDID_classification_type_t Classification_Type; // 所属区域
+    CNDID_operator_location_type_t OperatorLocationType; // 控制站位置类型
+    double OperatorLatitude;  // 无效、无值或未知:0度(纬度/经度均为0度)
+    double OperatorLongitude; // 无效、无值或未知:0度(纬度/经度均为0度)
+    uint16_t AreaCount;       // 默认值 1
+    uint16_t AreaRadius;      // 米。默认值为0
+    float AreaCeiling;        // 米。无效、无值或未知:-1000米
+    float AreaFloor;          // 米。无效、无值或未知:-1000米
+    CNDID_category_CN_t CategoryCN; // 仅在ClassificationType = CNDID_CLASSIFICATION_TYPE_CN 时填写
+    CNDID_class_CN_t ClassCN;       // 仅在ClassificationType = CNDID_CLASSIFICATION_TYPE_CN 时填写
+    float OperatorAltitudeGeo; // 米(WGS84-HAE)。无效、无值或未知:-1000米
+    uint32_t Timestamp;       // 相对于2019年1月1日世界标准时间/ Unix时间00:00:00
+} CNDID_System_data;
+// byte 0 是报头
+typedef struct __attribute__((__packed__)) CNDID_System_encoded {
+    // Byte 0 [MessageType][ProtoVersion]  -- must define LSb first
+    uint8_t ProtoVersion: 4;
+    uint8_t MessageType : 4;
+    // Byte 1  -- must define LSb first
+    uint8_t OperatorLocationType: 2;
+    uint8_t ClassificationType : 3;
+    uint8_t CoordType :2; // 坐标系类型
+    uint8_t Reserved: 1;
+
+    // Byte 2-9
+    int32_t OperatorLatitude;
+    int32_t OperatorLongitude;
+
+    // Byte 10-16
+    uint16_t AreaCount;
+    uint8_t  AreaRadius;
+    uint16_t AreaCeiling;
+    uint16_t AreaFloor;
+
+    // Byte 17 [CategoryCN][ClassCN]  -- must define LSb first
+    uint8_t ClassCN: 4;
+    uint8_t CategoryCN: 4;
+
+    // Byte 18-23
+    uint16_t OperatorAltitudeGeo;
+    uint32_t Timestamp;
+
+    // Byte 24
+    char Reserved2;
+} CNDID_System_encoded;
+
+/***************************************0xF 打包报文*******************************************/
+
+/*
+ * 从联合成员的任何结构部分访问前两个字段(即ProtoVersion和MessageType)都是安全的,
+ *因为这些字段的声明是相同的,并且位于结构的开头部分。
+ *ISO/IEC 9899:1999第6.5.2.3部分第5条及相关的示例3对此进行了规定。
+https://www.iso.org/standard/29237.html
+ */
+typedef union CNDID_Message_encoded {
+    uint8_t rawData[CNDID_MESSAGE_SIZE]; // 一份报文25字节
+    CNDID_BasicID_encoded basicId;
+    CNDID_Location_encoded location;
+    CNDID_SelfID_encoded selfId;
+    CNDID_System_encoded system;
+} CNDID_Message_encoded;
+
+typedef struct __attribute__((__packed__)) CNDID_MessagePack_encoded {
+    // Byte 0 [MessageType][ProtoVersion]  -- must define LSb first
+    uint8_t ProtoVersion: 4;
+    uint8_t MessageType : 4;
+    // Byte 1 - 2
+    uint8_t SingleMessageSize; // 每个报文长度
+    uint8_t MsgPackSize; // 报文数量
+
+    // Byte 3 - 227
+    CNDID_Message_encoded Messages[CNDID_PACK_MAX_MESSAGES];
+} CNDID_MessagePack_encoded;
+
+typedef struct CNDID_MessagePack_data {
+    uint8_t SingleMessageSize; // Must always be CNDID_MESSAGE_SIZE
+    uint8_t MsgPackSize; // Number of messages in pack (NOT number of bytes)
+
+    CNDID_Message_encoded Messages[CNDID_PACK_MAX_MESSAGES];
+} CNDID_MessagePack_data;
+/*********************************************************************************************/
+
+typedef struct CNDID_UAS_Data {
+    CNDID_BasicID_data BasicID[CNDID_BASIC_ID_MAX_MESSAGES]; // 基础ID 2个ID报文???
+    CNDID_Location_data Location; // 位置向量
+    CNDID_SelfID_data SelfID;    // 运行描述
+    CNDID_System_data System;    // 系统
+    uint8_t BasicIDValid[CNDID_BASIC_ID_MAX_MESSAGES]; // 基础ID非法
+    uint8_t LocationValid; // 位置非法
+    uint8_t SelfIDValid; // 运行描述非法
+    uint8_t SystemValid; // 系统非法
+} CNDID_UAS_Data;
+
+
+
+
+
+
+// API Calls
+void cndid_initBasicIDData(CNDID_BasicID_data *data);
+void cndid_initLocationData(CNDID_Location_data *data);
+void cndid_initSelfIDData(CNDID_SelfID_data *data);
+void cndid_initSystemData(CNDID_System_data *data);
+void cndid_initMessagePackData(CNDID_MessagePack_data *data);
+void cndid_initUasData(CNDID_UAS_Data *data);
+
+int encodeCNBasicIDMessage(CNDID_BasicID_encoded *outEncoded, CNDID_BasicID_data *inData);
+int encodeCNLocationMessage(CNDID_Location_encoded *outEncoded, CNDID_Location_data *inData);
+int encodeCNSelfIDMessage(CNDID_SelfID_encoded *outEncoded, CNDID_SelfID_data *inData);
+int encodeCNSystemMessage(CNDID_System_encoded *outEncoded, CNDID_System_data *inData);
+int encodeCNMessagePack(CNDID_MessagePack_encoded *outEncoded, CNDID_MessagePack_data *inData);
+
+int decodeCNBasicIDMessage(CNDID_BasicID_data *outData, CNDID_BasicID_encoded *inEncoded);
+int decodeCNLocationMessage(CNDID_Location_data *outData, CNDID_Location_encoded *inEncoded);
+
+int decodeCNSelfIDMessage(CNDID_SelfID_data *outData, CNDID_SelfID_encoded *inEncoded);
+int decodeCNSystemMessage(CNDID_System_data *outData, CNDID_System_encoded *inEncoded);
+
+int decodeCNMessagePack(CNDID_UAS_Data *uasData, CNDID_MessagePack_encoded *pack);
+
+int getCNBasicIDType(CNDID_BasicID_encoded *inEncoded, enum CNDID_idtype *idType);
+
+CNDID_MessageType_t decodeCNMessageType(uint8_t byte);
+CNDID_MessageType_t decodeCNDroneID(CNDID_UAS_Data *uas_data, uint8_t *msg_data);
+
+// Helper Functions
+CNDID_HorizontalAccuracy_t createCNEnumHorizontalAccuracy(float Accuracy);
+CNDID_VerticalAccuracy_t createCNEnumVerticalAccuracy(float Accuracy);
+CNDID_SpeedAccuracy_t createCNEnumSpeedAccuracy(float Accuracy);
+CNDID_TimeStampAccuracy_t createCNEnumTimestampAccuracy(float Accuracy);
+
+float decodeCNHorizontalAccuracy(CNDID_HorizontalAccuracy_t Accuracy);
+float decodeCNVerticalAccuracy(CNDID_VerticalAccuracy_t Accuracy);
+float decodeCNSpeedAccuracy(CNDID_SpeedAccuracy_t Accuracy);
+float decodeCNTimestampAccuracy(CNDID_TimeStampAccuracy_t Accuracy);
+
+// CN DroneID WiFi functions
+
+/**
+ * cndid_message_build_pack - 组合消息并对cndid数据包进行编码
+ * @UAS_Data:无人机的一般状态信息
+ * @pack:要写入的缓冲区空间
+ * @buflen:缓冲区空间的最大长度
+ *
+ * Returns length on success, < 0 on failure. @buf only contains a valid message
+ * if the return code is >0
+ */
+int cndid_message_build_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen);
+
+/* cndid_wifi_build_nan_sync_beacon_frame - 创建一个NAN同步信标帧
+ * 该帧应在NAN动作帧之前发送。
+ * @mac:将发送NAN帧的wifi适配器的mac地址
+ * @buf:指向将写入NAN的缓冲区空间的指针
+ * 
+ * @buf_size:缓冲区的最大大小
+ * Returns the packet length on success, or < 0 on error.
+ */
+int cndid_wifi_build_nan_sync_beacon_frame(char *mac, uint8_t *buf, size_t buf_size);
+
+/* cndid_wifi_build_message_pack_nan_action_frame - 创建一个消息包
+ * 包含来自无人机信息的每种类型的消息,将其放入一个NAN动作帧中。
+ * @UAS_Data:无人机的一般状态信息
+ * @mac:将发送NAN帧的WiFi适配器的mac地址
+ * @send_counter:序列号,每次调用此函数时需递增
+ * @buf:指向将写入NAN的缓冲区空间的指针
+ * @buf_size:缓冲区的最大大小
+ *
+ * Returns the packet length on success, or < 0 on error.
+ */
+int cndid_wifi_build_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data, char *mac,
+                                                  uint8_t send_counter,
+                                                  uint8_t *buf, size_t buf_size);
+
+/* cndid_wifi_build_message_pack_beacon_frame - 创建一个消息包
+ * 将来自无人机信息的每种类型的消息整合到一个信标帧中。
+ * @UAS_Data:无人机的一般状态信息
+ * @mac:将发送信标帧的WiFi适配器的MAC地址
+ * @SSID:要发送的WiFi网络的服务集标识符
+ * @SSID_len:服务集标识符字符串的字节长度
+ * @interval_tu:WiFi时间单位中的信标间隔
+ * @send_counter:序列号,每次调用此函数时需递增
+ * @buf:指向将写入信标帧的缓冲区空间的指针
+ * @buf_size:缓冲区的最大大小
+ *
+ * Returns the packet length on success, or < 0 on error.
+ */
+int cndid_wifi_build_message_pack_beacon_frame(CNDID_UAS_Data *UAS_Data, char *mac,
+                                              const char *SSID, size_t SSID_len,
+                                              uint16_t interval_tu, uint8_t send_counter,
+                                              uint8_t *buf, size_t buf_size);
+
+/* cndid_message_process_pack - 从cndid消息包中解码消息
+ * @UAS_Data:无人机的一般状态信息
+ * @pack:要从中读取的缓冲区空间
+ * @buflen:缓冲区空间的长度
+ *
+ * Returns 0 on success
+ */
+int cndid_message_process_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen);
+
+/* cndid_wifi_receive_message_pack_nan_action_frame - 处理接收到的消息包
+ * 将来自无人机信息的每种类型的消息转换为NAN动作帧
+ * @UAS_Data:无人机的一般状态信息
+ * @mac:将发送NAN帧的WiFi适配器的MAC地址
+ * @buf:存储NAN的缓冲区空间指针
+ * @buf_size:缓冲区的最大大小
+ *
+ * Returns 0 on success, or < 0 on error. Will fill 6 bytes into @mac.
+ */
+int cndid_wifi_receive_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data,
+                                                    char *mac, uint8_t *buf, size_t buf_size);
+
+#ifndef CNDID_DISABLE_PRINTF
+void PrintByteArray(uint8_t *byteArray, uint16_t asize, int spaced);
+void PrintBasicID_data(CNDID_BasicID_data *BasicID);
+void PrintLocation_data(CNDID_Location_data *Location);
+void PrintSelfID_data(CNDID_SelfID_data *SelfID);
+void PrintSystem_data(CNDID_System_data *System_data);
+#endif // CNDID_DISABLE_PRINTF
+
+

+ 537 - 0
RemoteIDModule/did_GB2025_wifi.cpp

@@ -0,0 +1,537 @@
+/*
+Copyright (C) 2020 Simon Wunderlich, Marek Sobe
+Copyright (C) 2020 Doodle Labs
+
+SPDX-License-Identifier: Apache-2.0
+
+Open Drone ID C Library
+
+Maintainer:
+Simon Wunderlich
+sw@simonwunderlich.de
+*/
+/*该文件是对开源wifi修改适配国产标准*/
+#if defined(ARDUINO_ARCH_ESP32)
+#include <Arduino.h>
+int clock_gettime(clockid_t, struct timespec *);
+#else 
+#include <string.h>
+#include <stddef.h>
+#include <stdio.h>
+#endif
+
+#include <errno.h>
+#include <time.h>
+
+#include "did_GB2025_wifi.h"
+
+
+#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
+#define cpu_to_le16(x)  (x)
+#define cpu_to_le64(x)  (x)
+#else
+#define cpu_to_le16(x)      (bswap_16(x))
+#define cpu_to_le64(x)      (bswap_64(x))
+#endif
+
+#define IEEE80211_FCTL_FTYPE          0x000c
+#define IEEE80211_FCTL_STYPE          0x00f0
+
+#define IEEE80211_FTYPE_MGMT            0x0000
+#define IEEE80211_STYPE_ACTION          0x00D0
+#define IEEE80211_STYPE_BEACON          0x0080
+
+/* IEEE 802.11-2016 capability info */
+#define IEEE80211_CAPINFO_ESS               0x0001
+#define IEEE80211_CAPINFO_IBSS              0x0002
+#define IEEE80211_CAPINFO_CF_POLLABLE       0x0004
+#define IEEE80211_CAPINFO_CF_POLLREQ        0x0008
+#define IEEE80211_CAPINFO_PRIVACY           0x0010
+#define IEEE80211_CAPINFO_SHORT_PREAMBLE    0x0020
+/* bits 6-7 reserved */
+#define IEEE80211_CAPINFO_SPECTRUM_MGMT     0x0100
+#define IEEE80211_CAPINFO_QOS               0x0200
+#define IEEE80211_CAPINFO_SHORT_SLOTTIME    0x0400
+#define IEEE80211_CAPINFO_APSD              0x0800
+#define IEEE80211_CAPINFO_RADIOMEAS         0x1000
+/* bit 13 reserved */
+#define IEEE80211_CAPINFO_DEL_BLOCK_ACK     0x4000
+#define IEEE80211_CAPINFO_IMM_BLOCK_ACK     0x8000
+
+/* IEEE 802.11 Element IDs */
+#define IEEE80211_ELEMID_SSID		0x00
+#define IEEE80211_ELEMID_RATES		0x01
+#define IEEE80211_ELEMID_VENDOR		0xDD
+
+/* 《邻居感知网络规范》v3.1第2.8.2节
+* NAN集群ID是一个MAC地址,其取值范围为50-6F-9A-01-00-00至50-6F-9A-01-FF-FF,
+* 承载于部分NAN帧的A3字段中。NAN集群ID由发起NAN集群的设备随机选择。
+* 然而,《ASTM远程ID规范》v1.1规定,NAN集群ID必须固定为50-6F-9A-01-00-FF这一值。
+ */
+static const uint8_t *get_nan_cluster_id(void)
+{
+    static const uint8_t cluster_id[6] = { 0x50, 0x6F, 0x9A, 0x01, 0x00, 0xFF };
+    return cluster_id;
+}
+
+static int buf_fill_ieee80211_mgmt(uint8_t *buf, size_t *len, size_t buf_size,
+                                   const uint16_t subtype,
+                                   const uint8_t *dst_addr,
+                                   const uint8_t *src_addr,
+                                   const uint8_t *bssid)
+{
+    if (*len + sizeof(struct ieee80211_mgmt) > buf_size)
+        return -ENOMEM;
+
+    struct ieee80211_mgmt *mgmt = (struct ieee80211_mgmt *)(buf + *len);
+    mgmt->frame_control = (uint16_t) cpu_to_le16(IEEE80211_FTYPE_MGMT | subtype);
+    mgmt->duration = cpu_to_le16(0x0000);
+    memcpy(mgmt->da, dst_addr, sizeof(mgmt->da));
+    memcpy(mgmt->sa, src_addr, sizeof(mgmt->sa));
+    memcpy(mgmt->bssid, bssid, sizeof(mgmt->bssid));
+    mgmt->seq_ctrl = cpu_to_le16(0x0000);
+    *len += sizeof(*mgmt);
+
+    return 0;
+}
+
+static int buf_fill_ieee80211_beacon(uint8_t *buf, size_t *len, size_t buf_size, uint16_t interval_tu)
+{
+    if (*len + sizeof(struct ieee80211_beacon) > buf_size)
+        return -ENOMEM;
+
+    struct ieee80211_beacon *beacon = (struct ieee80211_beacon *)(buf + *len);
+    struct timespec ts;
+    uint64_t mono_us = 0;
+
+#if defined(CLOCK_MONOTONIC)
+    clock_gettime(CLOCK_MONOTONIC, &ts);
+    mono_us = (uint64_t)((double) ts.tv_sec * 1e6 + (double) ts.tv_nsec * 1e-3);
+#elif defined(CLOCK_REALTIME)
+    clock_gettime(CLOCK_REALTIME, &ts);
+    mono_us = (uint64_t)((double) ts.tv_sec * 1e6 + (double) ts.tv_nsec * 1e-3);
+#elif defined(ARDUINO)
+#warning "No REALTIME or MONOTONIC clock, using micros()."
+    mono_us = micros();
+#else
+#warning "Unable to set wifi timestamp."
+#endif
+    beacon->timestamp = cpu_to_le64(mono_us);
+    beacon->beacon_interval = cpu_to_le16(interval_tu);
+    beacon->capability = cpu_to_le16(IEEE80211_CAPINFO_SHORT_SLOTTIME | IEEE80211_CAPINFO_SHORT_PREAMBLE);
+    *len += sizeof(*beacon);
+
+    return 0;
+}
+
+/* void* 不能用 可能是编译器版本的问题 改成uint8_t* 了*/
+int did_GB2025_message_build_pack(UavIdentificationData *UAS_Data, uint8_t *pack, size_t buflen)
+{
+    if (UAS_Data == NULL || pack == NULL || buflen == 0) {
+        return -1;  // 参数错误
+    }
+    
+    UavIdentificationPacket *msg_pack_enc = (UavIdentificationPacket *)pack;
+ 
+    
+    // 1. 调用组包函数
+    int8_t ret = uav_identification_pack(msg_pack_enc, UAS_Data);
+    if (ret != 0) {
+        return -2;  // 组包失败
+    }
+    
+    // 2. 计算实际包大小(头部 + 内容)
+    // 数据包总大小 = 固定头部(1+1+1+3) + 内容长度
+    size_t total_len = sizeof(msg_pack_enc->data_type) + 
+                       sizeof(msg_pack_enc->version) + 
+                       sizeof(msg_pack_enc->content_len) + 
+                       sizeof(msg_pack_enc->data_flag) + 
+                       msg_pack_enc->content_len;
+    
+    // 3. 检查缓冲区大小
+    if (total_len > buflen) {
+        return -3;  // 缓冲区不足
+    }
+    
+    return (int)total_len;  // 返回实际使用的字节数
+}
+// 里面的服务id可能后面要改 还有一些指向 open droneid的
+int did_GB2025_wifi_build_nan_sync_beacon_frame(char *mac, uint8_t *buf, size_t buf_size)
+{
+    /* Broadcast address */
+    uint8_t target_addr[6] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A };
+    /* "org.opendroneid.remoteid" hash */
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 };
+    const uint8_t *cluster_id = get_nan_cluster_id();
+    struct ieee80211_vendor_specific *vendor;
+    struct nan_master_indication_attribute *master_indication_attr;
+    struct nan_cluster_attribute *cluster_attr;
+    struct nan_service_id_list_attribute *nsila;
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_BEACON, target_addr, (uint8_t *)mac, cluster_id);
+    if (ret <0)
+        return ret;
+
+    /* Beacon */
+    ret = buf_fill_ieee80211_beacon(buf, &len, buf_size, 0x0200);
+    if (ret <0)
+        return ret;
+
+    /* Vendor Specific */
+    if (len + sizeof(*vendor) > buf_size)
+        return -ENOMEM;
+
+    vendor = (struct ieee80211_vendor_specific *)(buf + len);
+    memset(vendor, 0, sizeof(*vendor));
+    vendor->element_id = IEEE80211_ELEMID_VENDOR;
+    vendor->length = 0x22;
+    memcpy(vendor->oui, wifi_alliance_oui, sizeof(vendor->oui));
+    vendor->oui_type = 0x13; 
+    len += sizeof(*vendor);
+
+    /* NAN Master Indication attribute */
+    if (len + sizeof(*master_indication_attr) > buf_size)
+        return -ENOMEM;
+
+    master_indication_attr = (struct nan_master_indication_attribute *)(buf + len);
+    memset(master_indication_attr, 0, sizeof(*master_indication_attr));
+    master_indication_attr->header.attribute_id = 0x00;
+    master_indication_attr->header.length = cpu_to_le16(0x0002);
+    /* Information that is used to indicate a NAN Device’s preference to serve
+     * as the role of Master, with a larger value indicating a higher
+     * preference. Values 1 and 255 are used for testing purposes only.
+     */
+    master_indication_attr->master_preference = 0xFE;
+    /* Random factor value 0xEA is recommended by the European Standard */
+    master_indication_attr->random_factor = 0xEA;
+    len += sizeof(*master_indication_attr);
+
+    /* NAN Cluster attribute */
+    if (len + sizeof(*cluster_attr) > buf_size)
+        return -ENOMEM;
+
+    cluster_attr = (struct nan_cluster_attribute *)(buf + len);
+    memset(cluster_attr, 0, sizeof(*cluster_attr));
+    cluster_attr->header.attribute_id = 0x1;
+    cluster_attr->header.length = cpu_to_le16(0x000D);
+    memcpy(cluster_attr->device_mac, mac, sizeof(cluster_attr->device_mac));
+    cluster_attr->random_factor = 0xEA;
+    cluster_attr->master_preference = 0xFE;
+    cluster_attr->hop_count_to_anchor_master = 0x00;
+    memset(cluster_attr->anchor_master_beacon_transmission_time, 0, sizeof(cluster_attr->anchor_master_beacon_transmission_time));
+    len += sizeof(*cluster_attr);
+
+    /* NAN attributes */
+    if (len + sizeof(*nsila) > buf_size)
+        return -ENOMEM;
+
+    nsila = (struct nan_service_id_list_attribute *)(buf + len);
+    memset(nsila, 0, sizeof(*nsila));
+    nsila->header.attribute_id = 0x02;
+    nsila->header.length = cpu_to_le16(0x0006);
+    memcpy(nsila->service_id, service_id, sizeof(service_id));
+    len += sizeof(*nsila);
+
+    return (int) len;
+}
+
+int did_GB2025_wifi_build_message_pack_nan_action_frame(UavIdentificationData *UAS_Data, char *mac,
+                                                  uint8_t send_counter,
+                                                  uint8_t *buf, size_t buf_size)
+{
+    /* Neighbor Awareness Networking Specification v3.0 in section 2.8.1
+     * NAN网络ID要求目标MAC地址为51-6F-9A-01-00-00*/
+    uint8_t target_addr[6] = { 0x51, 0x6F, 0x9A, 0x01, 0x00, 0x00 };
+    /* "org.opendroneid.remoteid 哈希值 国际通用的*/
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 };
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A };
+    const uint8_t *cluster_id = get_nan_cluster_id();
+    struct nan_service_discovery *nsd;
+    struct nan_service_descriptor_attribute *nsda;
+    struct nan_service_descriptor_extension_attribute *nsdea;
+    struct DID_GB2025_service_info *si;
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_ACTION, target_addr, (uint8_t *)mac, cluster_id);
+    if (ret <0)
+        return ret;
+
+    /* NAN Service Discovery header */
+    if (len + sizeof(*nsd) > buf_size)
+        return -ENOMEM;
+
+    nsd = (struct nan_service_discovery *)(buf + len);
+    memset(nsd, 0, sizeof(*nsd));
+    nsd->category = 0x04;               /* IEEE 802.11 Public Action frame */
+    nsd->action_code = 0x09;            /* IEEE 802.11 Public Action frame Vendor Specific*/
+    memcpy(nsd->oui, wifi_alliance_oui, sizeof(nsd->oui));
+    nsd->oui_type = 0x13;               /* Identify Type and version of the NAN */
+    len += sizeof(*nsd);
+
+    /* NAN Attribute for Service Descriptor header */
+    if (len + sizeof(*nsda) > buf_size)
+        return -ENOMEM;
+
+    nsda = (struct nan_service_descriptor_attribute *)(buf + len);
+    nsda->header.attribute_id = 0x3;    /* Service Descriptor Attribute type */
+    memcpy(nsda->service_id, service_id, sizeof(service_id));
+    /* always 1 */
+    nsda->instance_id = 0x01;           /* always 1 */
+    nsda->requestor_instance_id = 0x00; /* from triggering frame */
+    nsda->service_control = 0x10;       /* follow up */
+    len += sizeof(*nsda);
+
+    /* CNDID Service Info Attribute header */
+    if (len + sizeof(*si) > buf_size)
+        return -ENOMEM;
+
+    si = (struct DID_GB2025_service_info *)(buf + len);
+    memset(si, 0, sizeof(*si));
+    si->message_counter = send_counter;
+    len += sizeof(*si);
+
+    ret = did_GB2025_message_build_pack(UAS_Data, buf + len, buf_size - len);
+    if (ret < 0)
+        return ret;
+    len += ret;
+
+    /* set the lengths according to the message pack lengths */
+    nsda->service_info_length = sizeof(*si) + ret;
+    nsda->header.length = cpu_to_le16(sizeof(*nsda) - sizeof(struct nan_attribute_header) + nsda->service_info_length);
+
+    /* NAN Attribute for Service Descriptor extension header */
+    if (len + sizeof(*nsdea) > buf_size)
+        return -ENOMEM;
+
+    nsdea = (struct nan_service_descriptor_extension_attribute *)(buf + len);
+    nsdea->header.attribute_id = 0xE;
+    nsdea->header.length = cpu_to_le16(0x0004);
+    nsdea->instance_id = 0x01;
+    nsdea->control = cpu_to_le16(0x0200);
+    nsdea->service_update_indicator = send_counter;
+    len += sizeof(*nsdea);
+
+    return (int) len;
+}
+
+int did_GB2025_wifi_build_message_pack_beacon_frame(UavIdentificationData *UAS_Data, char *mac,
+                                              const char *SSID, size_t SSID_len,
+                                              uint16_t interval_tu, uint8_t send_counter,
+                                              uint8_t *buf, size_t buf_size)
+{
+    /* Broadcast address */
+    uint8_t target_addr[6] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
+    uint8_t asd_stan_oui[3] = { 0xFA, 0x0B, 0xBC }; // 国标也是0xFA0BBC
+    /* Mgmt Beacon frame mandatory fields + IE 221 */
+    struct ieee80211_ssid *ssid_s;
+    struct ieee80211_supported_rates *rates;
+    struct ieee80211_vendor_specific *vendor;
+
+    /* Message Pack */
+    struct DID_GB2025_service_info *si;
+
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    ret = buf_fill_ieee80211_mgmt(buf, &len, buf_size, IEEE80211_STYPE_BEACON, target_addr, (uint8_t *)mac, (uint8_t *)mac);
+    if (ret <0)
+        return ret;
+
+    /* Mandatory Beacon as of 802.11-2016 Part 11 */
+    ret = buf_fill_ieee80211_beacon(buf, &len, buf_size, interval_tu);
+    if (ret <0)
+        return ret;
+
+    /* SSID: 1-32 bytes */
+    if (len + sizeof(*ssid_s) > buf_size)
+        return -ENOMEM;
+
+    ssid_s = (struct ieee80211_ssid *)(buf + len);
+    if(!SSID || (SSID_len ==0) || (SSID_len > 32))
+        return -EINVAL;
+    ssid_s->element_id = IEEE80211_ELEMID_SSID;
+    ssid_s->length = (uint8_t) SSID_len;
+    memcpy(ssid_s->ssid, SSID, ssid_s->length);
+    len += sizeof(*ssid_s) + SSID_len;
+
+    /* Supported Rates: 1 record at minimum */
+    if (len + sizeof(*rates) > buf_size)
+        return -ENOMEM;
+
+    rates = (struct ieee80211_supported_rates *)(buf + len);
+    rates->element_id = IEEE80211_ELEMID_RATES;
+    rates->length = 1; // One rate only
+    rates->supported_rates = 0x8C;     // 6 Mbps
+    len += sizeof(*rates);
+
+    /* Vendor Specific Information Element (IE 221) */
+    if (len + sizeof(*vendor) > buf_size)
+        return -ENOMEM;
+
+    vendor = (struct ieee80211_vendor_specific *)(buf + len);
+    vendor->element_id = IEEE80211_ELEMID_VENDOR;
+    vendor->length = 0x00;  // Length updated at end of function
+    memcpy(vendor->oui, asd_stan_oui, sizeof(vendor->oui));
+    vendor->oui_type = 0x0D;
+    len += sizeof(*vendor);
+
+    /* DID GB2025 Service Info Attribute header */
+    if (len + sizeof(*si) > buf_size)
+        return -ENOMEM;
+
+    si = (struct DID_GB2025_service_info *)(buf + len);
+    memset(si, 0, sizeof(*si));
+    si->message_counter = send_counter;
+    len += sizeof(*si);
+
+    ret = did_GB2025_message_build_pack(UAS_Data, buf + len, buf_size - len);
+    if (ret < 0)
+        return ret;
+    len += ret;
+
+    /* set the lengths according to the message pack lengths */
+    vendor->length = sizeof(vendor->oui) + sizeof(vendor->oui_type) + sizeof(*si) + ret; // ret 是个负的表示空闲字节数
+
+    return (int) len;
+}
+// 解包
+int did_GB2025_message_process_pack(UavIdentificationData  *UAS_Data, uint8_t *pack, size_t buflen)
+{
+    if (UAS_Data == NULL || pack == NULL || buflen == 0) {
+        return -1;
+    }
+    
+    UavIdentificationPacket *msg_pack_enc = (UavIdentificationPacket *) pack;
+    
+    // 固定头部大小:data_type(1) + version(1) + content_len(1) + data_flag(3) = 6字节
+    const size_t FIXED_HEADER_SIZE = 6;
+    
+    // 1. 首先检查是否能安全读取固定头部
+    if (buflen < FIXED_HEADER_SIZE) {
+        return -2;  // 缓冲区太小,连头部都不够
+    }
+    
+    // 2. 现在可以安全地读取 content_len
+    uint8_t content_len = msg_pack_enc->content_len;
+    
+    // 3. 检查 content_len 是否合理
+    if (content_len > MAX_CONTENT_BYTES) {
+        return -3;  // 内容长度超限
+    }
+    
+    // 4. 计算完整的包大小
+    size_t total_size = FIXED_HEADER_SIZE + content_len;
+    
+    // 5. 验证整个包是否在缓冲区范围内
+    if (total_size > buflen) {
+        return -4;  // 包不完整
+    }
+    
+    // 6. 检查数据类型(可选)
+    if (msg_pack_enc->data_type != PACKET_DATA_TYPE) {
+        return -5;  // 数据类型错误
+    }
+    
+    // 7. 初始化解包目标
+    uav_identification_data_init(UAS_Data);
+    
+    // 8. 执行解包
+    if (uav_identification_unpack(UAS_Data, msg_pack_enc) != 0) {
+        return -6;  // 解包失败
+    }
+    
+    // 9. 返回实际处理的字节数
+    return (int)total_size;
+}
+
+int did_GB2025_wifi_receive_message_pack_nan_action_frame(UavIdentificationData  *UAS_Data,
+                                                    char *mac, uint8_t *buf, size_t buf_size)
+{
+    struct ieee80211_mgmt *mgmt; // 802.11管理帧头
+    struct nan_service_discovery *nsd; // NAN服务发现帧头
+    struct nan_service_descriptor_attribute *nsda; // NAN服务描述符属性
+    struct nan_service_descriptor_extension_attribute *nsdea;  // NAN服务描述符扩展属性
+    struct DID_GB2025_service_info *si; // 中国远程ID服务信息
+    uint8_t target_addr[6] = { 0x51, 0x6F, 0x9A, 0x01, 0x00, 0x00 };  // 远程ID(Remote ID)分配的专用组播地址
+    uint8_t wifi_alliance_oui[3] = { 0x50, 0x6F, 0x9A }; // Wi-Fi联盟OUI
+    uint8_t service_id[6] = { 0x88, 0x69, 0x19, 0x9D, 0x92, 0x09 }; // 远程ID服务ID 国际通用的 不需要改
+    int ret;
+    size_t len = 0;
+
+    /* IEEE 802.11 Management Header */
+    if (len + sizeof(*mgmt) > buf_size) // 检查缓冲区是否足够容纳一个管理帧头
+        return -EINVAL;
+    mgmt = (struct ieee80211_mgmt *)(buf + len);
+    if ((mgmt->frame_control & cpu_to_le16(IEEE80211_FCTL_FTYPE | IEEE80211_FCTL_STYPE)) !=
+        cpu_to_le16(IEEE80211_FTYPE_MGMT | IEEE80211_STYPE_ACTION))
+        return -EINVAL;
+    if (memcmp(mgmt->da, target_addr, sizeof(mgmt->da)) != 0)
+        return -EINVAL;
+    memcpy(mac, mgmt->sa, sizeof(mgmt->sa));
+
+    len += sizeof(*mgmt);
+
+    /* NAN Service Discovery header */
+    if (len + sizeof(*nsd) > buf_size)
+        return -EINVAL;
+    nsd = (struct nan_service_discovery *)(buf + len);
+    if (nsd->category != 0x04)
+        return -EINVAL;
+    if (nsd->action_code != 0x09)
+        return -EINVAL;
+    if (memcmp(nsd->oui, wifi_alliance_oui, sizeof(wifi_alliance_oui)) != 0)
+        return -EINVAL;
+    if (nsd->oui_type != 0x13)
+        return -EINVAL;
+    len += sizeof(*nsd);
+
+    /* NAN Attribute for Service Descriptor header */
+    if (len + sizeof(*nsda) > buf_size)
+        return -EINVAL;
+    nsda = (struct nan_service_descriptor_attribute *)(buf + len);
+    if (nsda->header.attribute_id != 0x3)
+        return -EINVAL;
+    if (memcmp(nsda->service_id, service_id, sizeof(service_id)) != 0)
+        return -EINVAL;
+    if (nsda->instance_id != 0x01)
+        return -EINVAL;
+    if (nsda->service_control != 0x10)
+        return -EINVAL;
+    len += sizeof(*nsda);
+
+    // 在读取 si 之前应该检查空间
+    if (len + sizeof(*si) > buf_size)
+        return -EINVAL;
+
+    si = (struct DID_GB2025_service_info *)(buf + len);
+    ret = did_GB2025_message_process_pack(UAS_Data, buf + len + sizeof(*si), buf_size - len - sizeof(*nsdea));
+    if (ret < 0)
+        return -EINVAL;
+    if (nsda->service_info_length != (sizeof(*si) + ret))
+        return -EINVAL;
+    if (nsda->header.length != (cpu_to_le16(sizeof(*nsda) - sizeof(struct nan_attribute_header) + nsda->service_info_length)))
+        return -EINVAL;
+    len += sizeof(*si) + ret;
+
+    /* NAN Attribute for Service Descriptor extension header */
+    if (len + sizeof(*nsdea) > buf_size)
+        return -ENOMEM;
+    nsdea = (struct nan_service_descriptor_extension_attribute *)(buf + len);
+    if (nsdea->header.attribute_id != 0xE)
+        return -EINVAL;
+    if (nsdea->header.length != cpu_to_le16(0x0004))
+        return -EINVAL;
+    if (nsdea->instance_id != 0x01)
+        return -EINVAL;
+    if (nsdea->control != cpu_to_le16(0x0200))
+        return -EINVAL;
+
+    return 0;
+}

+ 11 - 0
RemoteIDModule/did_GB2025_wifi.h

@@ -0,0 +1,11 @@
+#pragma once
+#include "stdint.h"
+#include "did_GB_2025.h"
+#include "odid_wifi.h"
+
+#define GB2025_WIFI_VENDOR_IE_ELEMENT_ID 0xDD
+struct __attribute__((__packed__)) DID_GB2025_service_info {
+    uint8_t message_counter;
+    UavIdentificationPacket GB2025_message_pack[];
+};
+

+ 627 - 0
RemoteIDModule/did_GB_2025.cpp

@@ -0,0 +1,627 @@
+#include "did_GB_2025.h"
+#include <stdio.h>
+
+/************************** 工具函数:字节序转换 **************************/
+void uav_put_uint16_le(uint16_t val, uint8_t *buf) {
+    if (buf == NULL) return;
+    buf[0] = val & 0xFF;
+    buf[1] = (val >> 8) & 0xFF;
+}
+
+void uav_put_uint32_le(uint32_t val, uint8_t *buf) {
+    if (buf == NULL) return;
+    buf[0] = val & 0xFF;
+    buf[1] = (val >> 8) & 0xFF;
+    buf[2] = (val >> 16) & 0xFF;
+    buf[3] = (val >> 24) & 0xFF;
+}
+
+uint16_t uav_get_uint16_le(const uint8_t *buf) {
+    if (buf == NULL) return 0;
+    return (uint16_t)buf[0] | ((uint16_t)buf[1] << 8);
+}
+
+uint32_t uav_get_uint32_le(const uint8_t *buf) {
+    if (buf == NULL) return 0;
+    return (uint32_t)buf[0] | ((uint32_t)buf[1] << 8) | 
+           ((uint32_t)buf[2] << 16) | ((uint32_t)buf[3] << 24);
+}
+
+/************************** 编码函数实现 **************************/
+uint32_t uav_enc_lat(double lat, bool is_valid)
+{
+     // 未知或不可用
+    if (!is_valid || isnan(lat) || isinf(lat)) {
+        return 0xFFFFFFFF;  // 0xFFFFFFFF
+    }
+    
+    // 范围检查:经度±180°,纬度±90°
+    if (lat > 90.0 || lat < -90.0) {
+        return 0xFFFFFFFF;
+    }
+    
+    // 编码:实际值 × 10^7,四舍五入
+    double scaled = lat * LAT_LON_SCALE;
+    int32_t enc = (int32_t)(scaled + (scaled >= 0 ? 0.5 : -0.5));
+    
+    return (uint32_t)enc;  // 保持负数的位模式
+
+}
+/**
+ * 经纬度编码(表3序号006/008)
+ * 编码值 = 实际值 × 10^7,32位小端序
+ * 西经、南纬以负值表示,未知/不可用时取"FFFFFFFF"
+ */
+uint32_t uav_enc_lon(double lon, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(lon) || isinf(lon)) {
+        return 0xFFFFFFFF;  // 0xFFFFFFFF
+    }
+    
+    // 范围检查:经度±180°,纬度±90°
+    if (lon > 180.0 || lon < -180.0) {
+        return 0xFFFFFFFF;
+    }
+    
+    // 编码:实际值 × 10^7,四舍五入
+    double scaled = lon * LAT_LON_SCALE;
+    int32_t enc = (int32_t)(scaled + (scaled >= 0 ? 0.5 : -0.5));
+    
+    return (uint32_t)enc;  // 保持负数的位模式
+}
+
+/**
+ * 遥控站高度/大地高度/气压高度编码(表3序号007/013/014)
+ * 编码值 = (实际值 + 1000) × 2,16位小端序
+ * 分辨率0.5m,未知/不可用时取"0"
+ */
+uint16_t uav_enc_geo_alt(double alt, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(alt) || isinf(alt)) {
+        return 0;  // 0
+    }
+    
+    // 计算:(alt + 1000) × 2,四舍五入
+    double calc = (alt + GEO_ALT_OFFSET) * GEO_ALT_SCALE;
+    
+    // 范围检查:必须能表示为16位无符号整数
+    if (calc < 0.0 || calc > 65534.0) {  // 保留0xFFFF,但标准用0表示未知
+        return 0;
+    }
+    
+    return (uint16_t)(calc + 0.5);
+}
+
+/**
+ * 相对高度编码(表3序号011)
+ * 编码值 = (实际值 + 9000) × 2,16位小端序
+ * 分辨率0.5m,未知/不可用时取"0"
+ */
+uint16_t uav_enc_rel_alt(double alt, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(alt) || isinf(alt)) {
+        return 0;  // 0
+    }
+    
+    // 计算:(alt + 9000) × 2,四舍五入
+    double calc = (alt + REL_ALT_OFFSET) * REL_ALT_SCALE;
+    
+    // 范围检查:-9000m ~ +23767m对应0~65534
+    if (calc < 0.0 || calc > 65534.0) {
+        return 0;
+    }
+    
+    return (uint16_t)(calc + 0.5);
+}
+
+/**
+ * 航迹角编码(表3序号009)
+ * 编码值 = 实际值 × 10,16位小端序
+ * 有效值0~3599,分辨率0.1°,未知/不可用时取"FFFF"
+ */
+uint16_t uav_enc_track_angle(double angle, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(angle) || isinf(angle)) {
+        return 0xFFFF;  // 0xFFFF
+    }
+    
+    // 有效范围:0~359.9°
+    if (angle < 0.0 || angle >= 360.0) {
+        return 0xFFFF;
+    }
+    
+    // 编码:×10,向下取整(标准要求)
+    uint16_t enc = (uint16_t)(angle * ANGLE_SPEED_SCALE);
+    
+    // 确保不超过3599
+    return enc > 3599 ? 3599 : enc;
+}
+
+/**
+ * 地速编码(表3序号010)
+ * 编码值 = 实际值 × 10,16位小端序
+ * 分辨率0.1m/s,向下取整,未知/不可用时取"FFFF"
+ */
+uint16_t uav_enc_ground_speed(double speed, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(speed) || isinf(speed)) {
+        return 0xFFFF;  // 0xFFFF
+    }
+    
+    // 速度不能为负
+    if (speed < 0.0) {
+        return 0xFFFF;
+    }
+    
+    // 编码:×10,向下取整(标准要求)
+    return (uint16_t)(speed * ANGLE_SPEED_SCALE);
+}
+
+/**
+ * 垂直速度编码(表3序号012)
+ * 第1位为标志位:0上升,1下降
+ * 编码值0~127,实际值×2,分辨率0.5m/s
+ * 未知/不可用时取"FF"
+ */
+uint8_t uav_enc_vert_speed(double v_speed, bool is_valid) {
+    // 未知或不可用
+    if (!is_valid || isnan(v_speed) || isinf(v_speed)) {
+        return 0xFF;  // 0xFF
+    }
+    
+    // 方向标志
+    uint8_t enc = (v_speed < 0.0) ? 0x80 : 0x00;
+    
+    // 取绝对值
+    double abs_speed = fabs(v_speed);
+    
+    // 范围限制:最大63.5 m/s (127/2)
+    if (abs_speed > 63.5) {
+        abs_speed = 63.5;
+    }
+    
+    // 编码:×2,四舍五入
+    uint8_t val = (uint8_t)(abs_speed * VERT_SPEED_SCALE + 0.5);
+    
+    return enc | (val & 0x7F);
+}
+
+/**
+ * 时间戳编码(表3序号020)
+ * Unix时间戳(ms),6字节小端序
+ * 未知/不可用时取全0
+ */
+void uav_enc_timestamp(uint64_t timestamp, bool is_valid, uint8_t *buf) {
+    if (buf == NULL) return;
+    
+    // 未知或不可用
+    if (!is_valid) {
+        memset(buf, 0, 6);
+        return;
+    }
+    
+    // 6字节小端序
+    buf[0] = (uint8_t)(timestamp >> 0);
+    buf[1] = (uint8_t)(timestamp >> 8);
+    buf[2] = (uint8_t)(timestamp >> 16);
+    buf[3] = (uint8_t)(timestamp >> 24);
+    buf[4] = (uint8_t)(timestamp >> 32);
+    buf[5] = (uint8_t)(timestamp >> 40);
+}
+
+/**
+ * 版本号编码(表1)
+ * 第1~3位固定为"001",第4~8位为从版本号0~63
+ */
+uint8_t uav_set_packet_version() {
+    uint8_t ver = VERSION_ENCODE;
+    return ver;
+}
+
+/************************** 解码函数实现 **************************/
+
+/**
+ * 经纬度解码
+ */
+double uav_dec_lat_lon(uint32_t enc_val) {
+    if (enc_val == 0xFFFFFFFF) return 0.0;
+    
+    // 按有符号整数解释
+    int32_t signed_val = (int32_t)enc_val;
+    return (double)signed_val / LAT_LON_SCALE;
+}
+
+/**
+ * 大地高度/气压高度解码
+ */
+double uav_dec_geo_alt(uint16_t enc_val) {
+    if (enc_val == 0) return 0.0;
+    return (double)enc_val / GEO_ALT_SCALE - GEO_ALT_OFFSET;
+}
+
+/**
+ * 相对高度解码
+ */
+double uav_dec_rel_alt(uint16_t enc_val) {
+    if (enc_val == 0) return 0.0;
+    return (double)enc_val / REL_ALT_SCALE - REL_ALT_OFFSET;
+}
+
+/**
+ * 航迹角解码
+ */
+double uav_dec_track_angle(uint16_t enc_val) {
+    if (enc_val == 0xFFFF) return -1.0;
+    return (double)enc_val / ANGLE_SPEED_SCALE;
+}
+
+/**
+ * 地速解码
+ */
+double uav_dec_ground_speed(uint16_t enc_val) {
+    if (enc_val == 0xFFFF) return -1.0;
+    return (double)enc_val / ANGLE_SPEED_SCALE;
+}
+
+/**
+ * 垂直速度解码
+ */
+double uav_dec_vert_speed(uint8_t enc_val) {
+    if (enc_val == 0xFF) return 0.0;
+    
+    double val = (double)(enc_val & 0x7F) / VERT_SPEED_SCALE;
+    return (enc_val & 0x80) ? -val : val;
+}
+
+/**
+ * 时间戳解码
+ */
+uint64_t uav_dec_timestamp(const uint8_t *buf) {
+    if (buf == NULL) return 0;
+    
+    // 检查是否全0(未知)
+    bool is_unknown = true;
+    for (int i = 0; i < 6; i++) {
+        if (buf[i] != 0) {
+            is_unknown = false;
+            break;
+        }
+    }
+    if (is_unknown) return 0;
+    
+    // 6字节小端序合并
+    uint64_t ts = 0;
+    ts |= (uint64_t)buf[0] << 0;
+    ts |= (uint64_t)buf[1] << 8;
+    ts |= (uint64_t)buf[2] << 16;
+    ts |= (uint64_t)buf[3] << 24;
+    ts |= (uint64_t)buf[4] << 32;
+    ts |= (uint64_t)buf[5] << 40;
+    
+    return ts;
+}
+/************************** 辅助函数:原始数据初始化 **************************/
+void uav_identification_data_init(UavIdentificationData *data) {
+    if (data == NULL) return;
+    memset(data, 0, sizeof(UavIdentificationData));
+    memset(data->unique_code, FILL_CHAR, 20);
+    memset(data->register_id, FILL_CHAR, 8);
+    // 所有有效性标志初始化为false
+    data->is_station_pos_valid = false;
+    data->is_uav_pos_valid = false;
+    data->is_station_alt_valid = false;
+    data->is_uav_geo_alt_valid = false;
+    data->is_track_angle_valid = false;
+    data->is_ground_speed_valid = false;
+    data->is_timestamp_valid = false;
+    data->is_rel_alt_valid = false;
+    data->is_vert_speed_valid = false;
+    data->is_press_alt_valid = false;
+    // 可选字段接收标志初始化为false
+    data->flag_run_class = false;
+    data->flag_rel_alt = false;
+    data->flag_vert_speed = false;
+    data->flag_press_alt = false;
+}
+
+/************************** 核心函数:组包 (可选 必选 都进行组包)**************************/
+int8_t uav_identification_pack(UavIdentificationPacket *packet, const UavIdentificationData *data) {
+    if (packet == NULL || data == NULL) return -1;
+    memset(packet, 0, sizeof(UavIdentificationPacket));
+
+    // 1. 固定头部填充 0xFF + 0x20+ len + 3 data descr + N data
+    packet->data_type = PACKET_DATA_TYPE; // 报头
+    packet->version = uav_set_packet_version(); // 版本
+    uint8_t *content_ptr = packet->content; // 实际报文内容
+    // 无论是否合法都强制发送所有报文 非法的发非法值 也就是数据描述字节依次是 0xFF 0xFF 0xFE 最后一位是确定下一位是描述还是载荷
+    /********** 第1字节:控制001~007项(按分类顺序填充) **********/
+    packet->data_flag[0] = BYTE1_ALL_FIELDS | MARK_BYTE_NEXT; // 所有项强制发送(含可选003项)
+    
+    // 001-唯一产品识别码 - 大端序
+    for (int i = 0; i < 20; i++) {
+        content_ptr[i] = data->unique_code[19 - i]; // 单片机是小端序
+    }
+    content_ptr += 20;
+
+    // 002-实名登记标志 - 大端序 op id ??? 保留后8 byte
+    for (int i = 0; i < 8; i++) {
+        content_ptr[i] = data->register_id[7 - i];
+    }
+    content_ptr += 8;
+    
+    // 003-运行类别(O,强制发送,无需判断使能标志)
+    *content_ptr++ = (uint8_t)data->run_class;
+    
+    // 004-无人机分类(M)
+    *content_ptr++ = (uint8_t)data->uav_type;
+    
+    // 005-遥控站位置类型(M)
+    *content_ptr++ = (uint8_t)data->station_type;
+    
+    // 006-遥控站位置(M):经纬度编码+小端序 其实不用转也行 默认小端序 
+    uint32_t enc_sta_lon = uav_enc_lon(data->station_lon, data->is_station_pos_valid); // 接口里面其实
+    uint32_t enc_sta_lat = uav_enc_lat(data->station_lat, data->is_station_pos_valid);
+    uav_put_uint32_le(enc_sta_lon, content_ptr); content_ptr += 4;
+    uav_put_uint32_le(enc_sta_lat, content_ptr); content_ptr += 4;
+    
+    // 007-遥控站高度(M):大地高度编码+小端序
+    uint16_t enc_sta_alt = uav_enc_geo_alt(data->station_geo_alt, data->is_station_alt_valid);
+    uav_put_uint16_le(enc_sta_alt, content_ptr); content_ptr += 2;
+
+    /********** 第2字节:控制008~014项(按分类顺序填充) **********/
+    packet->data_flag[1] = BYTE2_ALL_FIELDS | MARK_BYTE_NEXT; // 所有项强制发送(含可选011/012/014项)
+    
+    // 008-无人机位置(M):经纬度编码+小端序
+    uint32_t enc_uav_lon = uav_enc_lon(data->uav_lon, data->is_uav_pos_valid);
+    uint32_t enc_uav_lat = uav_enc_lat(data->uav_lat, data->is_uav_pos_valid);
+    uav_put_uint32_le(enc_uav_lon, content_ptr); content_ptr += 4;
+    uav_put_uint32_le(enc_uav_lat, content_ptr); content_ptr += 4;
+    
+    // 009-航迹角(M):编码+小端序
+    uint16_t enc_angle = uav_enc_track_angle(data->track_angle, data->is_track_angle_valid);
+    uav_put_uint16_le(enc_angle, content_ptr); content_ptr += 2;
+    
+    // 010-地速(M):编码+小端序
+    uint16_t enc_speed = uav_enc_ground_speed(data->ground_speed, data->is_ground_speed_valid);
+    uav_put_uint16_le(enc_speed, content_ptr); content_ptr += 2;
+    
+    // 011-相对高度(O,强制发送):编码+小端序
+    uint16_t enc_rel_alt = uav_enc_rel_alt(data->uav_rel_alt, data->is_rel_alt_valid);
+    uav_put_uint16_le(enc_rel_alt, content_ptr); content_ptr += 2;
+    
+    // 012-垂直速度(O,强制发送):编码
+    uint8_t enc_vert_speed = uav_enc_vert_speed(data->uav_vert_speed, data->is_vert_speed_valid);
+    *content_ptr++ = enc_vert_speed;
+    
+    // 013-无人机大地高度(M):编码+小端序
+    uint16_t enc_uav_geo_alt = uav_enc_geo_alt(data->uav_geo_alt, data->is_uav_geo_alt_valid);
+    uav_put_uint16_le(enc_uav_geo_alt, content_ptr); content_ptr += 2;
+    
+    // 014-气压高度(O,强制发送):编码+小端序
+    uint16_t enc_press_alt = uav_enc_geo_alt(data->uav_press_alt, data->is_press_alt_valid);
+    uav_put_uint16_le(enc_press_alt, content_ptr); content_ptr += 2;
+
+    /********** 第3字节:控制015~021项(按分类顺序填充) **********/
+    packet->data_flag[2] = BYTE3_ALL_FIELDS; // 所有项强制发送(均为必选)
+    
+    // 015-运行状态(M)
+    *content_ptr++ = (uint8_t)data->run_state;
+    
+    // 016-坐标系类型(M)
+    *content_ptr++ = (uint8_t)data->coord_type;
+    
+    // 017-水平精度(M)
+    *content_ptr++ = data->hori_accuracy;
+    
+    // 018-垂直精度(M)
+    *content_ptr++ = data->vert_accuracy;
+    
+    // 019-速度精度(M)
+    *content_ptr++ = data->speed_accuracy;
+    
+    // 020-时间戳(M):6字节小端序
+    uav_enc_timestamp(data->timestamp, data->is_timestamp_valid, content_ptr);
+    content_ptr += 6;
+    
+    // 021-时间戳精度(M)
+    *content_ptr++ = data->time_accuracy;
+
+    // 2. 长度校验与赋值
+    uint8_t content_len = (uint8_t)(content_ptr - packet->content);
+    if (content_len == 0 || content_len > MAX_CONTENT_BYTES) return -2;
+    packet->content_len = content_len; // 填充数据包长度
+
+    return 0;
+}
+
+/************************** 核心函数:解包 (根据标识位选择解包字节)**************************/
+int8_t uav_identification_unpack(UavIdentificationData *data, const UavIdentificationPacket *packet) {
+    if (data == NULL || packet == NULL) return -1;
+    if (packet->data_type != PACKET_DATA_TYPE || packet->content_len == 0 || packet->content_len > MAX_CONTENT_BYTES) return -2;
+    uav_identification_data_init(data);
+    const uint8_t *content_ptr = packet->content;
+    const uint8_t *data_flag = packet->data_flag;
+
+    /********** 第1字节:解析001~007项 **********/
+    // 001-唯一产品识别码(M,必须存在) 大端序  如果是小端序单片机需要进行端转换 否则不需要
+    if (!(data_flag[0] & BYTE1_MASK_001)) return -3;
+    memcpy(data->unique_code, content_ptr, 20);
+    content_ptr += 20;
+    
+    // 002-实名登记标志(M,必须存在) 大端序
+    if (!(data_flag[0] & BYTE1_MASK_002)) return -3;
+    memcpy(data->register_id, content_ptr, 8);
+    content_ptr += 8;
+    
+    // // 001-唯一产品识别码(M,必须存在) 大端序 -> 需要反转回小端
+    // if (!(data_flag[0] & BYTE1_MASK_001)) return -3;
+    // for (int i = 0; i < 20; i++) {
+    //     data->unique_code[i] = content_ptr[19 - i];  // 反转回来
+    // }
+    // content_ptr += 20;
+    
+    // // 002-实名登记标志(M,必须存在) 大端序 -> 需要反转回小端
+    // if (!(data_flag[0] & BYTE1_MASK_002)) return -3;
+    // for (int i = 0; i < 8; i++) {
+    //     data->register_id[i] = content_ptr[7 - i];  // 反转回来
+    // }
+    // content_ptr += 8;
+
+    // 003-运行类别(O,收到则置位接收标志)
+    if (data_flag[0] & BYTE1_MASK_003) {
+        data->flag_run_class = true;
+        data->run_class = (UavRunClass)*content_ptr++;
+    }
+    
+    // 004-无人机分类(M,必须存在)
+    if (!(data_flag[0] & BYTE1_MASK_004)) return -3;
+    data->uav_type = (UavType)*content_ptr++;
+    
+    // 005-遥控站位置类型(M,必须存在)
+    if (!(data_flag[0] & BYTE1_MASK_005)) return -3;
+    data->station_type = (UavStationType)*content_ptr++;
+    
+    // 006-遥控站位置(M,必须存在)
+    if (!(data_flag[0] & BYTE1_MASK_006)) return -3;
+    uint32_t enc_sta_lon = uav_get_uint32_le(content_ptr); content_ptr +=4;
+    uint32_t enc_sta_lat = uav_get_uint32_le(content_ptr); content_ptr +=4;
+    data->station_lon = uav_dec_lat_lon(enc_sta_lon);
+    data->station_lat = uav_dec_lat_lon(enc_sta_lat);
+    data->is_station_pos_valid = (enc_sta_lon != 0xFFFFFFFF) && (enc_sta_lat != 0xFFFFFFFF);
+    
+    // 007-遥控站高度(M,必须存在)
+    if (!(data_flag[0] & BYTE1_MASK_007)) return -3;
+    uint16_t enc_sta_alt = uav_get_uint16_le(content_ptr); content_ptr +=2;
+    data->station_geo_alt = uav_dec_geo_alt(enc_sta_alt);
+    data->is_station_alt_valid = (enc_sta_alt != 0);
+
+    /********** 第2字节:解析008~014项 **********/
+    // 008-无人机位置(M,必须存在)
+    if (!(data_flag[1] & BYTE2_MASK_008)) return -3;
+    uint32_t enc_uav_lon = uav_get_uint32_le(content_ptr); content_ptr +=4;
+    uint32_t enc_uav_lat = uav_get_uint32_le(content_ptr); content_ptr +=4;
+    data->uav_lon = uav_dec_lat_lon(enc_uav_lon);
+    data->uav_lat = uav_dec_lat_lon(enc_uav_lat);
+    data->is_uav_pos_valid = (enc_uav_lon != 0xFFFFFFFF) && (enc_uav_lat != 0xFFFFFFFF);
+    
+    // 009-航迹角(M,必须存在)
+    if (!(data_flag[1] & BYTE2_MASK_009)) return -3;
+    uint16_t enc_angle = uav_get_uint16_le(content_ptr); content_ptr +=2;
+    data->track_angle = uav_dec_track_angle(enc_angle);
+    data->is_track_angle_valid = (enc_angle != 0xFFFF);
+    
+    // 010-地速(M,必须存在)
+    if (!(data_flag[1] & BYTE2_MASK_010)) return -3;
+    uint16_t enc_speed = uav_get_uint16_le(content_ptr); content_ptr +=2;
+    data->ground_speed = uav_dec_ground_speed(enc_speed);
+    data->is_ground_speed_valid = (enc_speed != 0xFFFF);
+    
+    // 011-相对高度(O,收到则置位接收标志)
+    if (data_flag[1] & BYTE2_MASK_011) {
+        data->flag_rel_alt = true;
+        uint16_t enc_rel_alt = uav_get_uint16_le(content_ptr); content_ptr +=2;
+        data->uav_rel_alt = uav_dec_rel_alt(enc_rel_alt);
+        data->is_rel_alt_valid = (enc_rel_alt != 0);
+    }
+    
+    // 012-垂直速度(O,收到则置位接收标志)
+    if (data_flag[1] & BYTE2_MASK_012) {
+        data->flag_vert_speed = true;
+        uint8_t enc_vert = *content_ptr++;
+        data->uav_vert_speed = uav_dec_vert_speed(enc_vert);
+        data->is_vert_speed_valid = (enc_vert != 0xFF);
+    }
+    
+    // 013-无人机大地高度(M,必须存在)
+    if (!(data_flag[1] & BYTE2_MASK_013)) return -3;
+    uint16_t enc_uav_geo = uav_get_uint16_le(content_ptr); content_ptr +=2;
+    data->uav_geo_alt = uav_dec_geo_alt(enc_uav_geo);
+    data->is_uav_geo_alt_valid = (enc_uav_geo != 0);
+    
+    // 014-气压高度(O,收到则置位接收标志)
+    if (data_flag[1] & BYTE2_MASK_014) {
+        data->flag_press_alt = true;
+        uint16_t enc_press = uav_get_uint16_le(content_ptr); content_ptr +=2;
+        data->uav_press_alt = uav_dec_geo_alt(enc_press);
+        data->is_press_alt_valid = (enc_press != 0);
+    }
+
+    /********** 第3字节:解析015~021项 **********/
+    // 015-运行状态(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_015)) return -3;
+    data->run_state = (UavRunState)*content_ptr++;
+    
+    // 016-坐标系类型(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_016)) return -3;
+    data->coord_type = (UavCoordType)*content_ptr++;
+    
+    // 017-水平精度(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_017)) return -3;
+    data->hori_accuracy = (UavHorizontalAccuracy_t)*content_ptr++;
+    
+    // 018-垂直精度(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_018)) return -3;
+    data->vert_accuracy = (UavVerticalAccuracy_t)*content_ptr++;
+    
+    // 019-速度精度(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_019)) return -3;
+    data->speed_accuracy = (UAVSpeedAccuracy_t)*content_ptr++;
+    
+    // 020-时间戳(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_020)) return -3;
+    data->timestamp = uav_dec_timestamp(content_ptr); content_ptr +=6;
+    data->is_timestamp_valid = (data->timestamp != 0);
+    
+    // 021-时间戳精度(M,必须存在)
+    if (!(data_flag[2] & BYTE3_MASK_021)) return -3;
+    data->time_accuracy = (UavTimestampAccuracy_t)*content_ptr++;
+
+    return 0;
+}
+
+/************************** 调试函数:打印数据包 **************************/
+void uav_identification_packet_print(const UavIdentificationPacket *packet) {
+    if (packet == NULL) return;
+    uint8_t major = VERSION_DECODE_MAJOR(packet->version);
+    uint8_t minor = VERSION_DECODE_MINOR(packet->version);
+    printf("==================== UAV Packet (GB46750-2025) ====================\n");
+    printf("Data Type: 0x%02X | Version: V%d.%d\n",
+           packet->data_type, major, minor);
+    printf("Content Len: %d Byte | Data Flag: 0x%02X 0x%02X 0x%02X\n",
+           packet->content_len, packet->data_flag[0], packet->data_flag[1], packet->data_flag[2]);
+    printf("Content (Hex): ");
+    for (int i = 0; i < packet->content_len; i++) {
+        printf("%02X ", packet->content[i]);
+        if ((i+1) % 16 == 0) printf("\n\t\t\t");
+    }
+    printf("\n===================================================================\n");
+}
+
+/************************** 调试函数:打印原始数据 **************************/
+void uav_identification_data_print(const UavIdentificationData *data) {
+    if (data == NULL) return;
+    printf("==================== UAV Raw Data (Decoded) ====================\n");
+    // 身份信息
+    printf("Unique Code: %s | Register Flag: %s\n", data->unique_code, data->register_id);
+    printf("UAV Type: %d | Run State: %d | Coord Type: %d\n",
+           data->uav_type, data->run_state, data->coord_type);
+    // 位置信息
+    printf("Station Lon: %.7f° | Lat: %.7f° | Alt: %.1fm (Valid: %d)\n",
+           data->station_lon, data->station_lat, data->station_geo_alt, data->is_station_pos_valid);
+    printf("UAV Lon: %.7f° | Lat: %.7f° | Geo Alt: %.1fm (Valid: %d)\n",
+           data->uav_lon, data->uav_lat, data->uav_geo_alt, data->is_uav_pos_valid);
+    // 运动信息
+    printf("Track Angle: %.1f° (Valid: %d) | Ground Speed: %.1fm/s (Valid: %d)\n",
+           data->track_angle, data->is_track_angle_valid, data->ground_speed, data->is_ground_speed_valid);
+    // 精度信息
+    printf("Hori Acc: %d | Vert Acc: %d | Speed Acc: %d\n",
+           data->hori_accuracy, data->vert_accuracy, data->speed_accuracy);
+    printf("Timestamp: %llums | Time Acc: %d (Valid: %d)\n",
+           (unsigned long long)data->timestamp, data->time_accuracy, data->is_timestamp_valid);
+    // 可选信息(强制发送,必然存在)
+    printf("Run Class: %d (Received: %d)\n", data->run_class, data->flag_run_class);
+    printf("Relative Alt: %.1fm (Valid: %d)\n", data->uav_rel_alt, data->is_rel_alt_valid);
+    printf("Vert Speed: %.1fm/s (Valid: %d)\n", data->uav_vert_speed, data->is_vert_speed_valid);
+    printf("Press Alt: %.1fm (Valid: %d)\n", data->uav_press_alt, data->is_press_alt_valid);
+    printf("==================================================================\n");
+}

+ 326 - 0
RemoteIDModule/did_GB_2025.h

@@ -0,0 +1,326 @@
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <math.h>
+
+/************************** 标准编码规则宏定义(GB46750-2025表3) **************************/
+// 数据类型固定值(表1要求)
+#define PACKET_DATA_TYPE        0xFF
+// 版本号宏(标准要求:前3位固定001,后5位0~63,即V1.X)
+#define VERSION_MAJOR_FIXED     1               // 主版本固定为1(前3位001)
+#define VERSION_MINOR_FIXED     0
+#define VERSION_ENCODE    ((((VERSION_MAJOR_FIXED) & 0x07) << 5) | ((VERSION_MINOR_FIXED) & 0x3F))
+#define VERSION_DECODE_MAJOR(ver) ((ver) >> 5)   // 从编码值解码主版本
+#define VERSION_DECODE_MINOR(ver) ((ver) & 0x3F) // 从编码值解码从版本
+
+// 基础数据标识字节数(3字节),扩展标志位默认0(表2要求)
+#define BASE_DATA_FLAG_BYTES    3
+// 最大数据内容项字节数(1~200)(表1要求)
+#define MAX_CONTENT_BYTES       200
+// 字符串填充字符(NULL)(表3要求)
+#define FILL_CHAR               '\0'
+
+// 经纬度放大倍数(×10^7)(表3要求)
+#define LAT_LON_SCALE           10000000LL
+// 大地高度/气压高度:(h+1000)×2,分辨率0.5m(表3要求)
+#define GEO_ALT_OFFSET          1000
+#define GEO_ALT_SCALE           2
+// 相对高度:(h+9000)×2,分辨率0.5m(表3要求)
+#define REL_ALT_OFFSET          9000
+#define REL_ALT_SCALE           2
+// 航迹角/地速放大倍数(×10),分辨率0.1°/0.1m/s(表3要求)
+#define ANGLE_SPEED_SCALE       10
+// 垂直速度放大倍数(×2),分辨率0.5m/s(表3要求)
+#define VERT_SPEED_SCALE        2
+// 定义总编码发送字节数
+#define EXTEND_N_BYTE (0) // 除了默认3字节 扩展的字节
+#define EXTEND_N_INFO (0) // 除了默认3字节数据包字节数 扩展的包数据数
+#define SEND_ENCODE_PACKAGE_HEAD_LEN (0x3)
+#define SEND_ENCODE_PACKAGE_DATA_MARK (0x3+EXTEND_N_BYTE)
+#define SEND_ENCODE_PACKAGE_INFO (72)
+#define SEND_ENCODE_PACKAGE_LEN (SEND_ENCODE_PACKAGE_HEAD_LEN+SEND_ENCODE_PACKAGE_DATA_MARK+SEND_ENCODE_PACKAGE_INFO)
+
+/************************** 按字节分类的掩码宏定义 **************************/
+// 第1字节:控制001~007项(表2对应关系)
+#define BYTE1_MASK_001  0x80  // 唯一产品识别码(M)
+#define BYTE1_MASK_002  0x40  // 实名登记标志(M)
+#define BYTE1_MASK_003  0x20  // 运行类别(O)
+#define BYTE1_MASK_004  0x10  // 无人机分类(M)
+#define BYTE1_MASK_005  0x08  // 遥控站位置类型(M)
+#define BYTE1_MASK_006  0x04  // 遥控站位置(M)
+#define BYTE1_MASK_007  0x02  // 遥控站高度(M)
+
+// 第2字节:控制008~014项(表2对应关系)
+#define BYTE2_MASK_008  0x80  // 无人机位置(M)
+#define BYTE2_MASK_009  0x40  // 航迹角(M)
+#define BYTE2_MASK_010  0x20  // 地速(M)
+#define BYTE2_MASK_011  0x10  // 相对高度(O)
+#define BYTE2_MASK_012  0x08  // 垂直速度(O)
+#define BYTE2_MASK_013  0x04  // 无人机大地高度(M)
+#define BYTE2_MASK_014  0x02  // 气压高度(O)
+
+// 第3字节:控制015~021项(表2对应关系)
+#define BYTE3_MASK_015  0x80  // 运行状态(M)
+#define BYTE3_MASK_016  0x40  // 坐标系类型(M)
+#define BYTE3_MASK_017  0x20  // 水平精度(M)
+#define BYTE3_MASK_018  0x10  // 垂直精度(M)
+#define BYTE3_MASK_019  0x08  // 速度精度(M)
+#define BYTE3_MASK_020  0x04  // 时间戳(M)
+#define BYTE3_MASK_021  0x02  // 时间戳精度(M)
+// 下一个字节是否是标识字节
+#define MARK_BYTE_NEXT (0x01)
+// 全字段使能掩码(可选字段强制发送)
+// 第1字节所有必选+可选字段掩码(不含扩展位)
+#define BYTE1_ALL_FIELDS (BYTE1_MASK_001 | BYTE1_MASK_002 | BYTE1_MASK_003 | \
+                          BYTE1_MASK_004 | BYTE1_MASK_005 | BYTE1_MASK_006 | \
+                          BYTE1_MASK_007)
+
+#define BYTE2_ALL_FIELDS   (BYTE2_MASK_008 | BYTE2_MASK_009 | BYTE2_MASK_010 | \
+                            BYTE2_MASK_011 | BYTE2_MASK_012 | BYTE2_MASK_013 | \
+                            BYTE2_MASK_014)  // 0xFE
+
+#define BYTE3_ALL_FIELDS   (BYTE3_MASK_015 | BYTE3_MASK_016 | BYTE3_MASK_017 | \
+                            BYTE3_MASK_018 | BYTE3_MASK_019 | BYTE3_MASK_020 | \
+                            BYTE3_MASK_021)  // 0xFE
+
+/************************** 枚举类型定义(GB46750-2025表2/表3) **************************/
+// 坐标系类型
+typedef enum {
+    COORD_WGS84       = 0,    // WGS-84(默认)
+    COORD_CGCS2000    = 1,    // 2000国家大地坐标系
+    COORD_RESERVED    = 2     // 预留
+} UavCoordType;
+
+// 无人机分类
+typedef enum {
+    UAV_TYPE_MICRO    = 0,    // 微型
+    UAV_TYPE_LIGHT    = 1,    // 轻型
+    UAV_TYPE_SMALL    = 2,    // 小型
+    UAV_TYPE_MEDIUM   = 3,    // 中型
+    UAV_TYPE_LARGE    = 4,    // 大型
+    UAV_TYPE_RESERVED = 5     // 预留
+} UavType;
+
+// 无人机运行状态
+typedef enum {
+    UAV_STATE_UNREPORTED      = 0,    // 未报告
+    UAV_STATE_GROUND          = 1,    // 地面
+    UAV_STATE_AIR             = 2,    // 空中
+    UAV_STATE_EMERGENCY       = 3,    // 紧急状态
+    UAV_STATE_TX_FAIL_NORMAL  = 4,    // 发送失效-非紧急
+    UAV_STATE_TX_FAIL_EMERG   = 5,    // 发送失效-紧急
+    UAV_STATE_RESERVED        = 6     // 预留
+} UavRunState;
+
+// 遥控站位置类型
+typedef enum {
+    STATION_TYPE_TAKEOFF = 0,    // 起飞点位置
+    STATION_TYPE_REMOTE  = 1,    // 遥控站位置
+    STATION_TYPE_RESERVED= 2     // 预留
+} UavStationType;
+
+// 无人机运行类别
+typedef enum {
+    UAV_RUN_UNDEFINED = 0,    // 未定义
+    UAV_RUN_OPEN      = 1,    // 开放类
+    UAV_RUN_SPECIFIC  = 2,    // 特定类
+    UAV_RUN_APPROVED  = 3,    // 审定类
+    UAV_RUN_RESERVED  = 4     // 预留
+} UavRunClass;
+
+
+typedef enum UavHorizontalAccuracy {
+    UAV_HOR_ACC_UNKNOWN = 0,
+    UAV_HOR_ACC_10NM = 1,      // Nautical Miles. 18.52 km
+    UAV_HOR_ACC_4NM = 2,       // 7.408 km
+    UAV_HOR_ACC_2NM = 3,       // 3.704 km
+    UAV_HOR_ACC_1NM = 4,       // 1.852 km
+    UAV_HOR_ACC_0_5NM = 5,     // 926 m
+    UAV_HOR_ACC_0_3NM = 6,     // 555.6 m
+    UAV_HOR_ACC_0_1NM = 7,     // 185.2 m
+    UAV_HOR_ACC_0_05NM = 8,    // 92.6 m
+    UAV_HOR_ACC_30_METER = 9,
+    UAV_HOR_ACC_10_METER = 10,
+    UAV_HOR_ACC_3_METER = 11,
+    UAV_HOR_ACC_1_METER = 12,
+    // 13 to 15 reserved
+} UavHorizontalAccuracy_t;
+
+
+typedef enum UavVerticalAccuracy {
+    UAV_VER_ACC_UNKNOWN = 0,
+    UAV_VER_ACC_150_METER = 1,
+    UAV_VER_ACC_45_METER = 2,
+    UAV_VER_ACC_25_METER = 3,
+    UAV_VER_ACC_10_METER = 4,
+    UAV_VER_ACC_3_METER = 5,
+    UAV_VER_ACC_1_METER = 6,
+    // 7 to 15 reserved
+} UavVerticalAccuracy_t;
+
+typedef enum UAVSpeedAccuracy {
+    UAV_SPEED_ACC_UNKNOWN = 0,
+    UAV_SPEED_ACC_10_METERS_PER_SECOND = 1,
+    UAV_SPEED_ACC_3_METERS_PER_SECOND = 2,
+    UAV_SPEED_ACC_1_METERS_PER_SECOND = 3,
+    UAV_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
+    // 5 to 15 reserved
+}  UAVSpeedAccuracy_t;
+
+typedef enum UavTimestampAccuracy {
+    UAV_TIME_ACC_UNKNOWN = 0,
+    UAV_TIME_ACC_0_5_SECOND = 1,
+    UAV_TIME_ACC_0_4_SECOND = 2,
+    UAV_TIME_ACC_0_3_SECOND = 3,
+    UAV_TIME_ACC_0_2_SECOND = 4,
+    UAV_TIME_ACC_0_1_SECOND = 5,
+    UAV_TIME_ACC_0_05_SECOND = 6,
+    UAV_TIME_ACC_0_02_SECOND = 7,
+    UAV_TIME_ACC_0_01_SECOND = 8,
+} UavTimestampAccuracy_t;
+
+/************************** 核心数据结构体(存储原始物理值) **************************/
+// 无人机运行识别原始数据(上层业务直接赋值,无需关心编码规则)
+typedef struct {
+    // 必选-身份信息
+    char unique_code[20+1];        // 001-唯一产品识别码(20byte,ASCII) 大端序
+    char register_id[8+1];       // 002-实名登记标志(8byte,ASCII,后8位) 大端序
+    UavType uav_type;            // 004-无人机分类
+    UavRunState run_state;       // 015-运行状态
+    UavCoordType coord_type;     // 016-坐标系类型
+
+    // 必选-位置信息(原始值:经纬度°,高度m;西经/南纬为负)
+    UavStationType station_type; // 005-遥控站位置类型
+    double station_lon;          // 006-遥控站经度
+    double station_lat;          // 006-遥控站纬度
+    double station_geo_alt;      // 007-遥控站大地高度
+    double uav_lon;              // 008-无人机经度
+    double uav_lat;              // 008-无人机纬度
+    double uav_geo_alt;          // 013-无人机大地高度
+
+    // 必选-运动信息(原始值:航迹角°,地速m/s)
+    double track_angle;          // 009-航迹角(真北顺时针,0~359.9)
+    double ground_speed;         // 010-地速(≥0)
+
+    // 必选-精度信息(按表3取值)
+    UavHorizontalAccuracy_t hori_accuracy;       // 017-水平精度
+    UavVerticalAccuracy_t vert_accuracy;       // 018-垂直精度
+    UAVSpeedAccuracy_t speed_accuracy;      // 019-速度精度
+    uint64_t timestamp;          // 020-时间戳(ms,Unix)
+    UavTimestampAccuracy_t time_accuracy;       // 021-时间戳精度
+
+    // 可选-扩展信息(强制发送,无需外部使能)
+    UavRunClass run_class;       // 003-运行类别
+    double uav_rel_alt;          // 011-相对高度(m,基于起飞点)
+    double uav_vert_speed;       // 012-垂直速度(m/s,正升负降)
+    double uav_press_alt;        // 014-气压高度(m,101.325kPa为基准)
+
+    // 字段有效性标志(是否有效,无效则编码为未知值)
+    bool is_station_pos_valid;   // 遥控站经纬度
+    bool is_uav_pos_valid;       // 无人机经纬度
+    bool is_station_alt_valid;   // 遥控站大地高度
+    bool is_uav_geo_alt_valid;   // 无人机大地高度
+    bool is_track_angle_valid;   // 航迹角
+    bool is_ground_speed_valid;  // 地速
+    bool is_timestamp_valid;     // 时间戳
+    bool is_rel_alt_valid;       // 相对高度
+    bool is_vert_speed_valid;    // 垂直速度
+    bool is_press_alt_valid;     // 气压高度
+
+    // 可选字段接收标志(解包时自动置位,组包时无需关注)
+    bool flag_run_class;         // 003-运行类别是否接收
+    bool flag_rel_alt;           // 011-相对高度是否接收
+    bool flag_vert_speed;        // 012-垂直速度是否接收
+    bool flag_press_alt;         // 014-气压高度是否接收
+} UavIdentificationData;
+
+/************************** 数据包结构体(GB46750-2025图3) **************************/
+// 无人机运行识别数据包(组包后/解包前的字节流载体)
+typedef struct {
+    uint8_t data_type;           // 1byte-数据类型(固定0xFF)
+    uint8_t version;             // 1byte-版本号(3+5bit,V1.X)
+    uint8_t content_len;          // 1byte-数据内容项字节数
+    uint8_t data_flag[BASE_DATA_FLAG_BYTES]; // 3byte-基础数据标识位
+    uint8_t content[MAX_CONTENT_BYTES];      // 可变长-数据内容项(编码后)
+} UavIdentificationPacket;
+
+/************************** 工具函数:字节序转换 **************************/
+// 16位无符号整数转小端序字节
+void uav_put_uint16_le(uint16_t val, uint8_t *buf);
+// 32位无符号整数转小端序字节
+void uav_put_uint32_le(uint32_t val, uint8_t *buf);
+// 小端序字节转16位无符号整数
+uint16_t uav_get_uint16_le(const uint8_t *buf);
+// 小端序字节转32位无符号整数
+uint32_t uav_get_uint32_le(const uint8_t *buf);
+
+/************************** 编码函数:原始值→标准编码值 **************************/
+// 经纬度编码(°→32位小端序整数,×10^7)
+uint32_t uav_enc_lat(double lat, bool is_valid);
+uint32_t uav_enc_lon(double lon, bool is_valid);
+// 大地高度/气压高度编码(m→16位小端序整数,(h+1000)×2)
+uint16_t uav_enc_geo_alt(double alt, bool is_valid);
+// 相对高度编码(m→16位小端序整数,(h+9000)×2)
+uint16_t uav_enc_rel_alt(double alt, bool is_valid);
+// 航迹角编码(°→16位小端序整数,×10)
+uint16_t uav_enc_track_angle(double angle, bool is_valid);
+// 地速编码(m/s→16位小端序整数,×10)
+uint16_t uav_enc_ground_speed(double speed, bool is_valid);
+// 垂直速度编码(m/s→1字节,bit7表方向,数值×2)
+uint8_t uav_enc_vert_speed(double v_speed, bool is_valid);
+// 时间戳编码(ms→6字节小端序,仅取低6字节)
+void uav_enc_timestamp(uint64_t timestamp, bool is_valid, uint8_t *buf);
+// 设置数据包版本号(从版本X→V1.X,返回1字节编码值)
+uint8_t uav_set_packet_version(uint8_t minor);
+
+/************************** 解码函数:标准编码值→原始值 **************************/
+// 经纬度解码(32位编码值→°,÷10^7)
+double uav_dec_lat(uint32_t enc_val);
+double uav_dec_lon(uint32_t enc_val);
+// 大地高度/气压高度解码(16位编码值→m,(val/2)-1000)
+double uav_dec_geo_alt(uint16_t enc_val);
+// 相对高度解码(16位编码值→m,(val/2)-9000)
+double uav_dec_rel_alt(uint16_t enc_val);
+// 航迹角解码(16位编码值→°,÷10)
+double uav_dec_track_angle(uint16_t enc_val);
+// 地速解码(16位编码值→m/s,÷10)
+double uav_dec_ground_speed(uint16_t enc_val);
+// 垂直速度解码(1字节编码值→m/s,正升负降)
+double uav_dec_vert_speed(uint8_t enc_val);
+// 时间戳解码(6字节小端序→ms,Unix)
+uint64_t uav_dec_timestamp(const uint8_t *buf);
+
+/************************** 核心函数:组包+解包 **************************/
+// 初始化原始数据结构体(填充默认值/空字符/标志位false)
+void uav_identification_data_init(UavIdentificationData *data);
+// 组包:原始数据→标准数据包(返回0成功,-1参数错,-2内容超长)
+int8_t uav_identification_pack(UavIdentificationPacket *packet, const UavIdentificationData *data );
+// 解包:标准数据包→原始数据(返回0成功,-1参数错,-2包格式错,-3数据标识位异常)
+int8_t uav_identification_unpack(UavIdentificationData *data, const UavIdentificationPacket *packet);
+// 打印数据包(调试用,输出十六进制+关键字段)
+void uav_identification_packet_print(const UavIdentificationPacket *packet);
+// 打印原始数据(调试用,输出解码后的物理值)
+void uav_identification_data_print(const UavIdentificationData *data);
+
+
+
+// 组wifi和ble包函数
+int did_GB2025_message_build_pack(UavIdentificationData  *UAS_Data, uint8_t *pack, size_t buflen);
+
+int did_GB2025_wifi_build_nan_sync_beacon_frame(char *mac, uint8_t *buf, size_t buf_size);
+
+int did_GB2025_wifi_build_message_pack_nan_action_frame(UavIdentificationData  *UAS_Data, char *mac,
+                                                  uint8_t send_counter,
+                                                  uint8_t *buf, size_t buf_size);
+
+int did_GB2025_wifi_build_message_pack_beacon_frame(UavIdentificationData  *UAS_Data, char *mac,
+                                              const char *SSID, size_t SSID_len,
+                                              uint16_t interval_tu, uint8_t send_counter,
+                                              uint8_t *buf, size_t buf_size);
+
+int did_GB2025_message_process_pack(UavIdentificationData  *UAS_Data, uint8_t *pack, size_t buflen);
+
+int did_GB2025_wifi_receive_message_pack_nan_action_frame(UavIdentificationData  *UAS_Data,
+                                                    char *mac, uint8_t *buf, size_t buf_size);

+ 12 - 9
RemoteIDModule/efuse.cpp

@@ -31,29 +31,32 @@ static const struct {
 /*
 /*
   set efuses to prevent firmware upload except via signed web
   set efuses to prevent firmware upload except via signed web
   interface
   interface
+  当模块被设置为最高级别锁定(lock_level≥2)时,检查并永久熔断 ESP32 的关键 eFuse 位
+  (如禁用 JTAG、禁用固件烧录、禁用 NVS 擦除等),实现硬件级防篡改,且熔断后无法恢复。
  */
  */
 void set_efuses(void)
 void set_efuses(void)
 {
 {
     bool some_unset = false;
     bool some_unset = false;
     for (const auto &f : fuses) {
     for (const auto &f : fuses) {
-        const bool v = esp_efuse_read_field_bit(f.desc);
-        Serial.printf("%s = %u\n", f.name, unsigned(v));
-        some_unset |= !v;
+        const bool v = esp_efuse_read_field_bit(f.desc); // 读取单个eFuse位的值
+
+        Serial.printf("%s = %u\n", f.name, unsigned(v));  // 打印当前状态(0=未熔断,1=已熔断)
+        some_unset |= !v; // 只要有一个eFuse位未熔断,some_unset=true
     }
     }
-    if (g.lock_level >= 2 && some_unset) {
-        Serial.printf("Burning efuses\n");
+    if (g.lock_level >= 2 && some_unset) { // 仅当:1.锁定级别≥2(最高级锁定);2.有未熔断的熔丝 → 执行熔断
+        Serial.printf("Burning efuses\n"); 
         esp_efuse_batch_write_begin();
         esp_efuse_batch_write_begin();
         for (const auto &f : fuses) {
         for (const auto &f : fuses) {
-            const bool v = esp_efuse_read_field_bit(f.desc);
+            const bool v = esp_efuse_read_field_bit(f.desc); // 启动eFuse批量写入(ESP32要求批量操作)
             if (!v) {
             if (!v) {
                 Serial.printf("%s -> 1\n", f.name);
                 Serial.printf("%s -> 1\n", f.name);
-                auto ret = esp_efuse_write_field_bit(f.desc);
+                auto ret = esp_efuse_write_field_bit(f.desc); // 熔断该位(写入1)
                 if (ret != ESP_OK) {
                 if (ret != ESP_OK) {
-                    Serial.printf("%s change failed\n", f.name);
+                    Serial.printf("%s change failed\n", f.name); // 打印熔断失败日志
                 }
                 }
             }
             }
         }
         }
-        esp_efuse_batch_write_commit();
+        esp_efuse_batch_write_commit(); // 提交批量写入(真正执行熔断)
     }
     }
 }
 }
 
 

+ 94 - 71
RemoteIDModule/mavlink.cpp

@@ -17,24 +17,25 @@ mavlink_system_t mavlink_system = {0, MAV_COMP_ID_ODID_TXRX_1};
 
 
 /*
 /*
   send a buffer out a MAVLink channel
   send a buffer out a MAVLink channel
+  函数作用:把字节缓冲区通过指定MAVLink通道发送出去
  */
  */
 void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
 void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
 {
 {
     if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
     if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
-        return;
+        return; // 通道号超出支持范围  通道对应的串口未绑定(空指针)
     }
     }
-    auto &serial = *serial_ports[uint8_t(chan)];
-    serial.write(buf, len);
+    auto &serial = *serial_ports[uint8_t(chan)]; // 从全局数组中获取通道对应的物理串口引用
+    serial.write(buf, len); // 把字节缓冲区写入串口(核心:完成物理发送)
 }
 }
 
 
 /*
 /*
   abstraction for MAVLink on a serial port
   abstraction for MAVLink on a serial port
  */
  */
 MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
 MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
-    serial(_serial),
-    chan(_chan)
+    serial(_serial), // 绑定物理串口(如Serial1)到类成员serial
+    chan(_chan) // 绑定MAVLink通道号(如MAVLINK_COMM_0)到类成员chan
 {
 {
-    serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial;
+    serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial; // 函数体:将串口指针存入全局数组serial_ports
 }
 }
 
 
 void MAVLinkSerial::init(void)
 void MAVLinkSerial::init(void)
@@ -42,41 +43,49 @@ void MAVLinkSerial::init(void)
     // print banner at startup
     // print banner at startup
     serial.printf("ArduRemoteID version %u.%u %08x\n",
     serial.printf("ArduRemoteID version %u.%u %08x\n",
                   FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
                   FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
-    mavlink_system.sysid = g.mavlink_sysid;
+    mavlink_system.sysid = g.mavlink_sysid; // 初始化MAVLink系统ID:从全局配置g中读取预设的mavlink_sysid
 }
 }
-
+// 地面站(如 Mission Planner)会向 RemoteID 模块发送 PARAM_REQUEST_LIST 消息,
+// 请求获取所有参数(如 UIN、运营人 ID、发送频率等),
+// 这段代码就是按 50ms 间隔逐个回复参数值,方便地面站配置 / 查看 RemoteID 模块的参数。
 void MAVLinkSerial::update(void)
 void MAVLinkSerial::update(void)
 {
 {
     const uint32_t now_ms = millis();
     const uint32_t now_ms = millis();
 
 
-    if (mavlink_system.sysid != 0) {
-        update_send();
-    } else if (g.mavlink_sysid != 0) {
-        mavlink_system.sysid = g.mavlink_sysid;
-    } else if (now_ms - last_hb_warn_ms >= 2000) {
+    if (mavlink_system.sysid != 0) {  // 分支1:如果MAVLink系统ID已初始化(非0)
+        update_send(); // 执行MAVLink消息发送逻辑
+    } else if (g.mavlink_sysid != 0) { // 分支2:如果系统ID未初始化,但配置了g.mavlink_sysid(外部配置)
+        mavlink_system.sysid = g.mavlink_sysid;  // 用配置值初始化系统ID
+    } else if (now_ms - last_hb_warn_ms >= 2000) {  // 分支3:系统ID未初始化,且无配置 → 打印心跳等待提示(每2秒一次)
         last_hb_warn_ms = millis();
         last_hb_warn_ms = millis();
-        serial.printf("Waiting for heartbeat\n");
+        serial.printf("Waiting for heartbeat\n"); // 串口打印:等待飞控心跳
+        // serial.printf("等待心跳包\n");
     }
     }
-    update_receive();
-
+    update_receive(); // 接收串口数据,解析飞控发来的MAVLink消息
+    // 如果参数请求未完成,且距离上次发送超过50ms
     if (param_request_last_ms != 0 && now_ms - param_request_last_ms > 50) {
     if (param_request_last_ms != 0 && now_ms - param_request_last_ms > 50) {
         param_request_last_ms = now_ms;
         param_request_last_ms = now_ms;
         float value;
         float value;
-        if (param_next->get_as_float(value)) {
-            mavlink_msg_param_value_send(chan,
-                                         param_next->name, value,
-                                         MAV_PARAM_TYPE_REAL32,
-                                         g.param_count_float(),
-                                         g.param_index_float(param_next));
+        if (param_next->get_as_float(value)) { // 读取下一个参数的浮点值(如UIN、运营人ID转的浮点/字符串)
+            // 发送MAVLink PARAM_VALUE消息(回复地面站的参数查询)
+            mavlink_msg_param_value_send(chan, // MAVLink通道
+                                         param_next->name, value, // 参数名(如"UIN"、"OPERATOR_ID") // 参数值
+                                         MAV_PARAM_TYPE_REAL32, // 参数类型(浮点型)
+                                         g.param_count_float(), // 浮点参数总数
+                                         g.param_index_float(param_next)); // 当前参数索引
         }
         }
-        param_next++;
-        if (param_next->ptype == Parameters::ParamType::NONE) {
+        param_next++; // 指向下一个参数
+        if (param_next->ptype == Parameters::ParamType::NONE) { // 如果参数遍历完成 → 重置状态
             param_next = nullptr;
             param_next = nullptr;
             param_request_last_ms = 0;
             param_request_last_ms = 0;
         }
         }
     }
     }
 }
 }
-
+/*
+ RemoteID 模块每秒向飞控 / 地面站发送 MAVLink 心跳包(标识自身为 ODID 设备),
+ 并附带发送无人机解锁状态—— 让飞控 / 地面站识别 
+ “这是一个 RemoteID 设备”,并知晓无人机的解锁 / 上锁状态
+*/
 void MAVLinkSerial::update_send(void)
 void MAVLinkSerial::update_send(void)
 {
 {
     uint32_t now_ms = millis();
     uint32_t now_ms = millis();
@@ -95,54 +104,59 @@ void MAVLinkSerial::update_send(void)
     }
     }
 }
 }
 
 
-void MAVLinkSerial::update_receive(void)
+void MAVLinkSerial::update_receive(void) // 流式处理 一次处理缓冲区所有数据 然后解析
 {
 {
     // receive new packets
     // receive new packets
-    mavlink_message_t msg;
-    mavlink_status_t status;
-    status.packet_rx_drop_count = 0;
+    mavlink_message_t msg;    // 1. 定义MAVLink消息结构体(存储解析后的完整消息)
+    mavlink_status_t status;  // 2. 定义MAVLink状态结构体(记录解析状态,如丢包、同步等)
+    status.packet_rx_drop_count = 0;   // 3. 重置丢包计数(初始化解析状态)
 
 
-    const uint16_t nbytes = serial.available();
-    for (uint16_t i=0; i<nbytes; i++) {
-        const uint8_t c = (uint8_t)serial.read();
+    const uint16_t nbytes = serial.available(); // 4. 获取串口缓冲区中待读取的字节数
+    for (uint16_t i=0; i<nbytes; i++) { // 5. 遍历读取所有字节,逐字节解析
+        const uint8_t c = (uint8_t)serial.read();  // 6. 读取1个字节(飞控发来的MAVLink数据)
         // Try to get a new message
         // Try to get a new message
-        if (mavlink_parse_char(chan, c, &msg, &status)) {
-            process_packet(status, msg);
+        if (mavlink_parse_char(chan, c, &msg, &status)) { // 7. 核心:逐字节解析MAVLink消息
+            process_packet(status, msg); // 8. 解析出完整消息后,交给process_packet()处理(提取位置/状态等核心数据)
         }
         }
     }
     }
 }
 }
 
 
 /*
 /*
   printf via MAVLink STATUSTEXT for debugging
   printf via MAVLink STATUSTEXT for debugging
+  传统串口打印需要现场接电脑调试,而 MAVLink STATUSTEXT 消息可通过飞控转发到地面站,
+  即使无人机在空中,也能实时看到 RemoteID 模块的调试日志;
  */
  */
 void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
 void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
 {
 {
-    va_list arg_list;
-    char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
-    va_start(arg_list, fmt);
-    vsnprintf(text, sizeof(text), fmt, arg_list);
-    va_end(arg_list);
-    mavlink_msg_statustext_send(chan,
-                                severity,
-                                text,
-                                0, 0);
+    va_list arg_list;  // 1. 定义可变参数列表(处理printf风格的可变参数)
+    char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; // 2. 定义日志文本缓冲区:长度=STATUSTEXT消息的text字段长度+1(+1是字符串结束符)
+    va_start(arg_list, fmt); // 3. 初始化可变参数列表,指向fmt后的第一个参数
+    vsnprintf(text, sizeof(text), fmt, arg_list);  // 4. 格式化字符串:把fmt+可变参数写入text缓冲区,限制长度为缓冲区大小
+    va_end(arg_list); // 5. 结束可变参数列表
+    // 6. 发送MAVLink STATUSTEXT消息
+    mavlink_msg_statustext_send(chan,  // MAVLink通道号(对应飞控串口
+                                severity, // 日志级别
+                                text, // 格式化后的日志文本
+                                0, 0); // 扩展参数(MAVLink 2.0新增,暂用0)
 }
 }
-
+/*
+专门针对 OpenDroneID(ODID)标准的各类消息做解析,同时处理参数交互、安全指令等辅助逻辑
+*/
 void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
 void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
 {
 {
     const uint32_t now_ms = millis();
     const uint32_t now_ms = millis();
     switch (msg.msgid) {
     switch (msg.msgid) {
-    case MAVLINK_MSG_ID_HEARTBEAT: {
+    case MAVLINK_MSG_ID_HEARTBEAT: { // 心跳消息处理
         mavlink_heartbeat_t hb;
         mavlink_heartbeat_t hb;
-        if (mavlink_system.sysid == 0) {
-            mavlink_msg_heartbeat_decode(&msg, &hb);
+        if (mavlink_system.sysid == 0) { // 系统ID未初始化时
+            mavlink_msg_heartbeat_decode(&msg, &hb); // 仅接收飞控(非地面站GCS)的心跳,初始化模块sysid
             if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
             if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
-                mavlink_system.sysid = msg.sysid;
+                mavlink_system.sysid = msg.sysid; // 过滤地面站(GCS)心跳:只从飞控获取 sysid,防止地面站干扰
             }
             }
         }
         }
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: { // 位置消息 无人机经纬度、高度、速度、timestamp(时间戳)等位置信息
         mavlink_msg_open_drone_id_location_decode(&msg, &location);
         mavlink_msg_open_drone_id_location_decode(&msg, &location);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got Location\n");
             Serial.printf("MAVLink: got Location\n");
@@ -155,27 +169,27 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         last_location_ms = now_ms;
         last_location_ms = now_ms;
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: { // 基础 ID 消息
         mavlink_open_drone_id_basic_id_t basic_id_tmp;
         mavlink_open_drone_id_basic_id_t basic_id_tmp;
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got BasicID\n");
             Serial.printf("MAVLink: got BasicID\n");
-        }
+        } // 仅接收有效数据:UAS_ID非空 + ID类型合法(1~MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)
         mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id_tmp);
         mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id_tmp);
         if ((strlen((const char*) basic_id_tmp.uas_id) > 0) && (basic_id_tmp.id_type > 0) && (basic_id_tmp.id_type <= MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)) {
         if ((strlen((const char*) basic_id_tmp.uas_id) > 0) && (basic_id_tmp.id_type > 0) && (basic_id_tmp.id_type <= MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)) {
             //only update if we receive valid data
             //only update if we receive valid data
-            basic_id = basic_id_tmp;
-            last_basic_id_ms = now_ms;
+            basic_id = basic_id_tmp; // 更新本地缓存
+            last_basic_id_ms = now_ms; // 记录最后接收时间
         }
         }
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: { // 其他 ODID 消息(认证 / 自描述 / 系统 / 运营商 ID)
         mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
         mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got Auth\n");
             Serial.printf("MAVLink: got Auth\n");
         }
         }
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: { // 无人机自描述信息(如机型、用途)
         mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
         mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got SelfID\n");
             Serial.printf("MAVLink: got SelfID\n");
@@ -183,7 +197,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         last_self_id_ms = now_ms;
         last_self_id_ms = now_ms;
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: { // 系统信息(运营人位置、高度基准)
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got System\n");
             Serial.printf("MAVLink: got System\n");
@@ -195,7 +209,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         }
         }
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: { // 运营人位置更新
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got System update\n");
             Serial.printf("MAVLink: got System update\n");
         }
         }
@@ -217,7 +231,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         }
         }
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
+    case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: { // 运营人 ID(如企业名称、联系方式)
         mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
         mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got OperatorID\n");
             Serial.printf("MAVLink: got OperatorID\n");
@@ -225,12 +239,12 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         last_operator_id_ms = now_ms;
         last_operator_id_ms = now_ms;
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
+    case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // 参数列表请求
         param_next = g.find_by_index_float(0);
         param_next = g.find_by_index_float(0);
         param_request_last_ms = millis();
         param_request_last_ms = millis();
         break;
         break;
     };
     };
-    case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
+    case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { // 参数读取请求
         mavlink_param_request_read_t pkt;
         mavlink_param_request_read_t pkt;
         mavlink_msg_param_request_read_decode(&msg, &pkt);
         mavlink_msg_param_request_read_decode(&msg, &pkt);
         const Parameters::Param *p;
         const Parameters::Param *p;
@@ -253,7 +267,11 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
                                      g.param_index_float(p));
                                      g.param_index_float(p));
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_PARAM_SET: {
+    case MAVLINK_MSG_ID_PARAM_SET: { //  参数设置
+        /*
+          解析地面站发来的参数设置请求 → 校验参数类型 / 有效性 → 执行锁定安全逻辑(仅允许提高锁定级别)
+          → 执行参数修改(或拒绝)→ 回复修改后的参数值给地面站确认。
+        */
         mavlink_param_set_t pkt;
         mavlink_param_set_t pkt;
         mavlink_msg_param_set_decode(&msg, &pkt);
         mavlink_msg_param_set_decode(&msg, &pkt);
         auto *p = g.find(pkt.param_id);
         auto *p = g.find(pkt.param_id);
@@ -263,12 +281,17 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
             return;
             return;
         }
         }
         p->get_as_float(value);
         p->get_as_float(value);
-        if (g.lock_level > 0 &&
-            (strcmp(p->name, "LOCK_LEVEL") != 0 ||
-             uint8_t(pkt.param_value) <= uint8_t(value))) {
-            // only param set allowed is to increase lock level
+        /*
+        当模块锁定(lock_level>0)时,只要满足「修改的不是 LOCK_LEVEL 参数」OR「修改 LOCK_LEVEL 但新值≤当前值」
+        其中一个条件,就拒绝修改;
+        只有「修改 LOCK_LEVEL 且新值 > 当前值」才允许。
+        */
+        if (g.lock_level > 0 && 
+            (strcmp(p->name, "LOCK_LEVEL") != 0 || 
+             uint8_t(pkt.param_value) <= uint8_t(value))) {  
+            // only param set allowed is to increase lock level 
             mav_printf(MAV_SEVERITY_ERROR, "Parameters locked");
             mav_printf(MAV_SEVERITY_ERROR, "Parameters locked");
-        } else {
+        } else { // 不满足条件 → 允许修改(仅两种情况:1.未锁定;2.锁定但提高LOCK_LEVEL)
             p->set_as_float(pkt.param_value);
             p->set_as_float(pkt.param_value);
         }
         }
         p->get_as_float(value);
         p->get_as_float(value);
@@ -279,24 +302,24 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
                                      g.param_index_float(p));
                                      g.param_index_float(p));
         break;
         break;
     }
     }
-    case MAVLINK_MSG_ID_SECURE_COMMAND:
+    case MAVLINK_MSG_ID_SECURE_COMMAND: // 安全指令处理
     case MAVLINK_MSG_ID_SECURE_COMMAND_REPLY: {
     case MAVLINK_MSG_ID_SECURE_COMMAND_REPLY: {
         mavlink_secure_command_t pkt;
         mavlink_secure_command_t pkt;
         mavlink_msg_secure_command_decode(&msg, &pkt);
         mavlink_msg_secure_command_decode(&msg, &pkt);
         handle_secure_command(pkt);
         handle_secure_command(pkt);
         break;
         break;
     }
     }
-    default:
+    default: // 默认分支
         // we don't care about other packets
         // we don't care about other packets
         break;
         break;
     }
     }
 }
 }
 
 
 void MAVLinkSerial::arm_status_send(void)
 void MAVLinkSerial::arm_status_send(void)
-{
+{   // 1. 判定解锁状态码:
     const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
     const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
-    const char *reason = parse_fail==nullptr?"":parse_fail;
-    mavlink_msg_open_drone_id_arm_status_send(
+    const char *reason = parse_fail==nullptr?"":parse_fail; // 2. 判定失败原因:
+    mavlink_msg_open_drone_id_arm_status_send(  // 3. 发送MAVLink OpenDroneID解锁状态消息(ODID标准消息)
         chan,
         chan,
         status,
         status,
         reason);
         reason);

+ 15 - 15
RemoteIDModule/mavlink.h

@@ -8,26 +8,26 @@
 /*
 /*
   abstraction for MAVLink on a serial port
   abstraction for MAVLink on a serial port
  */
  */
-class MAVLinkSerial : public Transport {
+class MAVLinkSerial : public Transport { // 继承自 Transport 基类
 public:
 public:
     using Transport::Transport;
     using Transport::Transport;
     MAVLinkSerial(HardwareSerial &serial, mavlink_channel_t chan);
     MAVLinkSerial(HardwareSerial &serial, mavlink_channel_t chan);
-    void init(void) override;
-    void update(void) override;
+    void init(void) override; // 初始化串口和MAVLink
+    void update(void) override; // 主循环调用,处理收发数据
 
 
 private:
 private:
-    HardwareSerial &serial;
-    mavlink_channel_t chan;
-    uint32_t last_hb_ms;
-    uint32_t last_hb_warn_ms;
-    uint32_t param_request_last_ms;
-    const Parameters::Param *param_next;
+    HardwareSerial &serial;  // 串口对象引用(实际使用的串口,如 Serial1、Serial2)
+    mavlink_channel_t chan;  // MAVLink 通道号(0、1、2等,用于区分多个MAVLink连接)
+    uint32_t last_hb_ms; // 最后一次收到心跳包的时间戳
+    uint32_t last_hb_warn_ms; // 最后一次发送心跳警告的时间戳(避免频繁警告)
+    uint32_t param_request_last_ms; // 最后一次请求参数的时间
+    const Parameters::Param *param_next; // 下一个要发送的参数(用于参数列表传输)
 
 
-    void update_receive(void);
-    void update_send(void);
-    void process_packet(mavlink_status_t &status, mavlink_message_t &msg);
-    void mav_printf(uint8_t severity, const char *fmt, ...);
-    void handle_secure_command(const mavlink_secure_command_t &pkt);
+    void update_receive(void); // 接收并处理MAVLink消息
+    void update_send(void); // 发送MAVLink消息
+    void process_packet(mavlink_status_t &status, mavlink_message_t &msg); // 处理接收到的数据包
+    void mav_printf(uint8_t severity, const char *fmt, ...); // 通过MAVLink发送日志/调试信息
+    void handle_secure_command(const mavlink_secure_command_t &pkt); // 处理安全命令(加密/签名)
 
 
-    void arm_status_send(void);
+    void arm_status_send(void);  // 发送解锁状态
 };
 };

+ 20 - 11
RemoteIDModule/parameters.cpp

@@ -8,9 +8,10 @@
 
 
 Parameters g;
 Parameters g;
 static nvs_handle handle;
 static nvs_handle handle;
-
+// 正常商品lock应该为0 但是需要签名才能进行升级 所以这里默认值给-1
+// 默认参数值 参数最小值 参数最大值 对于lock默认值时0  改为-1可以任意web升级固件 不需要签名
 const Parameters::Param Parameters::params[] = {
 const Parameters::Param Parameters::params[] = {
-    { "LOCK_LEVEL",        Parameters::ParamType::INT8,  (const void*)&g.lock_level,       0, -1, 2 },
+    { "LOCK_LEVEL",        Parameters::ParamType::INT8,  (const void*)&g.lock_level,       -1, -1, 2 },
     { "CAN_NODE",          Parameters::ParamType::UINT8,  (const void*)&g.can_node,         0, 0, 127 },
     { "CAN_NODE",          Parameters::ParamType::UINT8,  (const void*)&g.can_node,         0, 0, 127 },
 #if defined(PIN_CAN_TERM)
 #if defined(PIN_CAN_TERM)
     { "CAN_TERMINATE",     Parameters::ParamType::UINT8,  (const void*)&g.can_term,        0, 0, 1 },
     { "CAN_TERMINATE",     Parameters::ParamType::UINT8,  (const void*)&g.can_term,        0, 0, 1 },
@@ -21,7 +22,7 @@ const Parameters::Param Parameters::params[] = {
     { "UAS_TYPE_2",        Parameters::ParamType::UINT8,  (const void*)&g.ua_type_2,          0, 0, 15 },
     { "UAS_TYPE_2",        Parameters::ParamType::UINT8,  (const void*)&g.ua_type_2,          0, 0, 15 },
     { "UAS_ID_TYPE_2",     Parameters::ParamType::UINT8,  (const void*)&g.id_type_2,          0, 0, 4 },
     { "UAS_ID_TYPE_2",     Parameters::ParamType::UINT8,  (const void*)&g.id_type_2,          0, 0, 4 },
     { "UAS_ID_2",          Parameters::ParamType::CHAR20, (const void*)&g.uas_id_2[0],        0, 0, 0 },
     { "UAS_ID_2",          Parameters::ParamType::CHAR20, (const void*)&g.uas_id_2[0],        0, 0, 0 },
-    { "BAUDRATE",          Parameters::ParamType::UINT32, (const void*)&g.baudrate,         57600, 9600, 921600 },
+    { "BAUDRATE",          Parameters::ParamType::UINT32, (const void*)&g.baudrate,         115200, 9600, 921600 },
     { "WIFI_NAN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_nan_rate,    0, 0, 5 },
     { "WIFI_NAN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_nan_rate,    0, 0, 5 },
     { "WIFI_BCN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_beacon_rate,    0, 0, 5 },
     { "WIFI_BCN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_beacon_rate,    0, 0, 5 },
     { "WIFI_POWER",        Parameters::ParamType::FLOAT,  (const void*)&g.wifi_power,       20, 2, 20 },
     { "WIFI_POWER",        Parameters::ParamType::FLOAT,  (const void*)&g.wifi_power,       20, 2, 20 },
@@ -41,11 +42,18 @@ const Parameters::Param Parameters::params[] = {
     { "PUBLIC_KEY5",       Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
     { "PUBLIC_KEY5",       Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
     { "MAVLINK_SYSID",     Parameters::ParamType::UINT8,  (const void*)&g.mavlink_sysid,    0, 0, 254 },
     { "MAVLINK_SYSID",     Parameters::ParamType::UINT8,  (const void*)&g.mavlink_sysid,    0, 0, 254 },
     { "OPTIONS",           Parameters::ParamType::UINT8,  (const void*)&g.options,          0, 0, 254 },
     { "OPTIONS",           Parameters::ParamType::UINT8,  (const void*)&g.options,          0, 0, 254 },
-    { "TO_DEFAULTS",     Parameters::ParamType::UINT8,  (const void*)&g.to_factory_defaults,    0, 0, 1 }, //if set to 1, reset to factory defaults and make 0.
+    { "TO_DEFAULTS",       Parameters::ParamType::UINT8,  (const void*)&g.to_factory_defaults,    0, 0, 1 }, //if set to 1, reset to factory defaults and make 0.
     { "DONE_INIT",         Parameters::ParamType::UINT8,  (const void*)&g.done_init,        0, 0, 0, PARAM_FLAG_HIDDEN},
     { "DONE_INIT",         Parameters::ParamType::UINT8,  (const void*)&g.done_init,        0, 0, 0, PARAM_FLAG_HIDDEN},
+    { "PROTOCOL",          Parameters::ParamType::UINT8,  (const void*)&g.protocol,      0, 0, 1 }, // 新加
     { "",                  Parameters::ParamType::NONE,   nullptr,  },
     { "",                  Parameters::ParamType::NONE,   nullptr,  },
 };
 };
-
+/*
+    这里才是真正的定义,分配内存
+    const:这个数组是常量,不能修改
+    Parameters::Param:使用Parameters类内部定义的Param结构体类型
+    Parameters::params:定义Parameters类的静态成员变量params
+    []:这是一个数组
+*/
 /*
 /*
   get count of parameters capable of being converted to load
   get count of parameters capable of being converted to load
  */
  */
@@ -70,7 +78,7 @@ uint16_t Parameters::param_count_float(void)
 }
 }
 
 
 /*
 /*
-  get index of parameter counting only those capable of representation as float
+  仅获取那些能够表示为浮点数的参数的索引
  */
  */
 int16_t Parameters::param_index_float(const Parameters::Param *f)
 int16_t Parameters::param_index_float(const Parameters::Param *f)
 {
 {
@@ -309,8 +317,8 @@ void Parameters::load_defaults(void)
 
 
 void Parameters::init(void)
 void Parameters::init(void)
 {
 {
-    load_defaults();
-
+    load_defaults(); // 遍历 params 数组,将每个参数的 “默认值” 写入对应的全局变量
+    // 初始化 NVS 并读取保存的参数
     if (nvs_flash_init() != ESP_OK ||
     if (nvs_flash_init() != ESP_OK ||
         nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
         nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
         Serial.printf("NVS init failed\n");
         Serial.printf("NVS init failed\n");
@@ -342,7 +350,7 @@ void Parameters::init(void)
         }
         }
         }
         }
     }
     }
-
+    // 补全 WiFi SSID(无配置时自动生成)
     if (strlen(g.wifi_ssid) == 0) {
     if (strlen(g.wifi_ssid) == 0) {
         uint8_t mac[6] {};
         uint8_t mac[6] {};
         esp_read_mac(mac, ESP_MAC_WIFI_STA);
         esp_read_mac(mac, ESP_MAC_WIFI_STA);
@@ -350,12 +358,12 @@ void Parameters::init(void)
                  mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
                  mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
 
 
     }
     }
-    if (g.to_factory_defaults == 1) {
+    if (g.to_factory_defaults == 1) { // 处理恢复出厂设置(应急重置)
         //should not happen, but in case the parameter is still set to 1, erase flash and reboot
         //should not happen, but in case the parameter is still set to 1, erase flash and reboot
         nvs_flash_erase();
         nvs_flash_erase();
         esp_restart();
         esp_restart();
     }
     }
-
+    // 首次初始化(仅上电第一次执行)
     if (g.done_init == 0) {
     if (g.done_init == 0) {
         set_by_name_uint8("DONE_INIT", 1);
         set_by_name_uint8("DONE_INIT", 1);
         // setup public keys
         // setup public keys
@@ -370,6 +378,7 @@ void Parameters::init(void)
 #endif
 #endif
 
 
     }
     }
+    Serial.printf("Protocol: %s\n", g.protocol == 0 ? "OpenDroneID" : "CN_DroneID");
 }
 }
 
 
 /*
 /*

+ 74 - 66
RemoteIDModule/parameters.h

@@ -5,71 +5,76 @@
 
 
 #define MAX_PUBLIC_KEYS 5
 #define MAX_PUBLIC_KEYS 5
 #define PUBLIC_KEY_LEN 32
 #define PUBLIC_KEY_LEN 32
-#define PARAM_NAME_MAX_LEN 16
+#define PARAM_NAME_MAX_LEN 16 // 参数名最长
 
 
-#define PARAM_FLAG_NONE 0
+#define PARAM_FLAG_NONE 0 
 #define PARAM_FLAG_PASSWORD (1U<<0)
 #define PARAM_FLAG_PASSWORD (1U<<0)
 #define PARAM_FLAG_HIDDEN (1U<<1)
 #define PARAM_FLAG_HIDDEN (1U<<1)
 
 
 class Parameters {
 class Parameters {
 public:
 public:
 #if defined(PIN_CAN_TERM)
 #if defined(PIN_CAN_TERM)
-    uint8_t can_term = !CAN_TERM_EN;
+    uint8_t can_term = !CAN_TERM_EN; // 是否用CAN终端电阻
 #endif
 #endif
-    int8_t lock_level;
-    uint8_t can_node;
-    uint8_t bcast_powerup;
-    uint32_t baudrate = 57600;
-    uint8_t ua_type;
-    uint8_t id_type;
-    char uas_id[21] = "ABCD123456789";
-    uint8_t ua_type_2;
+    int8_t lock_level;  // 固件锁等级(-1=无锁,0-2=不同安全级别)
+    uint8_t can_node; // CAN总线节点ID
+    uint8_t bcast_powerup;  // 上电即广播(1=是,0=等待有效位置)
+    uint32_t baudrate = 57600; // 串口波特率
+    uint8_t ua_type;  // 无人机类型
+    uint8_t id_type; // ID类型
+    char uas_id[21] = "ABCD123456789";// 无人机ID(20字符)
+    // 第二个ID(可选,用于多架次)
+    uint8_t ua_type_2; 
     uint8_t id_type_2;
     uint8_t id_type_2;
     char uas_id_2[21] = "ABCD123456789";
     char uas_id_2[21] = "ABCD123456789";
-    float wifi_nan_rate;
-    float wifi_beacon_rate;
-    float wifi_power;
-    float bt4_rate;
-    float bt4_power;
-    float bt5_rate;
-    float bt5_power;
-    uint8_t done_init;
-    uint8_t webserver_enable;
-    uint8_t mavlink_sysid;
-    char wifi_ssid[21] = "";
-    char wifi_password[21] = "ArduRemoteID";
-    uint8_t wifi_channel = 6;
-    uint8_t to_factory_defaults = 0;
-    uint8_t options;
+    float wifi_nan_rate; // WiFi NAN广播频率(Hz)
+    float wifi_beacon_rate;  // WiFi Beacon广播频率(Hz)
+    float wifi_power; // WiFi发射功率(dBm)
+    float bt4_rate; // 经典蓝牙广播频率
+    float bt4_power;  // 经典蓝牙功率
+    float bt5_rate;  // BLE长距离广播频率
+    float bt5_power;   // BLE长距离功率
+    uint8_t done_init;  // 首次初始化完成标志
+    uint8_t protocol; // 协议选择:0=国际,1=国标
+    uint8_t webserver_enable;  // 启用Web服务器
+    uint8_t mavlink_sysid; // mavlink系统id默认值通常是 0 或 245
+    char wifi_ssid[21] = ""; // WiFi名称
+    char wifi_password[21] = "ArduRemoteID"; // WiFi密码
+    uint8_t wifi_channel = 6;// WiFi信道
+    uint8_t to_factory_defaults = 0; // 恢复出厂设置
+    uint8_t options; // 功能选项(位掩码)
     struct {
     struct {
-        char b64_key[64];
-    } public_keys[MAX_PUBLIC_KEYS];
-
+        char b64_key[64];  // Base64编码的公钥
+    } public_keys[MAX_PUBLIC_KEYS]; // 最多5个公钥
+    // 参数类型枚举
     enum class ParamType {
     enum class ParamType {
-        NONE=0,
-        UINT8=1,
-        UINT32=2,
-        FLOAT=3,
-        CHAR20=4,
-        CHAR64=5,
-        INT8=6,
+        NONE=0,     // 无
+        UINT8=1,    // 8位无符号整数
+        UINT32=2,   // 32位无符号整数
+        FLOAT=3,    // 浮点数
+        CHAR20=4,   // 20字符字符串
+        CHAR64=5,   // 64字符字符串
+        INT8=6,     // 8位有符号整数
     };
     };
-
+    // 参数描述结构体
     struct Param {
     struct Param {
-        char name[PARAM_NAME_MAX_LEN+1];
-        ParamType ptype;
-        const void *ptr;
-        float default_value;
-        float min_value;
-        float max_value;
-        uint16_t flags;
-        uint8_t min_len;
-        void set_float(float v) const;
+        char name[PARAM_NAME_MAX_LEN+1];// 参数名(如"WIFI_SSID")
+        ParamType ptype; // 参数类型
+        const void *ptr;  // 指向实际变量的指针
+        float default_value;  // 默认值
+        float min_value;  // 最小值
+        float max_value;   // 最大值
+        uint16_t flags;   // 标志位(密码、隐藏等)
+        uint8_t min_len; // 最小长度(字符串用)
+        // 操作方法
+        // 设置值
+        void set_float(float v) const; 
         void set_uint8(uint8_t v) const;
         void set_uint8(uint8_t v) const;
         void set_int8(int8_t v) const;
         void set_int8(int8_t v) const;
         void set_uint32(uint32_t v) const;
         void set_uint32(uint32_t v) const;
         void set_char20(const char *v) const;
         void set_char20(const char *v) const;
         void set_char64(const char *v) const;
         void set_char64(const char *v) const;
+        // 获取值
         uint8_t get_uint8() const;
         uint8_t get_uint8() const;
         int8_t get_int8() const;
         int8_t get_int8() const;
         uint32_t get_uint32() const;
         uint32_t get_uint32() const;
@@ -79,40 +84,43 @@ public:
         bool get_as_float(float &v) const;
         bool get_as_float(float &v) const;
         void set_as_float(float v) const;
         void set_as_float(float v) const;
     };
     };
-    static const struct Param params[];
+    static const struct Param params[]; // 只是声明,不分配内存
+    // 参数查找
+    static const Param *find(const char *name); // 按名字找
+    static const Param *find_by_index(uint16_t idx);  // 按索引找
+    static const Param *find_by_index_float(uint16_t idx);  // 找可转浮点的参数
 
 
-    static const Param *find(const char *name);
-    static const Param *find_by_index(uint16_t idx);
-    static const Param *find_by_index_float(uint16_t idx);
+    void init(void); // 初始化
 
 
-    void init(void);
+    bool have_basic_id_info(void) const; // 检查是否有id信息
+    bool have_basic_id_2_info(void) const; // 检查是否有第2个id信息
 
 
-    bool have_basic_id_info(void) const;
-    bool have_basic_id_2_info(void) const;
-
-    bool set_by_name_uint8(const char *name, uint8_t v);
-    bool set_by_name_int8(const char *name, int8_t v);
-    bool set_by_name_char64(const char *name, const char *s);
-    bool set_by_name_string(const char *name, const char *s);
+    bool set_by_name_uint8(const char *name, uint8_t v); // 设置UINT8
+    bool set_by_name_int8(const char *name, int8_t v); // 设置INT8
+    bool set_by_name_char64(const char *name, const char *s);// 设置字符串
+    bool set_by_name_string(const char *name, const char *s); // 通用字符串设置
 
 
     /*
     /*
       return a public key
       return a public key
     */
     */
-    bool get_public_key(uint8_t i, uint8_t key[32]) const;
-    bool set_public_key(uint8_t i, const uint8_t key[32]);
-    bool remove_public_key(uint8_t i);
-    bool no_public_keys(void) const;
+    bool get_public_key(uint8_t i, uint8_t key[32]) const; // 获取公钥
+    bool set_public_key(uint8_t i, const uint8_t key[32]);// 设置公钥
+    bool remove_public_key(uint8_t i); // 删除公钥
+    bool no_public_keys(void) const; // 检查是否有公钥
 
 
-    static uint16_t param_count_float(void);
-    static int16_t param_index_float(const Param *p);
+    static uint16_t param_count_float(void); // 统计可浮点化的参数数量 排除字符串等非数值类型
+    static int16_t param_index_float(const Param *p); // 获取参数的浮点索引 返回它在浮点参数列表中的索引位置(不是原始参数表的索引)
 
 
 private:
 private:
-    void load_defaults(void);
+    void load_defaults(void); // 加载默认参数
 };
 };
 
 
 // bits for OPTIONS parameter
 // bits for OPTIONS parameter
 #define OPTIONS_FORCE_ARM_OK (1U<<0)
 #define OPTIONS_FORCE_ARM_OK (1U<<0)
 #define OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS (1U<<1)
 #define OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS (1U<<1)
 #define OPTIONS_PRINT_RID_MAVLINK (1U<<2)
 #define OPTIONS_PRINT_RID_MAVLINK (1U<<2)
-
+// protocol
+#define PROTOCOL_EU 0
+#define PROTOCOL_CN2023 1
+#define PROTOCOL_GB2025 2
 extern Parameters g;
 extern Parameters g;

+ 2 - 1
RemoteIDModule/transmitter.h

@@ -5,7 +5,8 @@
 
 
 #include <Arduino.h>
 #include <Arduino.h>
 #include <opendroneid.h>
 #include <opendroneid.h>
-
+#include "cndroneid.h"
+#include "did_GB_2025.h"
 class Transmitter {
 class Transmitter {
 public:
 public:
     virtual bool init(void);
     virtual bool init(void);

+ 13 - 8
RemoteIDModule/transport.cpp

@@ -59,10 +59,13 @@ uint8_t Transport::arm_status_check(const char *&reason)
     if (last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms) {
     if (last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms) {
         ret += "SELF_ID ";
         ret += "SELF_ID ";
     }
     }
-
-    if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
+    if(g.protocol == PROTOCOL_EU) // 国标不含操作员ID状态错误
+    {
+        if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
         ret += "OP_ID ";
         ret += "OP_ID ";
+        }
     }
     }
+   
 
 
     if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
     if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
         // we use location age limit for system as the operator location needs to come in as fast
         // we use location age limit for system as the operator location needs to come in as fast
@@ -70,11 +73,11 @@ uint8_t Transport::arm_status_check(const char *&reason)
         ret += "SYS ";
         ret += "SYS ";
     }
     }
 
 
-    if (location.latitude == 0 && location.longitude == 0) {
+    if (location.latitude == 0 && location.longitude == 0) { // 飞机经纬度数值是否符合范围
         ret += "LOC ";
         ret += "LOC ";
     }
     }
 
 
-    if (system.operator_latitude == 0 && system.operator_longitude == 0) {
+    if (system.operator_latitude == 0 && system.operator_longitude == 0) { // 操作员所在经纬度
         ret += "OP_LOC ";
         ret += "OP_LOC ";
     }
     }
 
 
@@ -94,7 +97,7 @@ uint8_t Transport::arm_status_check(const char *&reason)
 }
 }
 
 
 /*
 /*
-  make a session key
+  make a session key  用随机数 时间戳 mac地址生成当前64bit会话密钥
  */
  */
 void Transport::make_session_key(uint8_t key[8]) const
 void Transport::make_session_key(uint8_t key[8]) const
 {
 {
@@ -113,22 +116,24 @@ void Transport::make_session_key(uint8_t key[8]) const
 }
 }
 
 
 /*
 /*
+  数字签名验证函数
   check signature in a command against public keys
   check signature in a command against public keys
  */
  */
 bool Transport::check_signature(uint8_t sig_length, uint8_t data_len, uint32_t sequence, uint32_t operation,
 bool Transport::check_signature(uint8_t sig_length, uint8_t data_len, uint32_t sequence, uint32_t operation,
                                 const uint8_t *data)
                                 const uint8_t *data)
 {
 {
-    if (g.no_public_keys()) {
+    if (g.no_public_keys()) { // 通过不设置公钥跳过这个
         // allow through if no keys are setup
         // allow through if no keys are setup
+        // 如果未设置密钥,则允许通过
         return true;
         return true;
     }
     }
     if (sig_length != 64) {
     if (sig_length != 64) {
-        // monocypher signatures are 64 bytes
+        // Monocypher签名为64字节
         return false;
         return false;
     }
     }
 
 
     /*
     /*
-      loop over all public keys, if one matches then we are OK
+      遍历所有公钥,如果有一个匹配,那么我们就没问题了
      */
      */
     for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
     for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
         uint8_t key[32];
         uint8_t key[32];

+ 6 - 6
RemoteIDModule/transport.h

@@ -10,9 +10,9 @@
  */
  */
 class Transport {
 class Transport {
 public:
 public:
-    Transport();
-    virtual void init(void) = 0;
-    virtual void update(void) = 0;
+    Transport(); // 构造函数
+    virtual void init(void) = 0; // 这是一个虚函数,允许子类重写
+    virtual void update(void) = 0; // 这是一个虚函数,允许子类重写
     uint8_t arm_status_check(const char *&reason);
     uint8_t arm_status_check(const char *&reason);
 
 
     const mavlink_open_drone_id_location_t &get_location(void) const {
     const mavlink_open_drone_id_location_t &get_location(void) const {
@@ -54,10 +54,10 @@ public:
     const char *get_parse_fail(void) {
     const char *get_parse_fail(void) {
         return parse_fail;
         return parse_fail;
     }
     }
-    
+// 保护类,子类可以访问以下成员变量
 protected:
 protected:
-    // common variables between transports. The last message of each
-    // type, no matter what transport it was on, wins
+    // 传输之间的通用变量。每种类型的最后一条消息,
+    // 无论它处于何种传输方式,都将生效
     static const char *parse_fail;
     static const char *parse_fail;
 
 
     static uint32_t last_location_ms;
     static uint32_t last_location_ms;

+ 49 - 21
RemoteIDModule/webinterface.cpp

@@ -11,10 +11,14 @@
 #include "check_firmware.h"
 #include "check_firmware.h"
 #include "status.h"
 #include "status.h"
 
 
-static WebServer server(80);
-
+static WebServer server(80); // 80 是 HTTP 协议的默认端口
+static bool front_16byte_flag = false; // 调试观察前16个字节使用
 /*
 /*
   serve files from ROMFS
   serve files from ROMFS
+  ROMFS_Handler 是 Web 服务器的 “静态资源处理器”:拦截所有 Web 请求,
+  将 URI 映射到 ROMFS 中的 web/ 目录下的文件(如 / → web/index.html),
+  判断文件是否存在并匹配正确的 Content-Type,最终把 ROMFS 中的文件流式返回给浏览器,
+  是 Web 升级页面能正常加载的关键
  */
  */
 class ROMFS_Handler : public RequestHandler
 class ROMFS_Handler : public RequestHandler
 {
 {
@@ -87,14 +91,18 @@ class AJAX_Handler : public RequestHandler
 
 
 /*
 /*
   init web server
   init web server
+  该函数是 Web 升级的 “总开关”:启动 WiFi AP 并初始化 Web 服务器,
+  注册 AJAX/ROMFS 处理器支撑页面显示,绑定 /update 接口处理固件上传,
+  上传过程中缓存固件头部、写入 OTA 分区,最后通过你之前关注的 check_OTA_next() 校验固件合法性,
+  合法则升级重启,非法则返回失败,是 Web 升级从 “页面访问” 到 “固件生效” 的全流程入口
  */
  */
 void WebInterface::init(void)
 void WebInterface::init(void)
 {
 {
     Serial.printf("WAP start %s %s\n", g.wifi_ssid, g.wifi_password);
     Serial.printf("WAP start %s %s\n", g.wifi_ssid, g.wifi_password);
-    IPAddress myIP = WiFi.softAPIP();
+    IPAddress myIP = WiFi.softAPIP();  // 获取 AP 模式默认 IP(192.168.4.1)
 
 
-    server.addHandler( &AJAX_Handler );
-    server.addHandler( &ROMFS_Handler );
+    server.addHandler( &AJAX_Handler ); // 处理 AJAX 异步请求(如获取模块状态)
+    server.addHandler( &ROMFS_Handler ); // 处理静态页面(HTML/CSS/JS)
 
 
     /*handling uploading firmware file */
     /*handling uploading firmware file */
     server.on("/update", HTTP_POST, []() {
     server.on("/update", HTTP_POST, []() {
@@ -110,46 +118,62 @@ void WebInterface::init(void)
 			delay(1000);
 			delay(1000);
 			ESP.restart();
 			ESP.restart();
 		}
 		}
-    }, [this]() {
-        HTTPUpload& upload = server.upload();
+    }, [this]() { // 回调 2:上传过程中处理固件数据(核心中的核心)
+        HTTPUpload& upload = server.upload(); 
+        // 获取待写入的备用 OTA 分区(OTA0/OTA1 中非当前运行的分区)
         static const esp_partition_t* partition_new_firmware = esp_ota_get_next_update_partition(NULL); //get OTA partion to which we will write new firmware file;
         static const esp_partition_t* partition_new_firmware = esp_ota_get_next_update_partition(NULL); //get OTA partion to which we will write new firmware file;
-        if (upload.status == UPLOAD_FILE_START) {
+        if (upload.status == UPLOAD_FILE_START) { // 阶段1:开始上传(UPLOAD_FILE_START)
             Serial.printf("Update: %s\n", upload.filename.c_str());
             Serial.printf("Update: %s\n", upload.filename.c_str());
-            lead_len = 0;
-
+            lead_len = 0; // 初始化固件头部数据长度
+            // 启动固件更新,UPDATE_SIZE_UNKNOWN 表示固件大小未知 擦除备份区
             if (!Update.begin(UPDATE_SIZE_UNKNOWN)) { //start with max available size
             if (!Update.begin(UPDATE_SIZE_UNKNOWN)) { //start with max available size
                 Update.printError(Serial);
                 Update.printError(Serial);
             }
             }
-        } else if (upload.status == UPLOAD_FILE_WRITE) {
+        } else if (upload.status == UPLOAD_FILE_WRITE) { // 阶段2:上传中写入数据(UPLOAD_FILE_WRITE)
             /* flashing firmware to ESP*/
             /* flashing firmware to ESP*/
-            if (lead_len < sizeof(lead_bytes)) {
-                uint32_t n = sizeof(lead_bytes)-lead_len;
+            /*
+            就是专门用 16 字节的 “小盒子” 只装固件最开头的 16 个字节(固件的 “身份证”),
+            同时不管这个小盒子装没装满,收到的每一段固件数据都会完整写入备用 OTA 分区(备份区);
+            等小盒子装满 16 字节后,就只专心往备份区写固件,不再往小盒子存数据了
+            */
+            if (lead_len < sizeof(lead_bytes)) { /* 第一步:缓存固件头部数据(lead_bytes) */
+                uint32_t n = sizeof(lead_bytes)-lead_len; 
                 if (n > upload.currentSize) {
                 if (n > upload.currentSize) {
                     n = upload.currentSize;
                     n = upload.currentSize;
                 }
                 }
-                memcpy(&lead_bytes[lead_len], upload.buf, n);
+                memcpy(&lead_bytes[lead_len], upload.buf, n); // 拷贝到 lead_bytes 缓存
                 lead_len += n;
                 lead_len += n;
+                if(lead_len >= 16 && !front_16byte_flag )
+                {
+                    front_16byte_flag = true;
+                    Serial.printf("front 16 byte is %d %d %d %d ", lead_bytes[0], lead_bytes[1],lead_bytes[2],lead_bytes[3]); // 打印当前头16个字节
+                    Serial.printf("%d %d %d %d ", lead_bytes[4], lead_bytes[5],lead_bytes[6],lead_bytes[7]); // 打印当前头16个字节
+                    Serial.printf("%d %d %d %d ", lead_bytes[8], lead_bytes[9],lead_bytes[10],lead_bytes[11]); // 打印当前头16个字节
+                    Serial.printf("%d %d %d %d end\n", lead_bytes[12], lead_bytes[13],lead_bytes[14],lead_bytes[15]); // 打印当前头16个字节
+                }
             }
             }
+            /* 第二步:将固件数据写入 OTA 分区 */
             if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
             if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
-                Update.printError(Serial);
+                Update.printError(Serial); // 写入失败打印错误
             }
             }
-        } else if (upload.status == UPLOAD_FILE_END) {
+        } else if (upload.status == UPLOAD_FILE_END) { // 阶段3:上传完成(UPLOAD_FILE_END)
             // write extra bytes to force flush of the buffer before we check signature
             // write extra bytes to force flush of the buffer before we check signature
             uint32_t extra = SPI_FLASH_SEC_SIZE+1;
             uint32_t extra = SPI_FLASH_SEC_SIZE+1;
             while (extra--) {
             while (extra--) {
-                uint8_t ff = 0xff;
-                Update.write(&ff, 1);
+                uint8_t ff = 0xff; 
+                Update.write(&ff, 1); // 写入额外的 0xFF 字节,强制刷新 Flash 缓冲区(保证数据写入完成)
             }
             }
+            // 核心校验:调用 check_OTA_next() 验证固件合法性 必须签名后才能校验成功 并找到对应的应用描述符
             if (!CheckFirmware::check_OTA_next(partition_new_firmware, lead_bytes, lead_len)) {
             if (!CheckFirmware::check_OTA_next(partition_new_firmware, lead_bytes, lead_len)) {
                 Serial.printf("Update Failed: firmware checks have errors\n");
                 Serial.printf("Update Failed: firmware checks have errors\n");
                 server.sendHeader("Connection", "close");
                 server.sendHeader("Connection", "close");
                 server.send(500, "text/plain","FAIL");
                 server.send(500, "text/plain","FAIL");
                 delay(5000);
                 delay(5000);
-            } else if (Update.end(true)) {
+            } else if (Update.end(true)) { // 校验通过,完成更新
                 Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
                 Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
                 server.sendHeader("Connection", "close");
                 server.sendHeader("Connection", "close");
                 server.send(200, "text/plain","OK");
                 server.send(200, "text/plain","OK");
-            } else {
+            } else {  // Update.end() 执行失败
                 Update.printError(Serial);
                 Update.printError(Serial);
                 Serial.printf("Update Failed: Update.end function has errors\n");
                 Serial.printf("Update Failed: Update.end function has errors\n");
                 server.sendHeader("Connection", "close");
                 server.sendHeader("Connection", "close");
@@ -161,7 +185,11 @@ void WebInterface::init(void)
     Serial.printf("WAP started\n");
     Serial.printf("WAP started\n");
     server.begin();
     server.begin();
 }
 }
-
+/*
+该函数是 Web 服务的 “心跳循环”:通过 initialised 标志实现 init() 只执行一次(避免重复初始化),
+然后在主循环中反复调用 server.handleClient(),让 ESP32 持续监听并处理 80 端口的 Web 请求,
+确保用户访问升级页面、上传固件时能实时响应,是 Web 升级功能 “持续可用” 的基础
+*/
 void WebInterface::update()
 void WebInterface::update()
 {
 {
     if (!initialised) {
     if (!initialised) {