Explorar el Código

added BT5 support

Andrew Tridgell hace 3 años
padre
commit
4d99afd745

+ 152 - 0
RemoteIDModule/BLE_TX.cpp

@@ -0,0 +1,152 @@
+/*
+  BLE TX driver
+ */
+
+#include "BLE_TX.h"
+#include <esp_system.h>
+
+#include <BLEDevice.h>
+#include <BLEAdvertising.h>
+
+static esp_ble_gap_ext_adv_params_t ext_adv_params_1M = {
+    .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_CONNECTABLE,
+    .interval_min = 0x30,
+    .interval_max = 0x30,
+    .channel_map = ADV_CHNL_ALL,
+    .own_addr_type = BLE_ADDR_TYPE_RANDOM,
+    .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_ANY,
+    .primary_phy = ESP_BLE_GAP_PHY_CODED,
+    .max_skip = 0,
+    .secondary_phy = ESP_BLE_GAP_PHY_1M,
+    .sid = 0,
+    .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,
+    .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,
+    .interval_max = 0x45,
+    .channel_map = ADV_CHNL_ALL,
+    .own_addr_type = BLE_ADDR_TYPE_RANDOM,
+    .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_ANY,
+    .primary_phy = ESP_BLE_GAP_PHY_1M,
+    .max_skip = 0,
+    .secondary_phy = ESP_BLE_GAP_PHY_1M,
+    .sid = 2,
+    .scan_req_notif = false,
+};
+
+static esp_ble_gap_ext_adv_params_t ext_adv_params_coded = {
+    .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_SCANNABLE,
+    .interval_min = 0x50,
+    .interval_max = 0x50,
+    .channel_map = ADV_CHNL_ALL,
+    .own_addr_type = BLE_ADDR_TYPE_RANDOM,
+    .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_ANY,
+    .primary_phy = ESP_BLE_GAP_PHY_1M,
+    .max_skip = 0,
+    .secondary_phy = ESP_BLE_GAP_PHY_CODED,
+    .sid = 3,
+    .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);
+
+bool BLE_TX::init(void)
+{
+    BLEDevice::init("");
+
+    // generate random mac address
+    uint8_t mac_addr[6];
+    for (uint8_t i=0; i<6; i++) {
+        mac_addr[i] = uint8_t(random(256));
+    }
+    // set as a bluetooth random static address
+    mac_addr[0] |= 0xc0;
+
+    advert.setAdvertisingParams(0, &ext_adv_params_1M);
+    advert.setInstanceAddress(0, mac_addr);
+    advert.setDuration(0);
+
+    advert.setAdvertisingParams(1, &ext_adv_params_2M);
+    advert.setInstanceAddress(1, mac_addr);
+    advert.setDuration(1);
+
+    advert.setAdvertisingParams(2, &legacy_adv_params);
+    advert.setInstanceAddress(2, mac_addr);
+    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);
+
+    return true;
+}
+
+#define MIN(a,b) ((a)<(b)?(a):(b))
+
+bool BLE_TX::transmit(ODID_UAS_Data &UAS_data)
+{
+    // create a packed UAS data message
+    int length = odid_message_build_pack(&UAS_data, payload, 255);
+
+    // setup ASTM header
+    const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counter++) };
+
+    // combine header with payload
+    memcpy(payload2, header, sizeof(header));
+    memcpy(&payload2[sizeof(header)], payload, length);
+    int length2 = sizeof(header) + length;
+
+    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 = MIN(4, ID_len);
+    snprintf(legacy_name, sizeof(legacy_name), "DroneBeacon_%s", &UAS_ID[ID_len-ID_tail]);
+
+    memset(legacy_payload, 0, sizeof(legacy_payload));
+    const uint8_t legacy_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
+
+    memcpy(legacy_payload, legacy_header, sizeof(legacy_header));
+    memcpy(&legacy_payload[sizeof(legacy_header)], legacy_name, strlen(legacy_name));
+    const uint8_t legacy_length = sizeof(legacy_header) + strlen(legacy_name);
+    
+    // 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);
+
+    // we start advertising when we have the first lot of data to send
+    if (!started) {
+        advert.start();
+    }
+    started = true;
+
+    return true;
+}

+ 20 - 0
RemoteIDModule/BLE_TX.h

@@ -0,0 +1,20 @@
+/*
+  BLE BT4/BT5 driver
+ */
+#pragma once
+
+#include <Arduino.h>
+#include <opendroneid.h>
+
+class BLE_TX {
+public:
+    bool init(void);
+    bool transmit(ODID_UAS_Data &UAS_data);
+
+private:
+    int msg_counter;
+    uint8_t payload[250];
+    uint8_t payload2[255];
+    uint8_t legacy_payload[36];
+    bool started;
+};

+ 132 - 129
RemoteIDModule/RemoteIDModule.ino

@@ -1,7 +1,5 @@
 /*
-  implement OpenDroneID MAVLink support, populating squitter for sending bluetooth RemoteID messages
-
-  based on example code from https://github.com/sxjack/uav_electronic_ids
+  implement OpenDroneID MAVLink and DroneCAN support
  */
 /*
   released under GNU GPL v3 or later
@@ -12,17 +10,17 @@
 #include <math.h>
 #include <time.h>
 #include <sys/time.h>
+#include <opendroneid.h>
 
-#include <id_open.h>
 #include "mavlink.h"
 #include "DroneCAN.h"
+#include "WiFi_TX.h"
+#include "BLE_TX.h"
 
-static ID_OpenDrone          squitter;
-static DroneCAN              dronecan;
-
+static DroneCAN dronecan;
 static MAVLinkSerial mavlink{Serial1, MAVLINK_COMM_0};
-
-static bool squitter_initialised;
+static WiFi_NAN wifi;
+static BLE_TX ble;
 
 #define OUTPUT_RATE_HZ 5
 
@@ -34,6 +32,9 @@ static bool squitter_initialised;
 #define DEBUG_BAUDRATE 57600
 #define MAVLINK_BAUDRATE 57600
 
+// OpenDroneID output data structure
+static ODID_UAS_Data UAS_data;
+
 /*
   setup serial ports
  */
@@ -50,69 +51,135 @@ void setup()
 
     mavlink.init();
     dronecan.init();
+    wifi.init();
+    ble.init();
 }
 
 #define MIN(x,y) ((x)<(y)?(x):(y))
-#define ODID_COPY_MAVSTR(to, from) strncpy(to, (const char*)from, MIN(sizeof(to), sizeof(from)))
+#define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, MIN(sizeof(to), sizeof(from)))
 
-static void init_squitter_mavlink(void)
+static void set_data_mavlink(void)
 {
-    struct UTM_parameters utm_parameters {};
-
     const auto &operator_id = mavlink.get_operator_id();
     const auto &basic_id = mavlink.get_basic_id();
     const auto &system = mavlink.get_system();
     const auto &self_id = mavlink.get_self_id();
-
-    ODID_COPY_MAVSTR(utm_parameters.UAS_operator, operator_id.operator_id);
-    ODID_COPY_MAVSTR(utm_parameters.UAV_id, basic_id.uas_id);
-    ODID_COPY_MAVSTR(utm_parameters.flight_desc, self_id.description);
-    utm_parameters.UA_type = basic_id.ua_type;
-    utm_parameters.ID_type = basic_id.id_type;
-    utm_parameters.region = 1; // ??
-    utm_parameters.EU_category = system.category_eu;
-    utm_parameters.EU_class = system.class_eu;
-    // char    UTM_id[ID_SIZE * 2] ??
-
-    squitter.init(&utm_parameters);
+    const auto &location = mavlink.get_location();
+
+    // BasicID
+    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;
+
+    // OperatorID
+    UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
+    ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
+    UAS_data.OperatorIDValid = 1;
+
+    // SelfID
+    UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
+    ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
+    UAS_data.SelfIDValid = 1;
+
+    // System
+    UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
+    UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
+    UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
+    UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
+    UAS_data.System.AreaCount = system.area_count;
+    UAS_data.System.AreaRadius = system.area_radius;
+    UAS_data.System.AreaCeiling = system.area_ceiling;
+    UAS_data.System.AreaFloor = system.area_floor;
+    UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
+    UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
+    UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
+    UAS_data.System.Timestamp = system.timestamp;
+    UAS_data.SystemValid = 1;
+
+    // Location
+    UAS_data.Location.Status = (ODID_status_t)location.status;
+    UAS_data.Location.Direction = location.direction*0.01;
+    UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
+    UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
+    UAS_data.Location.Latitude = location.latitude*1.0e-7;
+    UAS_data.Location.Longitude = location.longitude*1.0e-7;
+    UAS_data.Location.AltitudeBaro = location.altitude_barometric;
+    UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
+    UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
+    UAS_data.Location.Height = location.height;
+    UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
+    UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
+    UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
+    UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
+    UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
+    UAS_data.Location.TimeStamp = location.timestamp;
+    UAS_data.LocationValid = 1;
 }
 
-#define MIN(x,y) ((x)<(y)?(x):(y))
+#undef ODID_COPY_STR
 #define ODID_COPY_STR(to, from) memcpy(to, from.data, MIN(from.len, sizeof(to)))
 
-static void init_squitter_dronecan(void)
+static void set_data_dronecan(void)
 {
-    struct UTM_parameters utm_parameters {};
-
     const auto &operator_id = dronecan.get_operator_id();
     const auto &basic_id = dronecan.get_basic_id();
     const auto &system = dronecan.get_system();
     const auto &self_id = dronecan.get_self_id();
-
-    ODID_COPY_STR(utm_parameters.UAS_operator, operator_id.operator_id);
-    ODID_COPY_STR(utm_parameters.UAV_id, basic_id.uas_id);
-    ODID_COPY_STR(utm_parameters.flight_desc, self_id.description);
-    utm_parameters.UA_type = basic_id.ua_type;
-    utm_parameters.ID_type = basic_id.id_type;
-    utm_parameters.region = 1; // ??
-    utm_parameters.EU_category = system.category_eu;
-    utm_parameters.EU_class = system.class_eu;
-    squitter.init(&utm_parameters);
+    const auto &location = dronecan.get_location();
+
+    // BasicID
+    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;
+
+    // OperatorID
+    UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
+    ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
+    UAS_data.OperatorIDValid = 1;
+
+    // SelfID
+    UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
+    ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
+    UAS_data.SelfIDValid = 1;
+
+    // System
+    UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
+    UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
+    UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
+    UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
+    UAS_data.System.AreaCount = system.area_count;
+    UAS_data.System.AreaRadius = system.area_radius;
+    UAS_data.System.AreaCeiling = system.area_ceiling;
+    UAS_data.System.AreaFloor = system.area_floor;
+    UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
+    UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
+    UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
+    UAS_data.System.Timestamp = system.timestamp;
+    UAS_data.SystemValid = 1;
+
+    // Location
+    UAS_data.Location.Status = (ODID_status_t)location.status;
+    UAS_data.Location.Direction = location.direction*0.01;
+    UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
+    UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
+    UAS_data.Location.Latitude = location.latitude*1.0e-7;
+    UAS_data.Location.Longitude = location.longitude*1.0e-7;
+    UAS_data.Location.AltitudeBaro = location.altitude_barometric;
+    UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
+    UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
+    UAS_data.Location.Height = location.height;
+    UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
+    UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
+    UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
+    UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
+    UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
+    UAS_data.Location.TimeStamp = location.timestamp;
+    UAS_data.LocationValid = 1;
 }
 
-static void timestamp_to_utm_time(struct UTM_data &utm_data, uint32_t timestamp)
-{
-    const uint32_t jan_1_2019_s = 1546261200UL;
-    const time_t unix_s = time_t(timestamp) + jan_1_2019_s;
-    const auto *tm = gmtime(&unix_s);
-
-    utm_data.years = tm->tm_year;
-    utm_data.months = tm->tm_mon;
-    utm_data.days = tm->tm_mday;
-    utm_data.hours = tm->tm_hour;
-    utm_data.minutes = tm->tm_min;
-    utm_data.seconds = tm->tm_sec;
-}
+static uint8_t beacon_payload[256];
 
 void loop()
 {
@@ -121,20 +188,6 @@ void loop()
     mavlink.update();
     dronecan.update();
 
-    if (!squitter_initialised && mavlink.system_valid()) {
-        squitter_initialised = true;
-        init_squitter_mavlink();
-    }
-
-    if (!squitter_initialised && dronecan.system_valid()) {
-        squitter_initialised = true;
-        init_squitter_dronecan();
-    }
-
-    if (!squitter_initialised) {
-        return;
-    }
-    
     const uint32_t now_ms = millis();
 
     if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
@@ -142,73 +195,23 @@ void loop()
         return;
     }
 
-    if (!mavlink.location_valid() &&
-        !dronecan.location_valid()) {
+    const bool mavlink_ok = mavlink.location_valid() && mavlink.system_valid();
+    const bool dronecan_ok = dronecan.location_valid() && dronecan.system_valid();
+    if (!mavlink_ok && !dronecan_ok) {
         return;
     }
 
-    last_update = now_ms;
-
-    struct UTM_data utm_data {};
-    const float M_PER_SEC_TO_KNOTS = 1.94384449;
-
-    if (mavlink.location_valid()) {
-        const auto &location = mavlink.get_location();
-        //const auto &operator_id = mavlink.get_operator_id();
-        const auto &system = mavlink.get_system();
-
-        utm_data.heading     = location.direction * 0.01;
-        utm_data.latitude_d  = location.latitude * 1.0e-7;
-        utm_data.longitude_d = location.longitude * 1.0e-7;
-        utm_data.base_latitude = system.operator_latitude * 1.0e-7;
-        utm_data.base_longitude = system.operator_longitude * 1.0e-7;
-        utm_data.base_alt_m     = system.operator_altitude_geo;
-        utm_data.alt_msl_m = location.altitude_geodetic;
-        utm_data.alt_agl_m = location.height;
-        utm_data.speed_kn  = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
-        utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
-
-        const float groundspeed = location.speed_horizontal * 0.01;
-        const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
-        const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
-
-        utm_data.vel_N_cm = vel_N * 100;
-        utm_data.vel_E_cm = vel_E * 100;
-        utm_data.vel_D_cm = location.speed_vertical * -0.01;
+    if (mavlink_ok) {
+        set_data_mavlink();
+    }
+    if (dronecan_ok) {
+        set_data_dronecan();
+    }
 
-        timestamp_to_utm_time(utm_data, system.timestamp);
+    last_update = now_ms;
 
-        utm_data.satellites = 8;
-    }
+    const auto length = odid_message_build_pack(&UAS_data,beacon_payload,255);
 
-    if (dronecan.location_valid()) {
-        const auto &location = dronecan.get_location();
-        //const auto &operator_id = dronecan.get_operator_id();
-        const auto &system = dronecan.get_system();
-
-        utm_data.heading     = location.direction * 0.01;
-        utm_data.latitude_d  = location.latitude * 1.0e-7;
-        utm_data.longitude_d = location.longitude * 1.0e-7;
-        utm_data.base_latitude = system.operator_latitude * 1.0e-7;
-        utm_data.base_longitude = system.operator_longitude * 1.0e-7;
-        utm_data.base_alt_m     = system.operator_altitude_geo;
-        utm_data.alt_msl_m = location.altitude_geodetic;
-        utm_data.alt_agl_m = location.height;
-        utm_data.speed_kn  = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
-        utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
-
-        const float groundspeed = location.speed_horizontal * 0.01;
-        const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
-        const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
-
-        utm_data.vel_N_cm = vel_N * 100;
-        utm_data.vel_E_cm = vel_E * 100;
-        utm_data.vel_D_cm = location.speed_vertical * -0.01;
-
-        timestamp_to_utm_time(utm_data, system.timestamp);
-
-        utm_data.satellites = 8;
-    }
-    
-    squitter.transmit(&utm_data);
+    wifi.transmit(UAS_data);
+    ble.transmit(UAS_data);
 }

+ 20 - 25
RemoteIDModule/WiFi_TX.cpp

@@ -9,52 +9,47 @@
 #include <WiFi.h>
 #include <esp_system.h>
 
-bool WiFi_NAN::init(const char *_ssid)
+bool WiFi_NAN::init(void)
 {
-    int            i;
-    int8_t         wifi_power;
-    wifi_config_t  wifi_config;
+    wifi_config_t wifi_config {};
 
-    strncpy(ssid, _ssid, sizeof(ssid));
-    ssid[sizeof(ssid)-1] = 0;
-
-    ssid_length = strlen(ssid);
-    WiFi.softAP(ssid, NULL, wifi_channel);
+    WiFi.softAP("", NULL, wifi_channel);
 
     esp_wifi_get_config(WIFI_IF_AP, &wifi_config);
   
     wifi_config.ap.ssid_hidden = 1;
-    esp_err_t status = esp_wifi_set_config(WIFI_IF_AP, &wifi_config);
-
-    // esp_wifi_set_country();
-    status = esp_wifi_set_bandwidth(WIFI_IF_AP,WIFI_BW_HT20);
-
-    // esp_wifi_set_max_tx_power(78);
-    esp_wifi_get_max_tx_power(&wifi_power);
 
-    String address = WiFi.macAddress();
-    status = esp_read_mac(WiFi_mac_addr,ESP_MAC_WIFI_STA);
+    if (esp_wifi_set_config(WIFI_IF_AP, &wifi_config) != ESP_OK) {
+        return false;
+    }
+    if (esp_wifi_set_bandwidth(WIFI_IF_AP, WIFI_BW_HT20) != ESP_OK) {
+        return false;
+    }
+    if (esp_read_mac(WiFi_mac_addr, ESP_MAC_WIFI_STA) != ESP_OK) {
+        return false;
+    }
 
     return true;
 }
 
 bool WiFi_NAN::transmit(ODID_UAS_Data &UAS_data)
 {
-    int            length;
-    esp_err_t      wifi_status;
-    char           text[128];
-    uint8_t        buffer[1024];
+    uint8_t buffer[1024] {};
 
+    int length;
     if ((length = odid_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
                                                         buffer,sizeof(buffer))) > 0) {
-        wifi_status = esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true);
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
     }
 
-    
     if ((length = odid_wifi_build_message_pack_nan_action_frame(&UAS_data,(char *)WiFi_mac_addr,
                                                                 ++send_counter,
                                                                 buffer,sizeof(buffer))) > 0) {
-        wifi_status = esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true);
+        if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
+            return false;
+        }
     }
 
     return true;

+ 1 - 1
RemoteIDModule/WiFi_TX.h

@@ -8,7 +8,7 @@
 
 class WiFi_NAN {
 public:
-    bool init(const char *ssid);
+    bool init(void);
     bool transmit(ODID_UAS_Data &UAS_data);
 
 private: