BLE_TX.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314
  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,
  18. .interval_max = 267,
  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,
  32. .interval_max = 1600,
  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,
  46. .interval_max = 1600,
  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. // set min/max interval based on output rate
  103. legacy_adv_params.interval_max = (1000/(g.bt4_rate*5))/0.625; //need rework when PR #73 is merged. I.e. 5 = 5 or 6
  104. legacy_adv_params.interval_min = 0.75*legacy_adv_params.interval_max;
  105. ext_adv_params_coded.interval_max = (1000/(g.bt5_rate))/0.625;
  106. ext_adv_params_coded.interval_min = 0.75*ext_adv_params_coded.interval_max;
  107. blename_adv_params.interval_max = (1000/(g.bt4_rate*5))/0.625;
  108. blename_adv_params.interval_min = 0.75*blename_adv_params.interval_max;
  109. // generate random mac address
  110. uint8_t mac_addr[6];
  111. generate_random_mac(mac_addr);
  112. // set as a bluetooth random static address
  113. mac_addr[0] |= 0xc0;
  114. advert.setAdvertisingParams(0, &legacy_adv_params);
  115. advert.setInstanceAddress(0, mac_addr);
  116. advert.setDuration(0);
  117. advert.setAdvertisingParams(1, &ext_adv_params_coded);
  118. advert.setDuration(1);
  119. advert.setInstanceAddress(1, mac_addr);
  120. advert.setAdvertisingParams(2, &blename_adv_params);
  121. advert.setDuration(2);
  122. advert.setInstanceAddress(2, mac_addr);
  123. // prefer S8 coding
  124. 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) {
  125. Serial.printf("Failed to setup S8 coding\n");
  126. }
  127. memset(&msg_counters,0, sizeof(msg_counters));
  128. return true;
  129. }
  130. #define IMIN(a,b) ((a)<(b)?(a):(b))
  131. bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data)
  132. {
  133. init();
  134. //set BLE name
  135. uint8_t legacy_name_payload[36];
  136. char legacy_name[28] {};
  137. const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
  138. const uint8_t ID_len = strlen(UAS_ID);
  139. const uint8_t ID_tail = IMIN(4, ID_len);
  140. snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
  141. memset(legacy_name_payload, 0, sizeof(legacy_name_payload));
  142. const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
  143. memcpy(legacy_name_payload, legacy_name_header, sizeof(legacy_name_header));
  144. memcpy(&legacy_name_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
  145. int legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
  146. advert.setAdvertisingData(2, legacy_length, legacy_payload);
  147. return true;
  148. }
  149. bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
  150. {
  151. init();
  152. // create a packed UAS data message
  153. uint8_t payload[250];
  154. int length = odid_message_build_pack(&UAS_data, payload, 255);
  155. if (length <= 0) {
  156. return false;
  157. }
  158. // setup ASTM header
  159. const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters[ODID_MSG_COUNTER_PACKED]++) };
  160. // combine header with payload
  161. memcpy(longrange_payload, header, sizeof(header));
  162. memcpy(&longrange_payload[sizeof(header)], payload, length);
  163. int longrange_length = sizeof(header) + length;
  164. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  165. // we start advertising when we have the first lot of data to send
  166. if (!started) {
  167. advert.start();
  168. }
  169. started = true;
  170. return true;
  171. }
  172. bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
  173. {
  174. init();
  175. static uint8_t legacy_phase = 0;
  176. int legacy_length = 0;
  177. // setup ASTM header
  178. const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; //exclude the message counter
  179. // combine header with payload
  180. memset(legacy_payload, 0, sizeof(legacy_payload));
  181. memcpy(legacy_payload, header, sizeof(header));
  182. switch (legacy_phase)
  183. {
  184. case 0:
  185. ODID_Location_encoded location_encoded;
  186. memset(&location_encoded, 0, sizeof(location_encoded));
  187. if (encodeLocationMessage(&location_encoded, &UAS_data.Location) != ODID_SUCCESS) {
  188. break;
  189. }
  190. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
  191. msg_counters[ODID_MSG_COUNTER_LOCATION]++;
  192. //msg_counters[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
  193. memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
  194. legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
  195. break;
  196. case 1:
  197. ODID_BasicID_encoded basicid_encoded;
  198. memset(&basicid_encoded, 0, sizeof(basicid_encoded));
  199. if (encodeBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  200. break;
  201. }
  202. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  203. msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
  204. //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  205. memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
  206. legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
  207. break;
  208. case 2:
  209. ODID_SelfID_encoded selfid_encoded;
  210. memset(&selfid_encoded, 0, sizeof(selfid_encoded));
  211. if (encodeSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  212. break;
  213. }
  214. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
  215. msg_counters[ODID_MSG_COUNTER_SELF_ID]++;
  216. //msg_counters[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
  217. memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
  218. legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
  219. break;
  220. case 3:
  221. ODID_System_encoded system_encoded;
  222. memset(&system_encoded, 0, sizeof(system_encoded));
  223. if (encodeSystemMessage(&system_encoded, &UAS_data.System) != ODID_SUCCESS) {
  224. break;
  225. }
  226. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
  227. msg_counters[ODID_MSG_COUNTER_SYSTEM]++;
  228. //msg_counters[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
  229. memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
  230. legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
  231. break;
  232. case 4:
  233. ODID_OperatorID_encoded operatorid_encoded;
  234. memset(&operatorid_encoded, 0, sizeof(operatorid_encoded));
  235. if (encodeOperatorIDMessage(&operatorid_encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  236. break;
  237. }
  238. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
  239. msg_counters[ODID_MSG_COUNTER_OPERATOR_ID]++;
  240. //msg_counters[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
  241. memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
  242. legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
  243. break;
  244. }
  245. legacy_phase++;
  246. legacy_phase %= 5;
  247. advert.setAdvertisingData(0, legacy_length, legacy_payload);
  248. if (!started) {
  249. advert.start();
  250. }
  251. started = true;
  252. return true;
  253. }