BLE_TX.cpp 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266
  1. /*
  2. BLE TX driver
  3. Many thanks to Roel Schiphorst from BlueMark for his assistance with the Bluetooth code
  4. Also many thanks to chegewara for his sample code:
  5. https://github.com/Tinyu-Zhao/Arduino-Borads/blob/b584d00a81e4ac6d7b72697c674ca1bbcb8aae69/libraries/BLE/examples/BLE5_multi_advertising/BLE5_multi_advertising.ino
  6. */
  7. #include "BLE_TX.h"
  8. #include "options.h"
  9. #include <esp_system.h>
  10. #include <BLEDevice.h>
  11. #include <BLEAdvertising.h>
  12. // set max power
  13. static const int8_t tx_power = ESP_PWR_LVL_P18;
  14. //interval min/max are configured for 1 Hz update rate. Somehow dynamic setting of these fields fails
  15. //shorter intervals lead to more BLE transmissions. This would result in increased power consumption and can lead to more interference to other radio systems.
  16. static esp_ble_gap_ext_adv_params_t legacy_adv_params = {
  17. .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_LEGACY_NONCONN,
  18. .interval_min = 192, //(unsigned int) 0.75*1000/(OUTPUT_RATE_HZ*6)/0.625; //allow ble controller to have some room for transmission.
  19. .interval_max = 267, //(unsigned int) 1000/(OUTPUT_RATE_HZ*6)/0.625;
  20. .channel_map = ADV_CHNL_ALL,
  21. .own_addr_type = BLE_ADDR_TYPE_RANDOM,
  22. .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_WLST, // we want unicast non-connectable transmission
  23. .tx_power = tx_power,
  24. .primary_phy = ESP_BLE_GAP_PHY_1M,
  25. .max_skip = 0,
  26. .secondary_phy = ESP_BLE_GAP_PHY_1M,
  27. .sid = 0,
  28. .scan_req_notif = false,
  29. };
  30. static esp_ble_gap_ext_adv_params_t ext_adv_params_coded = {
  31. .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_NONCONN_NONSCANNABLE_UNDIRECTED, //set to unicast advertising
  32. .interval_min = 1200, //(unsigned int) 0.75*1000/(OUTPUT_RATE_HZ)/0.625; //allow ble controller to have some room for transmission.
  33. .interval_max = 1600, //(unsigned int) 1000/(OUTPUT_RATE_HZ)/0.625;
  34. .channel_map = ADV_CHNL_ALL,
  35. .own_addr_type = BLE_ADDR_TYPE_RANDOM,
  36. .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_WLST, // we want unicast non-connectable transmission
  37. .tx_power = tx_power,
  38. .primary_phy = ESP_BLE_GAP_PHY_CODED,
  39. .max_skip = 0,
  40. .secondary_phy = ESP_BLE_GAP_PHY_CODED,
  41. .sid = 1,
  42. .scan_req_notif = false,
  43. };
  44. static esp_ble_gap_ext_adv_params_t blename_adv_params = {
  45. .type = ESP_BLE_GAP_SET_EXT_ADV_PROP_LEGACY_NONCONN,
  46. .interval_min = 1200, //(unsigned int) 0.75*1000/(OUTPUT_RATE_HZ)/0.625; //allow ble controller to have some room for transmission.
  47. .interval_max = 1600,//(unsigned int) 1000/(OUTPUT_RATE_HZ)/0.625;;
  48. .channel_map = ADV_CHNL_ALL,
  49. .own_addr_type = BLE_ADDR_TYPE_RANDOM,
  50. .filter_policy = ADV_FILTER_ALLOW_SCAN_ANY_CON_WLST, // we want unicast non-connectable transmission
  51. .tx_power = tx_power,
  52. .primary_phy = ESP_BLE_GAP_PHY_1M,
  53. .max_skip = 0,
  54. .secondary_phy = ESP_BLE_GAP_PHY_1M,
  55. .sid = 2,
  56. .scan_req_notif = false,
  57. };
  58. static BLEMultiAdvertising advert(3);
  59. bool BLE_TX::init(void)
  60. {
  61. if (initialised) {
  62. return true;
  63. }
  64. initialised = true;
  65. BLEDevice::init("");
  66. // generate random mac address
  67. uint8_t mac_addr[6];
  68. generate_random_mac(mac_addr);
  69. // set as a bluetooth random static address
  70. mac_addr[0] |= 0xc0;
  71. advert.setAdvertisingParams(0, &legacy_adv_params);
  72. advert.setInstanceAddress(0, mac_addr);
  73. advert.setDuration(0);
  74. advert.setAdvertisingParams(1, &ext_adv_params_coded);
  75. advert.setDuration(1);
  76. advert.setInstanceAddress(1, mac_addr);
  77. advert.setAdvertisingParams(2, &blename_adv_params);
  78. advert.setDuration(2);
  79. advert.setInstanceAddress(2, mac_addr);
  80. // prefer S8 coding
  81. 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) {
  82. Serial.printf("Failed to setup S8 coding\n");
  83. }
  84. memset(&msg_counters,0, sizeof(msg_counters));
  85. return true;
  86. }
  87. #define IMIN(a,b) ((a)<(b)?(a):(b))
  88. bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data)
  89. {
  90. init();
  91. //set BLE name
  92. uint8_t legacy_name_payload[36];
  93. char legacy_name[28] {};
  94. const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
  95. const uint8_t ID_len = strlen(UAS_ID);
  96. const uint8_t ID_tail = IMIN(4, ID_len);
  97. snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
  98. memset(legacy_name_payload, 0, sizeof(legacy_name_payload));
  99. const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
  100. memcpy(legacy_name_payload, legacy_name_header, sizeof(legacy_name_header));
  101. memcpy(&legacy_name_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
  102. int legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
  103. advert.setAdvertisingData(2, legacy_length, legacy_payload);
  104. return true;
  105. }
  106. bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
  107. {
  108. init();
  109. // create a packed UAS data message
  110. uint8_t payload[250];
  111. int length = odid_message_build_pack(&UAS_data, payload, 255);
  112. if (length <= 0) {
  113. return false;
  114. }
  115. // setup ASTM header
  116. const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters[ODID_MSG_COUNTER_PACKED]++) };
  117. // combine header with payload
  118. memcpy(longrange_payload, header, sizeof(header));
  119. memcpy(&longrange_payload[sizeof(header)], payload, length);
  120. int longrange_length = sizeof(header) + length;
  121. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  122. // we start advertising when we have the first lot of data to send
  123. if (!started) {
  124. advert.start();
  125. }
  126. started = true;
  127. return true;
  128. }
  129. bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
  130. {
  131. init();
  132. static uint8_t legacy_phase = 0;
  133. int legacy_length = 0;
  134. // setup ASTM header
  135. const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; //exclude the message counter
  136. // combine header with payload
  137. memset(legacy_payload, 0, sizeof(legacy_payload));
  138. memcpy(legacy_payload, header, sizeof(header));
  139. switch (legacy_phase)
  140. {
  141. case 0:
  142. ODID_Location_encoded location_encoded;
  143. memset(&location_encoded, 0, sizeof(location_encoded));
  144. if (encodeLocationMessage(&location_encoded, &UAS_data.Location) != ODID_SUCCESS) {
  145. break;
  146. }
  147. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
  148. msg_counters[ODID_MSG_COUNTER_LOCATION]++;
  149. //msg_counters[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
  150. memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
  151. legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
  152. break;
  153. case 1:
  154. ODID_BasicID_encoded basicid_encoded;
  155. memset(&basicid_encoded, 0, sizeof(basicid_encoded));
  156. if (encodeBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  157. break;
  158. }
  159. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  160. msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
  161. //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  162. memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
  163. legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
  164. break;
  165. case 2:
  166. ODID_SelfID_encoded selfid_encoded;
  167. memset(&selfid_encoded, 0, sizeof(selfid_encoded));
  168. if (encodeSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  169. break;
  170. }
  171. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
  172. msg_counters[ODID_MSG_COUNTER_SELF_ID]++;
  173. //msg_counters[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
  174. memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
  175. legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
  176. break;
  177. case 3:
  178. ODID_System_encoded system_encoded;
  179. memset(&system_encoded, 0, sizeof(system_encoded));
  180. if (encodeSystemMessage(&system_encoded, &UAS_data.System) != ODID_SUCCESS) {
  181. break;
  182. }
  183. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
  184. msg_counters[ODID_MSG_COUNTER_SYSTEM]++;
  185. //msg_counters[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
  186. memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
  187. legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
  188. break;
  189. case 4:
  190. ODID_OperatorID_encoded operatorid_encoded;
  191. memset(&operatorid_encoded, 0, sizeof(operatorid_encoded));
  192. if (encodeOperatorIDMessage(&operatorid_encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  193. break;
  194. }
  195. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
  196. msg_counters[ODID_MSG_COUNTER_OPERATOR_ID]++;
  197. //msg_counters[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
  198. memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
  199. legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
  200. break;
  201. }
  202. legacy_phase++;
  203. legacy_phase %= 5;
  204. advert.setAdvertisingData(0, legacy_length, legacy_payload);
  205. if (!started) {
  206. advert.start();
  207. }
  208. started = true;
  209. return true;
  210. }