Эх сурвалжийг харах

prevent serial error msgs corrupting mavlink

cleanup BLE advertising and mavlink debug
Andrew Tridgell 3 жил өмнө
parent
commit
59d29d08db

+ 7 - 37
RemoteIDModule/BLE_TX.cpp

@@ -31,21 +31,6 @@ static esp_ble_gap_ext_adv_params_t ext_adv_params_1M = {
     .scan_req_notif = false,
 };
 
-static esp_ble_gap_ext_adv_params_t ext_adv_params_2M = {
-    .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_SCANNABLE,
-    .interval_min = 0x40,
-    .interval_max = 0x40,
-    .channel_map = ADV_CHNL_ALL,
-    .own_addr_type = BLE_ADDR_TYPE_RANDOM,
-    .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_ANY,
-    .tx_power = tx_power,
-    .primary_phy = ESP_BLE_GAP_PHY_1M,
-    .max_skip = 0,
-    .secondary_phy = ESP_BLE_GAP_PHY_2M,
-    .sid = 1,
-    .scan_req_notif = false,
-};
-
 static esp_ble_gap_ext_adv_params_t legacy_adv_params = {
     .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_LEGACY_IND,
     .interval_min = 0x45,
@@ -76,13 +61,7 @@ static esp_ble_gap_ext_adv_params_t ext_adv_params_coded = {
     .scan_req_notif = false,
 };
 
-static esp_ble_gap_periodic_adv_params_t periodic_adv_params = {
-    .interval_min = 0x320, // 1000 ms interval
-    .interval_max = 0x640,
-    .properties = 0, // Do not include TX power
-};
-
-static BLEMultiAdvertising advert(4);
+static BLEMultiAdvertising advert(3);
 
 bool BLE_TX::init(void)
 {
@@ -100,20 +79,13 @@ bool BLE_TX::init(void)
     advert.setInstanceAddress(0, mac_addr);
     advert.setDuration(0);
 
-    advert.setAdvertisingParams(1, &ext_adv_params_2M);
+    advert.setAdvertisingParams(1, &legacy_adv_params);
     advert.setInstanceAddress(1, mac_addr);
     advert.setDuration(1);
 
-    advert.setAdvertisingParams(2, &legacy_adv_params);
-    advert.setInstanceAddress(2, mac_addr);
+    advert.setAdvertisingParams(2, &ext_adv_params_coded);
     advert.setDuration(2);
-
-    advert.setAdvertisingParams(3, &ext_adv_params_coded);
-    advert.setDuration(3);
-    advert.setInstanceAddress(3, mac_addr);
-
-    advert.setPeriodicAdvertisingParams(0, &periodic_adv_params);
-    advert.startPeriodicAdvertising(0);
+    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) {
@@ -156,11 +128,9 @@ bool BLE_TX::transmit(ODID_UAS_Data &UAS_data)
     
     // setup advertising data
     advert.setAdvertisingData(0, length2, payload2);
-    advert.setScanRspData(1, length2, payload2);
-    advert.setScanRspData(2, legacy_length, legacy_payload);
-    advert.setAdvertisingData(2, legacy_length, legacy_payload);
-    advert.setScanRspData(3, length2, payload2);
-    advert.setPeriodicAdvertisingData(0, length2, payload2);
+    advert.setScanRspData(1, legacy_length, legacy_payload);
+    advert.setAdvertisingData(1, legacy_length, legacy_payload);
+    advert.setScanRspData(2, length2, payload2);
 
     // we start advertising when we have the first lot of data to send
     if (!started) {

+ 0 - 10
RemoteIDModule/mavlink.cpp

@@ -12,8 +12,6 @@ static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS];
 
 mavlink_system_t mavlink_system = {0,MAV_COMP_ID_ODID_TXRX_1};
 
-#define dev_printf(fmt, args ...)  do {Serial.printf(fmt, ## args); } while(0)
-
 /*
   send a buffer out a MAVLink channel
  */
@@ -108,43 +106,36 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         if (mavlink_system.sysid == 0) {
             mavlink_msg_heartbeat_decode(&msg, &hb);
             if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
-                dev_printf("Got HEARTBEAT from %u/%u\n", msg.sysid, msg.compid);
                 mavlink_system.sysid = msg.sysid;
             }
         }
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
-        dev_printf("Got OPEN_DRONE_ID_LOCATION\n");
         mavlink_msg_open_drone_id_location_decode(&msg, &location);
         last_location_ms = now_ms;
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
-        dev_printf("Got OPEN_DRONE_ID_BASIC_ID\n");
         mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
         last_basic_id_ms = now_ms;
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
-        dev_printf("Got OPEN_DRONE_ID_AUTHENTICATION\n");
         mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
-        dev_printf("Got OPEN_DRONE_ID_SELF_ID\n");
         mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
         last_self_id_ms = now_ms;
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
-        dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         last_system_ms = now_ms;
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
-        dev_printf("Got OPEN_DRONE_ID_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);
         system.operator_latitude = pkt_system_update.operator_latitude;
@@ -159,7 +150,6 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
-        dev_printf("Got OPEN_DRONE_ID_OPERATOR_ID\n");
         mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
         last_operator_id_ms = now_ms;
         break;