BLE_TX.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318
  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. /*
  44. map dBm to a TX power
  45. */
  46. uint8_t BLE_TX::dBm_to_tx_power(float dBm) const
  47. {
  48. static const struct {
  49. uint8_t level;
  50. float dBm;
  51. } dBm_table[] = {
  52. { ESP_PWR_LVL_N27,-27 },
  53. { ESP_PWR_LVL_N24,-24 },
  54. { ESP_PWR_LVL_N21,-21 },
  55. { ESP_PWR_LVL_N18,-18 },
  56. { ESP_PWR_LVL_N15,-15 },
  57. { ESP_PWR_LVL_N12,-12 },
  58. { ESP_PWR_LVL_N9, -9 },
  59. { ESP_PWR_LVL_N6, -6 },
  60. { ESP_PWR_LVL_N3, -3 },
  61. { ESP_PWR_LVL_N0, 0 },
  62. { ESP_PWR_LVL_P3, 3 },
  63. { ESP_PWR_LVL_P6, 6 },
  64. { ESP_PWR_LVL_P9, 9 },
  65. { ESP_PWR_LVL_P12, 12 },
  66. { ESP_PWR_LVL_P15, 15 },
  67. { ESP_PWR_LVL_P18, 18 },
  68. };
  69. for (const auto &t : dBm_table) {
  70. if (dBm <= t.dBm) {
  71. return t.level;
  72. }
  73. }
  74. return ESP_PWR_LVL_P18;
  75. }
  76. static BLEMultiAdvertising advert(2);
  77. bool BLE_TX::init(void)
  78. {
  79. if (initialised) {
  80. return true;
  81. }
  82. initialised = true;
  83. BLEDevice::init("");
  84. // setup power levels
  85. legacy_adv_params.tx_power = dBm_to_tx_power(g.bt4_power);
  86. ext_adv_params_coded.tx_power = dBm_to_tx_power(g.bt5_power);
  87. // set min/max interval based on output rate
  88. legacy_adv_params.interval_max = (1000/(g.bt4_rate*7))/0.625;
  89. legacy_adv_params.interval_min = 0.75*legacy_adv_params.interval_max;
  90. ext_adv_params_coded.interval_max = (1000/(g.bt5_rate))/0.625;
  91. ext_adv_params_coded.interval_min = 0.75*ext_adv_params_coded.interval_max;
  92. // generate random mac address
  93. uint8_t mac_addr[6];
  94. generate_random_mac(mac_addr);
  95. // set as a bluetooth random static address
  96. mac_addr[0] |= 0xc0;
  97. advert.setAdvertisingParams(0, &legacy_adv_params);
  98. advert.setInstanceAddress(0, mac_addr);
  99. advert.setDuration(0);
  100. advert.setAdvertisingParams(1, &ext_adv_params_coded);
  101. advert.setDuration(1);
  102. advert.setInstanceAddress(1, mac_addr);
  103. // prefer S8 coding
  104. 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) {
  105. Serial.printf("Failed to setup S8 coding\n");
  106. }
  107. memset(&msg_counters,0, sizeof(msg_counters));
  108. return true;
  109. }
  110. #define IMIN(a,b) ((a)<(b)?(a):(b))
  111. bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
  112. {
  113. init();
  114. // create a packed UAS data message
  115. uint8_t payload[250];
  116. int length = odid_message_build_pack(&UAS_data, payload, 255);
  117. if (length <= 0) {
  118. return false;
  119. }
  120. // setup ASTM header
  121. const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters[ODID_MSG_COUNTER_PACKED]++) };
  122. // combine header with payload
  123. memcpy(longrange_payload, header, sizeof(header));
  124. memcpy(&longrange_payload[sizeof(header)], payload, length);
  125. int longrange_length = sizeof(header) + length;
  126. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  127. // we start advertising when we have the first lot of data to send
  128. if (!started) {
  129. advert.start();
  130. }
  131. started = true;
  132. return true;
  133. }
  134. bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
  135. {
  136. init();
  137. static uint8_t legacy_phase = 0;
  138. int legacy_length = 0;
  139. // setup ASTM header
  140. const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; //exclude the message counter
  141. // combine header with payload
  142. memset(legacy_payload, 0, sizeof(legacy_payload));
  143. memcpy(legacy_payload, header, sizeof(header));
  144. legacy_length = sizeof(header);
  145. switch (legacy_phase)
  146. {
  147. case 0: {
  148. if (UAS_data.LocationValid) {
  149. ODID_Location_encoded location_encoded;
  150. memset(&location_encoded, 0, sizeof(location_encoded));
  151. if (encodeLocationMessage(&location_encoded, &UAS_data.Location) != ODID_SUCCESS) {
  152. break;
  153. }
  154. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
  155. msg_counters[ODID_MSG_COUNTER_LOCATION]++;
  156. //msg_counters[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
  157. memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
  158. legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
  159. }
  160. break;
  161. }
  162. case 1: {
  163. if (UAS_data.BasicIDValid[0]) {
  164. ODID_BasicID_encoded basicid_encoded;
  165. memset(&basicid_encoded, 0, sizeof(basicid_encoded));
  166. if (encodeBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  167. break;
  168. }
  169. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  170. msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
  171. //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  172. memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
  173. legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
  174. }
  175. break;
  176. }
  177. case 2: {
  178. if (UAS_data.SelfIDValid) {
  179. ODID_SelfID_encoded selfid_encoded;
  180. memset(&selfid_encoded, 0, sizeof(selfid_encoded));
  181. if (encodeSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  182. break;
  183. }
  184. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
  185. msg_counters[ODID_MSG_COUNTER_SELF_ID]++;
  186. //msg_counters[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
  187. memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
  188. legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
  189. }
  190. break;
  191. }
  192. case 3: {
  193. if (UAS_data.SystemValid) {
  194. ODID_System_encoded system_encoded;
  195. memset(&system_encoded, 0, sizeof(system_encoded));
  196. if (encodeSystemMessage(&system_encoded, &UAS_data.System) != ODID_SUCCESS) {
  197. break;
  198. }
  199. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
  200. msg_counters[ODID_MSG_COUNTER_SYSTEM]++;
  201. //msg_counters[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
  202. memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
  203. legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
  204. }
  205. break;
  206. }
  207. case 4: {
  208. if (UAS_data.OperatorIDValid) {
  209. ODID_OperatorID_encoded operatorid_encoded;
  210. memset(&operatorid_encoded, 0, sizeof(operatorid_encoded));
  211. if (encodeOperatorIDMessage(&operatorid_encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  212. break;
  213. }
  214. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
  215. msg_counters[ODID_MSG_COUNTER_OPERATOR_ID]++;
  216. //msg_counters[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
  217. memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
  218. legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
  219. }
  220. break;
  221. }
  222. case 5: //in case of dual basic ID
  223. if (UAS_data.BasicIDValid[1]) {
  224. ODID_BasicID_encoded basicid2_encoded;
  225. memset(&basicid2_encoded, 0, sizeof(basicid2_encoded));
  226. if (encodeBasicIDMessage(&basicid2_encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
  227. break;
  228. }
  229. memcpy(&legacy_payload[sizeof(header)], &msg_counters[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  230. msg_counters[ODID_MSG_COUNTER_BASIC_ID]++;
  231. //msg_counters[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  232. memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
  233. legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
  234. }
  235. break;
  236. case 6: {
  237. //set BLE name
  238. char legacy_name[28] {};
  239. const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
  240. const uint8_t ID_len = strlen(UAS_ID);
  241. const uint8_t ID_tail = IMIN(4, ID_len);
  242. snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
  243. memset(legacy_payload, 0, sizeof(legacy_payload));
  244. const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
  245. memcpy(legacy_payload, legacy_name_header, sizeof(legacy_name_header));
  246. memcpy(&legacy_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
  247. legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
  248. break;
  249. }
  250. }
  251. legacy_phase++;
  252. if (UAS_data.BasicIDValid[1]) {
  253. legacy_phase %= 7;
  254. } else {
  255. legacy_phase %= 6;
  256. }
  257. advert.setAdvertisingData(0, legacy_length, legacy_payload);
  258. if (!started) {
  259. advert.start();
  260. }
  261. started = true;
  262. return true;
  263. }