BLE_TX.cpp 11 KB

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