Ver Fonte

1、添加参数控制使用can还是串口进行rid消息解析
2、can节点默认100

zhuts há 2 semanas atrás
pai
commit
45c815c280

+ 25 - 10
RemoteIDModule/BLE_TX.cpp

@@ -107,10 +107,12 @@ bool BLE_TX::init(void)
     // generate random mac address
     uint8_t mac_addr[6];
     generate_random_mac(mac_addr);
-
-    // set as a bluetooth random static address
     mac_addr[0] |= 0xc0;
-   
+
+    Serial.printf("Setting BT 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]);
+
     advert.setAdvertisingParams(0, &legacy_adv_params);
     advert.setInstanceAddress(0, mac_addr);
     advert.setDuration(0);
@@ -126,6 +128,7 @@ bool BLE_TX::init(void)
 
     memset(&msg_counters_CNDID,0, sizeof(msg_counters_CNDID));
     memset(&msg_counters_ODID,0, sizeof(msg_counters_ODID));
+    msg_counters_GB2025 = 0;
     return true;
 }
 
@@ -153,8 +156,11 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
     advert.setAdvertisingData(1, longrange_length, longrange_payload);
 
     // 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);
+    Serial.printf("started is %d \r\n", started);
+    Serial.printf("count is %d \r\n", msg_counters_ODID[ODID_MSG_COUNTER_PACKED]);
+    for(uint8_t i =0 ;i < longrange_length; i++ )
+        Serial.printf(" %x ", longrange_payload[i]);
+    Serial.printf("end \r\n");
     if (!started) {
         advert.start();
     }
@@ -332,6 +338,7 @@ bool BLE_TX::transmit_cn_longrange(CNDID_UAS_Data &UAS_data)
     // 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;
     }
@@ -352,8 +359,11 @@ bool BLE_TX::transmit_cn_longrange(CNDID_UAS_Data &UAS_data)
     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);
+    Serial.printf("started is %d \r\n", started);
+    Serial.printf("count is %d \r\n", msg_counters_CNDID[CNDID_MSG_COUNTER_PACKED]);
+    for(uint8_t i =0 ;i < longrange_length; i++ )
+        Serial.printf(" %x ", longrange_payload[i]);
+    Serial.printf("end \r\n");
     if (!started) {
         advert.start();
     }
@@ -511,12 +521,14 @@ bool BLE_TX::transmit_GB2025_longrange(UavIdentificationData &UAS_data)
     // create a packed UAS data message
     uint8_t payload[250];
     int length = did_GB2025_message_build_pack(&UAS_data, payload, 255);
+    Serial.printf("bt5 gb data len %d\r\n", length);
     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个固定头字节)
+    const uint8_t header[] { 
+        uint8_t(length+5),   // 头字段1:总长度(payload长度 + 5个固定头字节)
         0x16,  // 头字段2:ASTM协议固定标识(Remote ID相关)
         0xfa,  // 头字段3:厂商/类型标识(自定义或标准值)
         0xff,  // 头字段4:保留/扩展位
@@ -531,8 +543,11 @@ bool BLE_TX::transmit_GB2025_longrange(UavIdentificationData &UAS_data)
     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);
+    Serial.printf("started is %d \r\n", started);
+    Serial.printf("count is %d \r\n", msg_counters_GB2025);
+    for(uint8_t i =0 ;i < longrange_length; i++ )
+        Serial.printf(" %x ", longrange_payload[i]);
+    Serial.printf("end \r\n");
     if (!started) {
         advert.start();
     }

+ 5 - 0
RemoteIDModule/DroneCAN.cpp

@@ -159,22 +159,27 @@ void DroneCAN::onTransferReceived(CanardInstance* ins,
         break;
     case DRONECAN_REMOTEID_BASICID_ID:
         Serial.printf("DroneCAN: got BasicID\n");
+
         handle_BasicID(transfer);
         break;
     case DRONECAN_REMOTEID_LOCATION_ID:
         Serial.printf("DroneCAN: got Location\n");
+
         handle_Location(transfer);
         break;
     case DRONECAN_REMOTEID_SELFID_ID:
         Serial.printf("DroneCAN: got SelfID\n");
+
         handle_SelfID(transfer);
         break;
     case DRONECAN_REMOTEID_SYSTEM_ID:
         Serial.printf("DroneCAN: got System\n");
+
         handle_System(transfer);
         break;
     case DRONECAN_REMOTEID_OPERATORID_ID:
         Serial.printf("DroneCAN: got OperatorID\n");
+ 
         handle_OperatorID(transfer);
         break;
     case UAVCAN_PROTOCOL_PARAM_GETSET_ID:

+ 2 - 2
RemoteIDModule/Makefile

@@ -22,8 +22,8 @@ export PATH := $(HOME)/.local/bin:$(PATH)
 # 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
-
+all: headers CUAV-RID
+# esp32s3dev
 esp32s3dev: CHIP=esp32s3
 esp32s3dev: ArduRemoteID-ESP32S3_DEV.bin
 

+ 61 - 125
RemoteIDModule/RemoteIDModule.ino

@@ -114,7 +114,7 @@ void setup()
     WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
 
     g.init();
-
+    // g.protocol = 2;
   
     led.set_state(Led::LedState::INIT);
     led.update();
@@ -310,10 +310,16 @@ int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
     }
     
     /* ========== 高度类处理(013/014/007/011) ========== */
+
     if (odid->LocationValid) {
+        // Serial.printf("Geo altitude %f \r\n", odid->Location.AltitudeGeo);
+        // Serial.printf("Rel Height %f \r\n", odid->Location.Height);
+        // Serial.printf("Baro altitude %f \r\n", odid->Location.AltitudeBaro);
+        // Serial.printf("time stamp %f \r\n", odid->Location.TimeStamp);
         // 大地高度
         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 {
@@ -322,8 +328,10 @@ int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
         }
         
         // 气压高度
+       
         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;
@@ -334,9 +342,11 @@ int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
         }
         
         // 相对高度
+      
         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 {
@@ -375,19 +385,7 @@ int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
                                 (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 && 
@@ -415,6 +413,17 @@ int odid_to_gb2025_safe(const ODID_UAS_Data *odid, UavIdentificationData *gb) {
             gb->station_geo_alt = 0;
             gb->is_station_alt_valid = false;
         }
+
+        if (odid->System.Timestamp < 0)
+        {
+            gb->timestamp = 0;
+            gb->is_timestamp_valid = false;
+           
+        } else {
+            gb->timestamp = (uint64_t)(odid->System.Timestamp * 1000); // 使用unix时间 单位ms
+            gb->is_timestamp_valid = true;
+        }
+
     }
     
     return 0;
@@ -430,118 +439,45 @@ static const char *check_parse(void)
 {
     String ret = "";
     
-    if(g.protocol  == PROTOCOL_EU)
     {
-        {
-            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_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 ";
-                }
-            }
-        }
-        {
-            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 ";
-            }
+        ODID_Location_encoded encoded {};
+        if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
+            ret += "LOC ";
         }
-       
-    }else if(g.protocol  == PROTOCOL_CN2023) // 国标状态处理
+    }
     {
-        {
-            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 ";
-            }
+        ODID_System_encoded encoded {};
+        if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
+            ret += "SYS ";
         }
-       
     }
-    else if(g.protocol == PROTOCOL_GB2025)
     {
-        {
-            CNDID_Location_encoded encoded {};
-            if (encodeCNLocationMessage(&encoded, &CN_UAS_data.Location) != CNDID_SUCCESS) {
-                ret += "LOC ";
+        ODID_BasicID_encoded encoded {};
+        if (UAS_data.BasicIDValid[0] == 1) {
+            if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
+                ret += "ID_1 ";
             }
         }
-        {
-            CNDID_System_encoded encoded {};
-            if (encodeCNSystemMessage(&encoded, &CN_UAS_data.System) != CNDID_SUCCESS) {
-                ret += "SYS ";
+        memset(&encoded, 0, sizeof(encoded));
+        if (UAS_data.BasicIDValid[1] == 1) {
+            if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
+                ret += "ID_2 ";
             }
         }
-        {
-            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 ";
-                }
-            }
+    }
+    {
+        ODID_SelfID_encoded encoded {};
+        if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
+            ret += "SELF_ID ";
         }
-        {
-            CNDID_SelfID_encoded encoded {};
-            if (encodeCNSelfIDMessage(&encoded, &CN_UAS_data.SelfID) != CNDID_SUCCESS) {
-                ret += "SELF_ID ";
-            }
+    }
+    {
+        ODID_OperatorID_encoded encoded {};
+        if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
+            ret += "OP_ID ";
         }
     }
+       
     if (ret.length() > 0) {
         // if all errors would occur in this function, it will fit in
         // 50 chars that is also the max for the arm status message
@@ -808,7 +744,6 @@ static void set_data(Transport &t) // 两种类型都获取 广播按照需要
     if (g.options & OPTIONS_FORCE_ARM_OK) { // 设置强制绿灯?
         arm_check_ok = true;
     }
-
     led.set_state(pfst_check_ok && arm_check_ok? Led::LedState::ARM_OK : Led::LedState::ARM_FAIL);
 
     uint32_t now_ms = millis();
@@ -843,7 +778,11 @@ void loop()
 #else
     #error "Must enable DroneCAN or MAVLink"
 #endif
-
+    if(g.com_port == CAN_PORT){
+        auto &transport = dronecan;
+    }else if(g.com_port == UART_PORT){
+        auto &transport = mavlink1; 
+    }
     bool have_location = false;
     // - last_location_ms:最后一次收到有效位置数据的时间戳(毫秒)
     // - last_system_ms:最后一次收到飞控系统消息的时间戳(毫秒)
@@ -856,18 +795,14 @@ void loop()
 
     if (last_location_ms == 0 ||
         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 ||
         now_ms - last_system_ms > 5000) { 
-        //判定条件2:系统通信异常(飞控消息超时/未收到)
-        // - last_system_ms == 0:从未收到过飞控系统消息
-        // - 超时5秒:飞控和RemoteID模块断连超过5秒
+       
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
         CN_UAS_data.Location.Status = CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
     }
@@ -875,15 +810,16 @@ void loop()
     if (transport.get_parse_fail() != nullptr) {
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
         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
     // 网络更新必须在我们更新上述状态之后进行
     if (g.webserver_enable) {
         webif.update();
     } 
+
     if (g.bcast_powerup) { // true 上电即广播"模式
         // if we are broadcasting on powerup we always mark location valid
         // so the location with default data is sent 
@@ -947,7 +883,7 @@ void loop()
             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");
+        Serial.printf("update_bt5\n");
     }
 
     static uint32_t last_update_bt4_ms; // BLE 近端蓝牙发送频率 bt4_rate 达到对应的时间了就启动RemoteID BLE4发送
@@ -967,7 +903,7 @@ void loop()
             ble.transmit_cn_legacy(CN_UAS_data);
         // Serial.printf("update_bt4\n");   
     }
-   
+
     // sleep for a bit for power saving 节能 
     delay(1);
 }

+ 3 - 3
RemoteIDModule/board_config.h

@@ -178,12 +178,12 @@
 #define PIN_UART_TX 18
 #define PIN_UART_RX 17
 
-#define WS2812_LED_PIN GPIO_NUM_48
+#define WS2812_LED_PIN GPIO_NUM_33
 
-#define PIN_CAN_TERM GPIO_NUM_37
+#define PIN_CAN_TERM GPIO_NUM_11
 #define CAN_TERM_EN  LOW
 
-
+#define CAN_APP_NODE_NAME "vk-rid"
 #else
 #error "unsupported board"
 #endif

+ 2 - 2
RemoteIDModule/did_GB_2025.cpp

@@ -304,8 +304,8 @@ uint64_t uav_dec_timestamp(const uint8_t *buf) {
 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);
+    memset(data->unique_code, FILL_CHAR, 21);
+    memset(data->register_id, FILL_CHAR, 9);
     // 所有有效性标志初始化为false
     data->is_station_pos_valid = false;
     data->is_uav_pos_valid = false;

+ 6 - 0
RemoteIDModule/mavlink.cpp

@@ -173,6 +173,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         mavlink_open_drone_id_basic_id_t basic_id_tmp;
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             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);
         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)) {
@@ -186,6 +187,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got Auth\n");
+         
         }
         break;
     }
@@ -193,6 +195,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got SelfID\n");
+          
         }
         last_self_id_ms = now_ms;
         break;
@@ -201,6 +204,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got System\n");
+          
         }
         if ((last_system_timestamp != system.timestamp) || (system.timestamp == 0)) {
             //only update the timestamp if we receive information with a different timestamp
@@ -212,6 +216,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: { // 运营人位置更新
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got System update\n");
+          
         }
         mavlink_open_drone_id_system_update_t pkt_system_update;
         mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
@@ -235,6 +240,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
         if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
             Serial.printf("MAVLink: got OperatorID\n");
+           
         }
         last_operator_id_ms = now_ms;
         break;

+ 3 - 2
RemoteIDModule/parameters.cpp

@@ -12,10 +12,12 @@ static nvs_handle handle;
 // 默认参数值 参数最小值 参数最大值 对于lock默认值时0  改为-1可以任意web升级固件 不需要签名
 const Parameters::Param Parameters::params[] = {
     { "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,        100, 0, 127 },
 #if defined(PIN_CAN_TERM)
     { "CAN_TERMINATE",     Parameters::ParamType::UINT8,  (const void*)&g.can_term,        0, 0, 1 },
 #endif
+    { "COM_PORT",          Parameters::ParamType::UINT8,  (const void*)&g.com_port,         0, 0, 1 }, // 新加
+    { "PROTOCOL",          Parameters::ParamType::UINT8,  (const void*)&g.protocol,         0, 0, 2 }, // 新加
     { "UAS_TYPE",          Parameters::ParamType::UINT8,  (const void*)&g.ua_type,          0, 0, 15 },
     { "UAS_ID_TYPE",       Parameters::ParamType::UINT8,  (const void*)&g.id_type,          0, 0, 4 },
     { "UAS_ID",            Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0],        0, 0, 0 },
@@ -44,7 +46,6 @@ const Parameters::Param Parameters::params[] = {
     { "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.
     { "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,  },
 };
 /*

+ 5 - 1
RemoteIDModule/parameters.h

@@ -35,7 +35,8 @@ public:
     float bt5_rate;  // BLE长距离广播频率
     float bt5_power;   // BLE长距离功率
     uint8_t done_init;  // 首次初始化完成标志
-    uint8_t protocol; // 协议选择:0=国际,1=国标
+    uint8_t protocol; // 协议选择:0=国际,1=国标2023 2 GB2025
+    uint8_t com_port; // 0 can 1 uart
     uint8_t webserver_enable;  // 启用Web服务器
     uint8_t mavlink_sysid; // mavlink系统id默认值通常是 0 或 245
     char wifi_ssid[21] = ""; // WiFi名称
@@ -123,4 +124,7 @@ private:
 #define PROTOCOL_EU 0
 #define PROTOCOL_CN2023 1
 #define PROTOCOL_GB2025 2
+// com_port
+#define CAN_PORT  0
+#define UART_PORT 1
 extern Parameters g;

+ 2 - 5
RemoteIDModule/transport.cpp

@@ -59,13 +59,10 @@ 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) {
         ret += "SELF_ID ";
     }
-    if(g.protocol == PROTOCOL_EU) // 国标不含操作员ID状态错误
-    {
-        if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
+
+    if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
         ret += "OP_ID ";
-        }
     }
-   
 
     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