Explorar el Código

solved feedback @friissoren

Roel Schiphorst hace 3 años
padre
commit
052e9998a4
Se han modificado 3 ficheros con 90 adiciones y 37 borrados
  1. 79 34
      RemoteIDModule/BLE_TX.cpp
  2. 2 2
      RemoteIDModule/BLE_TX.h
  3. 9 1
      RemoteIDModule/RemoteIDModule.ino

+ 79 - 34
RemoteIDModule/BLE_TX.cpp

@@ -37,7 +37,7 @@ static esp_ble_gap_ext_adv_params_t legacy_adv_params = {
 static esp_ble_gap_ext_adv_params_t ext_adv_params_coded = {
     .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_NONCONN_NONSCANNABLE_UNDIRECTED, //set to unicast advertising
      .interval_min = 1200, //(unsigned int) 0.75*1000/(OUTPUT_RATE_HZ)/0.625; //allow ble controller to have some room for transmission.
-    .interval_max = 1600, // (unsigned int) 1000/(OUTPUT_RATE_HZ)/0.625;
+    .interval_max = 1600, //(unsigned int) 1000/(OUTPUT_RATE_HZ)/0.625;
     .channel_map = ADV_CHNL_ALL,
     .own_addr_type = BLE_ADDR_TYPE_RANDOM,
     .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_WLST, // we want unicast non-connectable transmission
@@ -49,7 +49,22 @@ static esp_ble_gap_ext_adv_params_t ext_adv_params_coded = {
     .scan_req_notif = false,
 };
 
-static BLEMultiAdvertising advert(2);
+static esp_ble_gap_ext_adv_params_t blename_adv_params = {
+    .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_LEGACY_NONCONN,
+    .interval_min = 1200, //(unsigned int) 0.75*1000/(OUTPUT_RATE_HZ)/0.625; //allow ble controller to have some room for transmission.
+    .interval_max = 1600,//(unsigned int) 1000/(OUTPUT_RATE_HZ)/0.625;;
+    .channel_map = ADV_CHNL_ALL,
+    .own_addr_type = BLE_ADDR_TYPE_RANDOM,
+    .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_WLST, // we want unicast non-connectable transmission
+    .tx_power = tx_power,
+    .primary_phy = ESP_BLE_GAP_PHY_1M,
+    .max_skip = 0,
+    .secondary_phy = ESP_BLE_GAP_PHY_1M,
+    .sid = 2,
+    .scan_req_notif = false,
+};
+
+static BLEMultiAdvertising advert(3);
 
 bool BLE_TX::init(void)
 {
@@ -71,18 +86,44 @@ bool BLE_TX::init(void)
     advert.setDuration(1);
     advert.setInstanceAddress(1, mac_addr);
 
+    advert.setAdvertisingParams(2, &blename_adv_params);
+    advert.setDuration(2);
+    advert.setInstanceAddress(2, mac_addr);
+
     // prefer S8 coding
     if (esp_ble_gap_set_prefered_default_phy(ESP_BLE_GAP_PHY_OPTIONS_PREF_S8_CODING, ESP_BLE_GAP_PHY_OPTIONS_PREF_S8_CODING) != ESP_OK) {
         Serial.printf("Failed to setup S8 coding\n");
     }
 
-    legacy_msg_counter = 0;
-    longrange_msg_counter = 0;
+    memset(&msg_counters,0, sizeof(msg_counters));
     return true;
 }
 
 #define IMIN(a,b) ((a)<(b)?(a):(b))
 
+bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data)
+{
+    //set BLE name
+    uint8_t legacy_name_payload[36];
+    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]);
+
+    memset(legacy_name_payload, 0, sizeof(legacy_name_payload));
+    const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
+
+    memcpy(legacy_name_payload, legacy_name_header, sizeof(legacy_name_header));
+    memcpy(&legacy_name_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
+
+    int legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
+
+    advert.setAdvertisingData(2, legacy_length, legacy_payload);
+
+    return true;
+}
+
 bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 {
     // create a packed UAS data message
@@ -93,7 +134,7 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
     }
 
     // setup ASTM header
-    const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(longrange_msg_counter++) };
+    const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters[ODID_MSG_COUNTER_PACKED]++) };
 
     // combine header with payload
     memcpy(longrange_payload, header, sizeof(header));
@@ -116,10 +157,10 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 	static uint8_t legacy_phase = 0;
 	int legacy_length = 0;
 	// setup ASTM header
-	const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d, uint8_t(legacy_msg_counter++) };
+	const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; //exclude the message counter
 	// combine header with payload
 	memset(legacy_payload, 0, sizeof(legacy_payload));
-	memcpy(legacy_payload, header, sizeof(header));
+    memcpy(legacy_payload, header, sizeof(header));
 
 	switch (legacy_phase)
     {
@@ -130,8 +171,12 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 				break;
 			}
 
-			memcpy(&legacy_payload[sizeof(header)], &location_encoded, sizeof(location_encoded));
-			legacy_length = sizeof(header) + sizeof(location_encoded);
+            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) + 1], &location_encoded, sizeof(location_encoded));
+			legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
 
 			break;
 
@@ -142,8 +187,12 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 				break;
 			}
 
-			memcpy(&legacy_payload[sizeof(header)], &basicid_encoded, sizeof(basicid_encoded));
-			legacy_length = sizeof(header) + sizeof(basicid_encoded);
+            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], &basicid_encoded, sizeof(basicid_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
 
 			break;
 
@@ -154,8 +203,12 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 				break;
 			}
 
-			memcpy(&legacy_payload[sizeof(header)], &selfid_encoded, sizeof(selfid_encoded));
-			legacy_length = sizeof(header) + sizeof(selfid_encoded);
+            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) + 1], &selfid_encoded, sizeof(selfid_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
 
 			break;
 
@@ -166,8 +219,12 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 				break;
 			}
 
-			memcpy(&legacy_payload[sizeof(header)], &system_encoded, sizeof(system_encoded));
-			legacy_length = sizeof(header) + sizeof(system_encoded);
+            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) + 1], &system_encoded, sizeof(system_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
 
 			break;
 
@@ -178,30 +235,18 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 				break;
 			}
 
-			memcpy(&legacy_payload[sizeof(header)], &operatorid_encoded, sizeof(operatorid_encoded));
-			legacy_length = sizeof(header) + sizeof(operatorid_encoded);
-
-			break;
-
-		case  5: //broadcast BLE name
-			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]);
-
-			memset(legacy_payload, 0, sizeof(legacy_payload));
-			const uint8_t legacy_header_ble_name[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
+            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, legacy_header_ble_name, sizeof(legacy_header_ble_name));
-			memcpy(&legacy_payload[sizeof(legacy_header_ble_name)], legacy_name, strlen(legacy_name) + 1);
-			legacy_length = sizeof(legacy_header_ble_name) + strlen(legacy_name);
+			memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
+            legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
 
 			break;
 	}
 
-	legacy_phase++;
-    legacy_phase %= 6;
+    legacy_phase++;
+    legacy_phase %= 5;
 
 	advert.setAdvertisingData(0, legacy_length, legacy_payload);
 

+ 2 - 2
RemoteIDModule/BLE_TX.h

@@ -10,11 +10,11 @@ class BLE_TX {
 public:
     bool init(void);
     bool transmit_longrange(ODID_UAS_Data &UAS_data);
+    bool transmit_legacy_name(ODID_UAS_Data &UAS_data);
     bool transmit_legacy(ODID_UAS_Data &UAS_data);
 
 private:
-    uint8_t legacy_msg_counter;
-    uint8_t longrange_msg_counter;
+    uint8_t msg_counters[ODID_MSG_COUNTER_AMOUNT];
     uint8_t legacy_payload[36];
     uint8_t longrange_payload[250];
     bool started;

+ 9 - 1
RemoteIDModule/RemoteIDModule.ino

@@ -272,10 +272,18 @@ void loop()
         wifi.transmit(UAS_data);
     }
 #endif
-#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
+
+#if AP_BLE_LONGRANGE_ENABLED
     if (loop_counter == 0) { //only run on the original update rate
         ble.transmit_longrange(UAS_data);
     }
+#endif
+
+#if AP_BLE_LEGACY_ENABLED
     ble.transmit_legacy(UAS_data);
 #endif
+
+#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
+    ble.transmit_legacy_name(UAS_data);
+#endif
 }