Quellcode durchsuchen

implemented the backend of the dual ID broadcast feature

Roel Schiphorst vor 3 Jahren
Ursprung
Commit
b2eada76e8

+ 23 - 1
RemoteIDModule/BLE_TX.cpp

@@ -298,10 +298,32 @@ bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
         legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
         legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
 
 
         break;
         break;
+
+    case  5: //in case of dual basic ID
+        if (UAS_data.BasicIDValid[1]) {
+            ODID_BasicID_encoded basicid2_encoded;
+            memset(&basicid2_encoded, 0, sizeof(basicid2_encoded));
+            if (encodeBasicIDMessage(&basicid2_encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
+                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) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
+        }
+        break;
     }
     }
 
 
     legacy_phase++;
     legacy_phase++;
-    legacy_phase %= 5;
+
+    if (UAS_data.BasicIDValid[1]) {
+        legacy_phase %= 6;
+    } else {
+        legacy_phase %= 5;
+    }
 
 
     advert.setAdvertisingData(0, legacy_length, legacy_payload);
     advert.setAdvertisingData(0, legacy_length, legacy_payload);
 
 

+ 11 - 7
RemoteIDModule/DroneCAN.cpp

@@ -466,14 +466,18 @@ void DroneCAN::readUniqueID(uint8_t id[6])
 void DroneCAN::handle_BasicID(CanardRxTransfer* transfer)
 void DroneCAN::handle_BasicID(CanardRxTransfer* transfer)
 {
 {
     dronecan_remoteid_BasicID pkt {};
     dronecan_remoteid_BasicID pkt {};
-    auto &mpkt = basic_id;
     dronecan_remoteid_BasicID_decode(transfer, &pkt);
     dronecan_remoteid_BasicID_decode(transfer, &pkt);
-    last_basic_id_ms = millis();
-    memset(&mpkt, 0, sizeof(mpkt));
-    COPY_STR(id_or_mac);
-    COPY_FIELD(id_type);
-    COPY_FIELD(ua_type);
-    COPY_STR(uas_id);
+
+    if ((pkt.uas_id.len > 0) && (pkt.id_type > 0) && (pkt.id_type <= MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)) {
+        //only update if we receive valid data
+        auto &mpkt = basic_id;
+        memset(&mpkt, 0, sizeof(mpkt));
+        COPY_STR(id_or_mac);
+        COPY_FIELD(id_type);
+        COPY_FIELD(ua_type);
+        COPY_STR(uas_id);
+        last_basic_id_ms = millis();
+    }
 }
 }
 
 
 void DroneCAN::handle_SelfID(CanardRxTransfer* transfer)
 void DroneCAN::handle_SelfID(CanardRxTransfer* transfer)

+ 27 - 6
RemoteIDModule/RemoteIDModule.ino

@@ -177,6 +177,10 @@ static void set_data(Transport &t)
       UAS_ID string via a MAVLink BASIC_ID message and also offers a
       UAS_ID string via a MAVLink BASIC_ID message and also offers a
       migration path from the old approach of GCS setting these values
       migration path from the old approach of GCS setting these values
       to having them as parameters
       to having them as parameters
+
+      BasicID 2 can be set in parameters, or provided via mavlink We
+      don't persist the BasicID2 if provided via mavlink to allow
+      users to change BasicID2 on different days
      */
      */
     if (!g.have_basic_id_info()) {
     if (!g.have_basic_id_info()) {
         if (basic_id.ua_type != 0 &&
         if (basic_id.ua_type != 0 &&
@@ -196,13 +200,30 @@ static void set_data(Transport &t)
         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;
         ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
         ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
-    } else {
-        // from transport
-        UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_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);
+        UAS_data.BasicIDValid[0] = 1;
+
+        // BasicID 2
+        if (g.have_basic_id_2_info()) {
+            // from parameters
+            UAS_data.BasicID[1].UAType = (ODID_uatype_t)g.ua_type_2;
+            UAS_data.BasicID[1].IDType = (ODID_idtype_t)g.id_type_2;
+            ODID_COPY_STR(UAS_data.BasicID[1].UASID, g.uas_id_2);
+            UAS_data.BasicIDValid[1] = 1;
+        } 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
+              and it is a different uas_id from the basicID1 then use it as BasicID2
+            */
+            if (basic_id.ua_type != 0 &&
+                basic_id.id_type != 0 &&
+                strnlen((const char *)basic_id.uas_id, 20) > 0) {
+                UAS_data.BasicID[1].UAType = (ODID_uatype_t)basic_id.ua_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);
+                UAS_data.BasicIDValid[1] = 1;
+            }
+        }
     }
     }
-    UAS_data.BasicIDValid[0] = 1;
 
 
     // OperatorID
     // OperatorID
     UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
     UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;

+ 7 - 2
RemoteIDModule/mavlink.cpp

@@ -153,8 +153,13 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         break;
         break;
     }
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
-        mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
-        last_basic_id_ms = now_ms;
+        mavlink_open_drone_id_basic_id_t 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)) {
+            //only update if we receive valid data
+            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: {

+ 8 - 0
RemoteIDModule/parameters.cpp

@@ -15,6 +15,9 @@ const Parameters::Param Parameters::params[] = {
     { "UAS_TYPE",          Parameters::ParamType::UINT8,  (const void*)&g.ua_type,          0, 0, 15 },
     { "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_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 },
     { "UAS_ID",            Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0],        0, 0, 0 },
+    { "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_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,         57600, 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 },
@@ -331,6 +334,11 @@ bool Parameters::have_basic_id_info(void) const
     return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
     return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
 }
 }
 
 
+bool Parameters::have_basic_id_2_info(void) const
+{
+    return strlen(g.uas_id_2) > 0 && g.id_type_2 > 0 && g.ua_type_2 > 0;
+}
+
 bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
 bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
 {
 {
     const auto *f = find(name);
     const auto *f = find(name);

+ 4 - 0
RemoteIDModule/parameters.h

@@ -19,6 +19,9 @@ public:
     uint8_t ua_type;
     uint8_t ua_type;
     uint8_t id_type;
     uint8_t id_type;
     char uas_id[21] = "ABCD123456789";
     char uas_id[21] = "ABCD123456789";
+    uint8_t ua_type_2;
+    uint8_t id_type_2;
+    char uas_id_2[21] = "ABCD123456789";
     float wifi_nan_rate;
     float wifi_nan_rate;
     float wifi_beacon_rate;
     float wifi_beacon_rate;
     float wifi_power;
     float wifi_power;
@@ -76,6 +79,7 @@ public:
     void init(void);
     void init(void);
 
 
     bool have_basic_id_info(void) const;
     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_uint8(const char *name, uint8_t v);
     bool set_by_name_char64(const char *name, const char *s);
     bool set_by_name_char64(const char *name, const char *s);