WiFi_TX.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  1. /*
  2. WiFi NAN and Beacon driver
  3. with thanks to https://github.com/sxjack/uav_electronic_ids for WiFi calls
  4. */
  5. #include "WiFi_TX.h"
  6. #include <esp_wifi.h>
  7. #include <WiFi.h>
  8. #include <esp_system.h>
  9. #include "parameters.h"
  10. bool WiFi_TX::init(void)
  11. {
  12. if (initialised) {
  13. return true;
  14. }
  15. initialised = true;
  16. //use a local MAC address to avoid tracking transponders based on their MAC address
  17. uint8_t mac_addr[6];
  18. generate_random_mac(mac_addr);
  19. mac_addr[0] |= 0x02; // set MAC local bit
  20. mac_addr[0] &= 0xFE; // unset MAC multicast bit
  21. //set MAC address
  22. esp_base_mac_addr_set(mac_addr);
  23. if (g.webserver_enable == 0) {
  24. WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 0); //make it visible and allow no connection
  25. } else {
  26. WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 1); //make it visible and allow only 1 connection
  27. }
  28. if (esp_wifi_set_bandwidth(WIFI_IF_AP, WIFI_BW_HT20) != ESP_OK) {
  29. return false;
  30. }
  31. memcpy(WiFi_mac_addr,mac_addr,6); //use generated random MAC address for OpenDroneID messages
  32. esp_wifi_set_max_tx_power(dBm_to_tx_power(g.wifi_power));
  33. return true;
  34. }
  35. bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
  36. {
  37. init();
  38. uint8_t buffer[1024] {};
  39. int length;
  40. if ((length = odid_wifi_build_nan_sync_beacon_frame((char *)WiFi_mac_addr,
  41. buffer,sizeof(buffer))) > 0) {
  42. if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
  43. return false;
  44. }
  45. }
  46. if ((length = odid_wifi_build_message_pack_nan_action_frame(&UAS_data,(char *)WiFi_mac_addr,
  47. ++send_counter_nan,
  48. buffer,sizeof(buffer))) > 0) {
  49. if (esp_wifi_80211_tx(WIFI_IF_AP,buffer,length,true) != ESP_OK) {
  50. return false;
  51. }
  52. }
  53. return true;
  54. }
  55. //update the payload of the beacon frames in this function
  56. bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
  57. {
  58. init();
  59. uint8_t buffer[1024] {};
  60. int length;
  61. if ((length = odid_wifi_build_message_pack_beacon_frame(&UAS_data,(char *)WiFi_mac_addr,
  62. "UAS_ID_OPEN", strlen("UAS_ID_OPEN"), //use dummy SSID, as we only extract payload data
  63. 1000/g.wifi_beacon_rate, ++send_counter_beacon, buffer, sizeof(buffer))) > 0) {
  64. //set the RID IE element
  65. uint8_t header_offset = 58;
  66. vendor_ie_data_t IE_data;
  67. IE_data.element_id = WIFI_VENDOR_IE_ELEMENT_ID;
  68. IE_data.vendor_oui[0] = 0xFA;
  69. IE_data.vendor_oui[1] = 0x0B;
  70. IE_data.vendor_oui[2] = 0xBC;
  71. IE_data.vendor_oui_type = 0x0D;
  72. IE_data.length = length - header_offset + 4; //add 4 as of definition esp_wifi_set_vendor_ie
  73. memcpy(IE_data.payload,&buffer[header_offset],length - header_offset);
  74. // so first remove old element, add new afterwards
  75. if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
  76. return false;
  77. }
  78. if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_BEACON, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
  79. return false;
  80. }
  81. //set the payload also to probe requests, to increase update rate on mobile phones
  82. // so first remove old element, add new afterwards
  83. if (esp_wifi_set_vendor_ie(false, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
  84. return false;
  85. }
  86. if (esp_wifi_set_vendor_ie(true, WIFI_VND_IE_TYPE_PROBE_RESP, WIFI_VND_IE_ID_0, &IE_data) != ESP_OK){
  87. return false;
  88. }
  89. return true;
  90. }
  91. else {
  92. return false;
  93. }
  94. }
  95. /*
  96. map dBm to a TX power
  97. */
  98. uint8_t WiFi_TX::dBm_to_tx_power(float dBm) const
  99. {
  100. if (dBm < 2) {
  101. dBm = 2;
  102. }
  103. if (dBm > 20) {
  104. dBm = 20;
  105. }
  106. return uint8_t((dBm+1.125) * 4);
  107. }