BLE_TX.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542
  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. // 调试抓包
  93. // generate random mac address
  94. uint8_t mac_addr[6];
  95. generate_random_mac(mac_addr);
  96. // set as a bluetooth random static address
  97. mac_addr[0] |= 0xc0;
  98. advert.setAdvertisingParams(0, &legacy_adv_params);
  99. advert.setInstanceAddress(0, mac_addr);
  100. advert.setDuration(0);
  101. advert.setAdvertisingParams(1, &ext_adv_params_coded);
  102. advert.setDuration(1);
  103. advert.setInstanceAddress(1, mac_addr);
  104. // prefer S8 coding
  105. 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) {
  106. Serial.printf("Failed to setup S8 coding\n");
  107. }
  108. memset(&msg_counters_CNDID,0, sizeof(msg_counters_CNDID));
  109. memset(&msg_counters_ODID,0, sizeof(msg_counters_ODID));
  110. return true;
  111. }
  112. #define IMIN(a,b) ((a)<(b)?(a):(b))
  113. bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
  114. {
  115. init();
  116. // create a packed UAS data message
  117. uint8_t payload[250];
  118. int length = odid_message_build_pack(&UAS_data, payload, 255);
  119. if (length <= 0) {
  120. return false;
  121. }
  122. // Serial.printf("ble4 tx power %d\n", legacy_adv_params.tx_power);
  123. // Serial.printf("ble5 tx power %d\n", ext_adv_params_coded.tx_power);
  124. // setup ASTM header
  125. const uint8_t header[] { uint8_t(length+5), 0x16, 0xfa, 0xff, 0x0d, uint8_t(msg_counters_ODID[ODID_MSG_COUNTER_PACKED]++) };
  126. // combine header with payload
  127. memcpy(longrange_payload, header, sizeof(header));
  128. memcpy(&longrange_payload[sizeof(header)], payload, length);
  129. int longrange_length = sizeof(header) + length;
  130. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  131. // we start advertising when we have the first lot of data to send
  132. // Serial.printf("started is %d\n", started);
  133. // Serial.printf("longrange is %s\n", longrange_payload);
  134. if (!started) {
  135. advert.start();
  136. }
  137. started = true;
  138. return true;
  139. }
  140. bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
  141. {
  142. init();
  143. // Serial.printf("ble4 tx power %d\n", legacy_adv_params.tx_power);
  144. // Serial.printf("ble5 tx power %d\n", ext_adv_params_coded.tx_power);
  145. static uint8_t legacy_phase = 0;
  146. int legacy_length = 0;
  147. // setup ASTM header
  148. const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; //exclude the message counter
  149. // combine header with payload
  150. memset(legacy_payload, 0, sizeof(legacy_payload));
  151. memcpy(legacy_payload, header, sizeof(header));
  152. legacy_length = sizeof(header);
  153. switch (legacy_phase)
  154. {
  155. case 0: {
  156. if (UAS_data.LocationValid) {
  157. ODID_Location_encoded location_encoded;
  158. memset(&location_encoded, 0, sizeof(location_encoded));
  159. if (encodeLocationMessage(&location_encoded, &UAS_data.Location) != ODID_SUCCESS) {
  160. break;
  161. }
  162. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_LOCATION], 1); //set packet counter
  163. msg_counters_ODID[ODID_MSG_COUNTER_LOCATION]++;
  164. //msg_counters_ODID[ODID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
  165. memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
  166. legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
  167. }
  168. break;
  169. }
  170. case 1: {
  171. if (UAS_data.BasicIDValid[0]) {
  172. ODID_BasicID_encoded basicid_encoded;
  173. memset(&basicid_encoded, 0, sizeof(basicid_encoded));
  174. if (encodeBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  175. break;
  176. }
  177. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  178. msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID]++;
  179. //msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  180. memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
  181. legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
  182. }
  183. break;
  184. }
  185. case 2: {
  186. if (UAS_data.SelfIDValid) {
  187. ODID_SelfID_encoded selfid_encoded;
  188. memset(&selfid_encoded, 0, sizeof(selfid_encoded));
  189. if (encodeSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  190. break;
  191. }
  192. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID], 1); //set packet counter
  193. msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID]++;
  194. //msg_counters_ODID[ODID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
  195. memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
  196. legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
  197. }
  198. break;
  199. }
  200. case 3: {
  201. if (UAS_data.SystemValid) {
  202. ODID_System_encoded system_encoded;
  203. memset(&system_encoded, 0, sizeof(system_encoded));
  204. if (encodeSystemMessage(&system_encoded, &UAS_data.System) != ODID_SUCCESS) {
  205. break;
  206. }
  207. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM], 1); //set packet counter
  208. msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM]++;
  209. //msg_counters_ODID[ODID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
  210. memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
  211. legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
  212. }
  213. break;
  214. }
  215. case 4: {
  216. if (UAS_data.OperatorIDValid) {
  217. ODID_OperatorID_encoded operatorid_encoded;
  218. memset(&operatorid_encoded, 0, sizeof(operatorid_encoded));
  219. if (encodeOperatorIDMessage(&operatorid_encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  220. break;
  221. }
  222. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID], 1); //set packet counter
  223. msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID]++;
  224. //msg_counters_ODID[ODID_MSG_COUNTER_OPERATOR_ID] %= 256; //likely not be needed as it is defined as uint_8
  225. memcpy(&legacy_payload[sizeof(header) + 1], &operatorid_encoded, sizeof(operatorid_encoded));
  226. legacy_length = sizeof(header) + 1 + sizeof(operatorid_encoded);
  227. }
  228. break;
  229. }
  230. case 5: //in case of dual basic ID
  231. if (UAS_data.BasicIDValid[1]) {
  232. ODID_BasicID_encoded basicid2_encoded;
  233. memset(&basicid2_encoded, 0, sizeof(basicid2_encoded));
  234. if (encodeBasicIDMessage(&basicid2_encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
  235. break;
  236. }
  237. memcpy(&legacy_payload[sizeof(header)], &msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  238. msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID]++;
  239. //msg_counters_ODID[ODID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  240. memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
  241. legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
  242. }
  243. break;
  244. case 6: {
  245. //set BLE name
  246. char legacy_name[28] {};
  247. const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
  248. const uint8_t ID_len = strlen(UAS_ID);
  249. const uint8_t ID_tail = IMIN(4, ID_len);
  250. snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
  251. memset(legacy_payload, 0, sizeof(legacy_payload));
  252. const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
  253. memcpy(legacy_payload, legacy_name_header, sizeof(legacy_name_header));
  254. memcpy(&legacy_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
  255. legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
  256. break;
  257. }
  258. }
  259. legacy_phase++;
  260. if (UAS_data.BasicIDValid[1]) {
  261. legacy_phase %= 7;
  262. } else {
  263. legacy_phase %= 6;
  264. }
  265. advert.setAdvertisingData(0, legacy_length, legacy_payload);
  266. // Serial.printf("started is %d\n", started);
  267. // Serial.printf("legacy is %s\n", legacy_payload);
  268. if (!started) {
  269. advert.start();
  270. }
  271. started = true;
  272. return true;
  273. }
  274. // bt5 蓝牙发送国标数据
  275. bool BLE_TX::transmit_cn_longrange(CNDID_UAS_Data &UAS_data)
  276. {
  277. init();
  278. // create a packed UAS data message
  279. uint8_t payload[250];
  280. int length = cndid_message_build_pack(&UAS_data, payload, 255);
  281. if (length <= 0) {
  282. return false;
  283. }
  284. // setup ASTM header American Society for Testing and Materials
  285. const uint8_t header[] { uint8_t(length+5), // 头字段1:总长度(payload长度 + 5个固定头字节)
  286. 0x16, // 头字段2:ASTM协议固定标识(Remote ID相关)
  287. 0xfa, // 头字段3:厂商/类型标识(自定义或标准值)
  288. 0xff, // 头字段4:保留/扩展位
  289. 0x0d, // 头字段5:消息类型(如打包的UAS数据类型)
  290. uint8_t(msg_counters_CNDID[CNDID_MSG_COUNTER_PACKED]++) }; // 头字段6:消息计数器(自增,防丢包/重放)
  291. // // 拼接协议头和payload到最终发送缓冲区longrange_payload
  292. memcpy(longrange_payload, header, sizeof(header)); // 先拷贝协议头
  293. memcpy(&longrange_payload[sizeof(header)], payload, length); // 再拷贝payload
  294. int longrange_length = sizeof(header) + length; // 计算最终数据包总长度
  295. // 设置BLE广播数据(参数:广播类型1,数据长度,数据缓冲区)
  296. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  297. // 首次发送时启动BLE广播(避免重复启动)
  298. // we start advertising when we have the first lot of data to send
  299. // Serial.printf("started is %d\n", started);
  300. // Serial.printf("longrange is %s\n", longrange_payload);
  301. if (!started) {
  302. advert.start();
  303. }
  304. started = true;
  305. return true;
  306. }
  307. // bt4 蓝牙发送国标数据
  308. bool BLE_TX::transmit_cn_legacy(CNDID_UAS_Data &UAS_data)
  309. {
  310. init();
  311. static uint8_t legacy_phase = 0;
  312. int legacy_length = 0;
  313. // 设置ASTM标头 这个标头可能要根据国标修改
  314. const uint8_t header[] { 0x1e, 0x16, 0xfa, 0xff, 0x0d }; // 排除消息计数器
  315. // 将头部与有效载荷结合起来
  316. memset(legacy_payload, 0, sizeof(legacy_payload));
  317. memcpy(legacy_payload, header, sizeof(header));
  318. legacy_length = sizeof(header);
  319. switch (legacy_phase)
  320. {
  321. case 0: {
  322. if (UAS_data.LocationValid) {
  323. CNDID_Location_encoded location_encoded;
  324. memset(&location_encoded, 0, sizeof(location_encoded));
  325. if (encodeCNLocationMessage(&location_encoded, &UAS_data.Location) != CNDID_SUCCESS) {
  326. break;
  327. }
  328. memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION], 1); //set packet counter
  329. msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION]++;
  330. //msg_counters_CNDID[CNDID_MSG_COUNTER_LOCATION] %= 256; //likely not be needed as it is defined as unint_8
  331. memcpy(&legacy_payload[sizeof(header) + 1], &location_encoded, sizeof(location_encoded));
  332. legacy_length = sizeof(header) + 1 + sizeof(location_encoded);
  333. }
  334. break;
  335. }
  336. case 1: {
  337. if (UAS_data.BasicIDValid[0]) {
  338. CNDID_BasicID_encoded basicid_encoded;
  339. memset(&basicid_encoded, 0, sizeof(basicid_encoded));
  340. if (encodeCNBasicIDMessage(&basicid_encoded, &UAS_data.BasicID[0]) != CNDID_SUCCESS) {
  341. break;
  342. }
  343. memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  344. msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID]++;
  345. //msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID] %= 256; //likely not be needed as it is defined as unint_8
  346. memcpy(&legacy_payload[sizeof(header) + 1], &basicid_encoded, sizeof(basicid_encoded));
  347. legacy_length = sizeof(header) + 1 + sizeof(basicid_encoded);
  348. }
  349. break;
  350. }
  351. case 2: {
  352. if (UAS_data.SelfIDValid) {
  353. CNDID_SelfID_encoded selfid_encoded;
  354. memset(&selfid_encoded, 0, sizeof(selfid_encoded));
  355. if (encodeCNSelfIDMessage(&selfid_encoded, &UAS_data.SelfID) != CNDID_SUCCESS) {
  356. break;
  357. }
  358. memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID], 1); //set packet counter
  359. msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID]++;
  360. //msg_counters_CNDID[CNDID_MSG_COUNTER_SELF_ID] %= 256; //likely not be needed as it is defined as uint_8
  361. memcpy(&legacy_payload[sizeof(header) + 1], &selfid_encoded, sizeof(selfid_encoded));
  362. legacy_length = sizeof(header) + 1 + sizeof(selfid_encoded);
  363. }
  364. break;
  365. }
  366. case 3: {
  367. if (UAS_data.SystemValid) {
  368. CNDID_System_encoded system_encoded;
  369. memset(&system_encoded, 0, sizeof(system_encoded));
  370. if (encodeCNSystemMessage(&system_encoded, &UAS_data.System) != CNDID_SUCCESS) {
  371. break;
  372. }
  373. memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM], 1); //set packet counter
  374. msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM]++;
  375. //msg_counters_CNDID[CNDID_MSG_COUNTER_SYSTEM] %= 256; //likely not be needed as it is defined as uint_8
  376. memcpy(&legacy_payload[sizeof(header) + 1], &system_encoded, sizeof(system_encoded));
  377. legacy_length = sizeof(header) + 1 + sizeof(system_encoded);
  378. }
  379. break;
  380. }
  381. case 4: //in case of dual basic ID 在存在双重基本身份标识的情况下
  382. if (UAS_data.BasicIDValid[1]) {
  383. CNDID_BasicID_encoded basicid2_encoded;
  384. memset(&basicid2_encoded, 0, sizeof(basicid2_encoded));
  385. if (encodeCNBasicIDMessage(&basicid2_encoded, &UAS_data.BasicID[1]) != CNDID_SUCCESS) {
  386. break;
  387. }
  388. memcpy(&legacy_payload[sizeof(header)], &msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID], 1); //set packet counter
  389. msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID]++;
  390. //msg_counters_CNDID[CNDID_MSG_COUNTER_BASIC_ID] %= 256; //可能不需要,因为它被定义为unint_8
  391. memcpy(&legacy_payload[sizeof(header) + 1], &basicid2_encoded, sizeof(basicid2_encoded));
  392. legacy_length = sizeof(header) + 1 + sizeof(basicid2_encoded);
  393. }
  394. break;
  395. case 5: {
  396. //set BLE name 构造BLE设备名称:CN_RemoteID_XXXX(XXXX是无人机ID后4位)
  397. char legacy_name[28] {};
  398. const char *UAS_ID = (const char *)UAS_data.BasicID[0].UASID;
  399. const uint8_t ID_len = strlen(UAS_ID);
  400. const uint8_t ID_tail = IMIN(4, ID_len);
  401. snprintf(legacy_name, sizeof(legacy_name), "ArduRemoteID_%s", &UAS_ID[ID_len-ID_tail]);
  402. // 清空缓冲区,构造BLE名称广播标头(符合BLE AD规范)
  403. memset(legacy_payload, 0, sizeof(legacy_payload));
  404. const uint8_t legacy_name_header[] { 0x02, 0x01, 0x06, uint8_t(strlen(legacy_name)+1), ESP_BLE_AD_TYPE_NAME_SHORT};
  405. // 拷贝名称标头 + 名称内容
  406. memcpy(legacy_payload, legacy_name_header, sizeof(legacy_name_header));
  407. memcpy(&legacy_payload[sizeof(legacy_name_header)], legacy_name, strlen(legacy_name) + 1);
  408. // 更新广播长度(标头+名称+结束符)
  409. legacy_length = sizeof(legacy_name_header) + strlen(legacy_name) + 1; //add extra char for \0
  410. break;
  411. }
  412. }
  413. legacy_phase++; // 每次发送后阶段自增
  414. if (UAS_data.BasicIDValid[1]) { // 根据是否有双重基础ID,控制阶段循环范围
  415. legacy_phase %= 6;
  416. } else {
  417. legacy_phase %= 5;
  418. }
  419. // 设置BLE广播数据(长度+内容)
  420. advert.setAdvertisingData(0, legacy_length, legacy_payload);
  421. // 若广播未启动则启动,标记为已启动
  422. // Serial.printf("started is %d\n", started);
  423. // Serial.printf("legacy is %s\n", legacy_payload);
  424. if (!started) {
  425. advert.start();
  426. }
  427. started = true;
  428. return true;
  429. }
  430. // 以下数据包不再准寻报文加集合报文的形式 无法再进行legacy这种分报文发送的形式
  431. bool BLE_TX::transmit_GB2025_longrange(UavIdentificationData &UAS_data)
  432. {
  433. init();
  434. // create a packed UAS data message
  435. uint8_t payload[250];
  436. int length = did_GB2025_message_build_pack(&UAS_data, payload, 255);
  437. if (length <= 0) {
  438. return false;
  439. }
  440. // setup ASTM header American Society for Testing and Materials
  441. const uint8_t header[] { uint8_t(length+5), // 头字段1:总长度(payload长度 + 5个固定头字节)
  442. 0x16, // 头字段2:ASTM协议固定标识(Remote ID相关)
  443. 0xfa, // 头字段3:厂商/类型标识(自定义或标准值)
  444. 0xff, // 头字段4:保留/扩展位
  445. 0x0d, // 头字段5:消息类型(如打包的UAS数据类型)
  446. uint8_t(msg_counters_GB2025++) }; // 头字段6:消息计数器(自增,防丢包/重放)
  447. // // 拼接协议头和payload到最终发送缓冲区longrange_payload
  448. memcpy(longrange_payload, header, sizeof(header)); // 先拷贝协议头
  449. memcpy(&longrange_payload[sizeof(header)], payload, length); // 再拷贝payload
  450. int longrange_length = sizeof(header) + length; // 计算最终数据包总长度
  451. // 设置BLE广播数据(参数:广播类型1,数据长度,数据缓冲区)
  452. advert.setAdvertisingData(1, longrange_length, longrange_payload);
  453. // 首次发送时启动BLE广播(避免重复启动)
  454. // we start advertising when we have the first lot of data to send
  455. // Serial.printf("started is %d\n", started);
  456. // Serial.printf("longrange is %s\n", longrange_payload);
  457. if (!started) {
  458. advert.start();
  459. }
  460. started = true;
  461. return true;
  462. }